2016-01-14 15:30:56 -04:00
|
|
|
#include "Sub.h"
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-04-05 17:25:03 -03:00
|
|
|
// enable_motor_output() - enable and output lowest possible value to motors
|
|
|
|
void Sub::enable_motor_output()
|
|
|
|
{
|
|
|
|
motors.output_min();
|
|
|
|
}
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// init_arm_motors - performs arming process including initialisation of barometer and gyros
|
|
|
|
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
|
2019-03-07 00:02:12 -04:00
|
|
|
bool Sub::init_arm_motors(AP_Arming::Method method)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
static bool in_arm_motors = false;
|
|
|
|
|
|
|
|
// exit immediately if already in this function
|
|
|
|
if (in_arm_motors) {
|
|
|
|
return false;
|
|
|
|
}
|
2017-03-01 00:05:51 -04:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
in_arm_motors = true;
|
|
|
|
|
2017-03-01 00:05:51 -04:00
|
|
|
if (!arming.pre_arm_checks(true)) {
|
2015-12-30 18:57:56 -04:00
|
|
|
AP_Notify::events.arming_failed = true;
|
|
|
|
in_arm_motors = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2019-02-11 04:11:57 -04:00
|
|
|
// let logger know that we're armed (it may open logs e.g.)
|
2019-01-18 00:24:08 -04:00
|
|
|
AP::logger().set_vehicle_armed(true);
|
2017-04-14 01:13:31 -03:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// disable cpu failsafe because initialising everything takes a while
|
2017-04-06 18:58:26 -03:00
|
|
|
mainloop_failsafe_disable();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// notify that arming will occur (we do this early to give plenty of warning)
|
|
|
|
AP_Notify::flags.armed = true;
|
2018-02-12 05:38:06 -04:00
|
|
|
// call notify update a few times to ensure the message gets out
|
2015-12-30 18:57:56 -04:00
|
|
|
for (uint8_t i=0; i<=10; i++) {
|
2018-02-12 05:38:06 -04:00
|
|
|
notify.update();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2017-04-05 19:14:40 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2017-07-08 22:51:41 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Arming motors");
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
initial_armed_bearing = ahrs.yaw_sensor;
|
|
|
|
|
2018-03-15 23:12:42 -03:00
|
|
|
if (!ahrs.home_is_set()) {
|
2015-12-30 18:57:56 -04:00
|
|
|
// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
|
2017-02-03 17:33:27 -04:00
|
|
|
|
2016-02-26 22:01:10 -04:00
|
|
|
// Always use absolute altitude for ROV
|
2017-02-03 17:33:27 -04:00
|
|
|
// ahrs.resetHeightDatum();
|
|
|
|
// Log_Write_Event(DATA_EKF_ALT_RESET);
|
2018-05-18 00:00:01 -03:00
|
|
|
} else if (ahrs.home_is_set() && !ahrs.home_is_locked()) {
|
2015-12-30 18:57:56 -04:00
|
|
|
// Reset home position if it has already been set before (but not locked)
|
2018-05-29 21:47:13 -03:00
|
|
|
if (!set_home_to_current_location(false)) {
|
|
|
|
// ignore this failure
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
2017-04-07 00:21:37 -03:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// enable gps velocity based centrefugal force compensation
|
|
|
|
ahrs.set_correct_centrifugal(true);
|
|
|
|
hal.util->set_soft_armed(true);
|
|
|
|
|
|
|
|
// enable output to motors
|
|
|
|
enable_motor_output();
|
|
|
|
|
|
|
|
// finally actually arm the motors
|
|
|
|
motors.armed(true);
|
|
|
|
|
|
|
|
Log_Write_Event(DATA_ARMED);
|
|
|
|
|
|
|
|
// log flight mode in case it was changed while vehicle was disarmed
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_Mode(control_mode, control_mode_reason);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// reenable failsafe
|
2017-04-06 18:58:26 -03:00
|
|
|
mainloop_failsafe_enable();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// perf monitor ignores delay due to arming
|
2017-11-13 04:04:31 -04:00
|
|
|
scheduler.perf_info.ignore_this_loop();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// flag exiting this function
|
|
|
|
in_arm_motors = false;
|
|
|
|
|
|
|
|
// return success
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// init_disarm_motors - disarm motors
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::init_disarm_motors()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// return immediately if we are already disarmed
|
|
|
|
if (!motors.armed()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-04-05 19:14:40 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2017-07-08 22:51:41 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Disarming motors");
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
2016-05-03 01:45:37 -03:00
|
|
|
// save compass offsets learned by the EKF if enabled
|
|
|
|
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {
|
2017-02-03 17:33:27 -04:00
|
|
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
2016-04-21 20:06:15 -03:00
|
|
|
Vector3f magOffsets;
|
|
|
|
if (ahrs.getMagOffsets(i, magOffsets)) {
|
|
|
|
compass.set_and_save_offsets(i, magOffsets);
|
|
|
|
}
|
|
|
|
}
|
2017-02-03 17:33:27 -04:00
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
Log_Write_Event(DATA_DISARMED);
|
|
|
|
|
|
|
|
// send disarm command to motors
|
|
|
|
motors.armed(false);
|
|
|
|
|
|
|
|
// reset the mission
|
|
|
|
mission.reset();
|
|
|
|
|
2019-01-18 00:24:08 -04:00
|
|
|
AP::logger().set_vehicle_armed(false);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// disable gps velocity based centrefugal force compensation
|
|
|
|
ahrs.set_correct_centrifugal(false);
|
|
|
|
hal.util->set_soft_armed(false);
|
2017-09-18 15:42:53 -03:00
|
|
|
|
|
|
|
// clear input holds
|
|
|
|
clear_input_hold();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// motors_output - send output to motors library which will adjust and send to ESCs and servos
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::motors_output()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// check if we are performing the motor test
|
|
|
|
if (ap.motor_test) {
|
2018-04-19 16:12:42 -03:00
|
|
|
verify_motor_test();
|
|
|
|
} else {
|
|
|
|
motors.set_interlock(true);
|
|
|
|
motors.output();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-04-19 16:12:42 -03:00
|
|
|
// Initialize new style motor test
|
|
|
|
// Perform checks to see if it is ok to begin the motor test
|
|
|
|
// Returns true if motor test has begun
|
|
|
|
bool Sub::init_motor_test()
|
|
|
|
{
|
|
|
|
uint32_t tnow = AP_HAL::millis();
|
|
|
|
|
|
|
|
// Ten second cooldown period required with no do_set_motor requests required
|
|
|
|
// after failure.
|
|
|
|
if (tnow < last_do_motor_test_fail_ms + 10000 && last_do_motor_test_fail_ms > 0) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "10 second cool down required");
|
2019-03-19 23:29:21 -03:00
|
|
|
return false;
|
2018-04-19 16:12:42 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// check if safety switch has been pushed
|
|
|
|
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL,"Disarm hardware safety switch before testing motors.");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// Make sure we are on the ground
|
|
|
|
if (!motors.armed()) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Arm motors before testing motors.");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
enable_motor_output(); // set all motor outputs to zero
|
|
|
|
ap.motor_test = true;
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// Verify new style motor test
|
|
|
|
// The motor test will fail if the interval between received
|
|
|
|
// MAV_CMD_DO_SET_MOTOR requests exceeds a timeout period
|
|
|
|
// Returns true if it is ok to proceed with new style motor test
|
|
|
|
bool Sub::verify_motor_test()
|
|
|
|
{
|
|
|
|
bool pass = true;
|
|
|
|
|
|
|
|
// Require at least 2 Hz incoming do_set_motor requests
|
|
|
|
if (AP_HAL::millis() > last_do_motor_test_ms + 500) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Motor test timed out!");
|
|
|
|
pass = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!pass) {
|
|
|
|
ap.motor_test = false;
|
|
|
|
motors.armed(false); // disarm motors
|
|
|
|
last_do_motor_test_fail_ms = AP_HAL::millis();
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Sub::handle_do_motor_test(mavlink_command_long_t command) {
|
|
|
|
last_do_motor_test_ms = AP_HAL::millis();
|
|
|
|
|
|
|
|
// If we are not already testing motors, initialize test
|
|
|
|
if(!ap.motor_test) {
|
|
|
|
if (!init_motor_test()) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "motor test initialization failed!");
|
|
|
|
return false; // init fail
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
float motor_number = command.param1;
|
|
|
|
float throttle_type = command.param2;
|
|
|
|
float throttle = command.param3;
|
|
|
|
// float timeout_s = command.param4; // not used
|
|
|
|
// float motor_count = command.param5; // not used
|
|
|
|
float test_type = command.param6;
|
|
|
|
|
|
|
|
if (!is_equal(test_type, (float)MOTOR_TEST_ORDER_BOARD)) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "bad test type %0.2f", (double)test_type);
|
|
|
|
return false; // test type not supported here
|
|
|
|
}
|
|
|
|
|
|
|
|
if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PILOT)) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "bad throttle type %0.2f", (double)throttle_type);
|
|
|
|
|
|
|
|
return false; // throttle type not supported here
|
|
|
|
}
|
|
|
|
|
|
|
|
if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PWM)) {
|
|
|
|
return motors.output_test_num(motor_number, throttle); // true if motor output is set
|
|
|
|
}
|
|
|
|
|
|
|
|
if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PERCENT)) {
|
|
|
|
throttle = constrain_float(throttle, 0.0f, 100.0f);
|
|
|
|
throttle = channel_throttle->get_radio_min() + throttle / 100.0f * (channel_throttle->get_radio_max() - channel_throttle->get_radio_min());
|
|
|
|
return motors.output_test_num(motor_number, throttle); // true if motor output is set
|
|
|
|
}
|
|
|
|
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-10-11 00:10:56 -03:00
|
|
|
// translate wpnav roll/pitch outputs to lateral/forward
|
2017-02-03 17:33:27 -04:00
|
|
|
void Sub::translate_wpnav_rp(float &lateral_out, float &forward_out)
|
|
|
|
{
|
|
|
|
// get roll and pitch targets in centidegrees
|
|
|
|
int32_t lateral = wp_nav.get_roll();
|
|
|
|
int32_t forward = -wp_nav.get_pitch(); // output is reversed
|
|
|
|
|
|
|
|
// constrain target forward/lateral values
|
|
|
|
// The outputs of wp_nav.get_roll and get_pitch should already be constrained to these values
|
|
|
|
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
|
|
|
|
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
|
|
|
|
|
|
|
|
// Normalize
|
|
|
|
lateral_out = (float)lateral/(float)aparm.angle_max;
|
|
|
|
forward_out = (float)forward/(float)aparm.angle_max;
|
2016-10-11 00:10:56 -03:00
|
|
|
}
|
2017-03-04 15:41:26 -04:00
|
|
|
|
|
|
|
// translate wpnav roll/pitch outputs to lateral/forward
|
|
|
|
void Sub::translate_circle_nav_rp(float &lateral_out, float &forward_out)
|
|
|
|
{
|
|
|
|
// get roll and pitch targets in centidegrees
|
|
|
|
int32_t lateral = circle_nav.get_roll();
|
|
|
|
int32_t forward = -circle_nav.get_pitch(); // output is reversed
|
|
|
|
|
|
|
|
// constrain target forward/lateral values
|
2017-03-06 22:29:03 -04:00
|
|
|
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
|
|
|
|
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
|
|
|
|
|
|
|
|
// Normalize
|
|
|
|
lateral_out = (float)lateral/(float)aparm.angle_max;
|
|
|
|
forward_out = (float)forward/(float)aparm.angle_max;
|
|
|
|
}
|
|
|
|
|
|
|
|
// translate pos_control roll/pitch outputs to lateral/forward
|
|
|
|
void Sub::translate_pos_control_rp(float &lateral_out, float &forward_out)
|
|
|
|
{
|
|
|
|
// get roll and pitch targets in centidegrees
|
|
|
|
int32_t lateral = pos_control.get_roll();
|
|
|
|
int32_t forward = -pos_control.get_pitch(); // output is reversed
|
|
|
|
|
|
|
|
// constrain target forward/lateral values
|
2017-03-04 15:41:26 -04:00
|
|
|
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
|
|
|
|
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
|
|
|
|
|
|
|
|
// Normalize
|
|
|
|
lateral_out = (float)lateral/(float)aparm.angle_max;
|
|
|
|
forward_out = (float)forward/(float)aparm.angle_max;
|
|
|
|
}
|