ardupilot/ArduPlane/system.cpp

770 lines
21 KiB
C++
Raw Normal View History

2015-05-13 03:09:36 -03:00
#include "Plane.h"
/*****************************************************************************
2012-08-21 23:19:51 -03:00
* The init_ardupilot function processes everything we need for an in - air restart
* We will determine later if we are actually on the ground and process a
* ground start in that case.
*
*****************************************************************************/
2015-05-13 03:09:36 -03:00
static void mavlink_delay_cb_static()
{
plane.mavlink_delay_cb();
}
static void failsafe_check_static()
{
plane.failsafe_check();
}
void Plane::init_ardupilot()
{
// initialise serial port
serial_manager.init_console();
hal.console->printf("\n\nInit %s"
2017-08-11 01:31:18 -03:00
"\n\nFree RAM: %u\n",
2018-06-13 08:12:16 -03:00
AP::fwversion().fw_string,
2017-08-11 01:31:18 -03:00
(unsigned)hal.util->available_memory());
//
2012-12-04 18:22:21 -04:00
// Check the EEPROM format version before loading any parameters from EEPROM
2012-08-21 23:19:51 -03:00
//
2012-02-12 04:20:56 -04:00
load_parameters();
2018-02-28 08:22:16 -04:00
#if STATS_ENABLED == ENABLED
// initialise stats module
g2.stats.init();
2018-02-28 08:22:16 -04:00
#endif
#if HIL_SUPPORT
if (g.hil_mode == 1) {
// set sensors to HIL mode
ins.set_hil_mode();
compass.set_hil_mode();
barometer.set_hil_mode();
}
#endif
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
set_control_channels();
#if HAVE_PX4_MIXER
if (!quadplane.enable) {
// this must be before BoardConfig.init() so if
// BRD_SAFETYENABLE==0 then we don't have safety off yet. For
// quadplanes we wait till AP_Motors is initialised
for (uint8_t tries=0; tries<10; tries++) {
if (setup_failsafe_mixing()) {
break;
}
hal.scheduler->delay(10);
}
}
#endif
2016-05-30 22:35:35 -03:00
gcs().set_dataflash(&DataFlash);
2014-01-19 21:58:49 -04:00
mavlink_system.sysid = g.sysid_this_mav;
// initialise serial ports
serial_manager.init();
2016-08-25 04:48:27 -03:00
gcs().chan(0).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
2017-02-14 08:07:54 -04:00
// Register mavlink_delay_cb, which will run anytime you have
// more than 5ms remaining in your call to hal.scheduler->delay
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
// setup any board specific drivers
BoardConfig.init();
#if HAL_WITH_UAVCAN
BoardConfig_CAN.init();
#endif
relay.init();
// initialise notify system
notify.init(false);
notify_flight_mode(control_mode);
init_rc_out_main();
2014-01-20 00:36:31 -04:00
// allow servo set on all channels except first 4
ServoRelayEvents.set_channel_mask(0xFFF0);
// keep a record of how many resets have happened. This can be
// used to detect in-flight resets
g.num_resets.set_and_save(g.num_resets+1);
2017-08-11 01:31:18 -03:00
// init baro
barometer.init();
// initialise rangefinder
rangefinder.init();
// initialise battery monitoring
battery.init();
rpm_sensor.init();
2016-05-16 00:33:43 -03:00
// setup telem slots with serial ports
2016-08-25 04:48:27 -03:00
gcs().setup_uarts(serial_manager);
// setup frsky
#if FRSKY_TELEM_ENABLED == ENABLED
// setup frsky, and pass a number of parameters to the library
2018-06-13 08:12:16 -03:00
frsky_telemetry.init(serial_manager, MAV_TYPE_FIXED_WING);
#endif
#if DEVO_TELEM_ENABLED == ENABLED
devo_telemetry.init(serial_manager);
#endif
2018-06-23 04:11:05 -03:00
#if OSD_ENABLED == ENABLED
osd.init();
2018-06-23 04:11:05 -03:00
#endif
2011-12-21 08:29:22 -04:00
#if LOGGING_ENABLED == ENABLED
2015-05-13 03:09:36 -03:00
log_init();
2011-12-21 08:29:22 -04:00
#endif
// initialise airspeed sensor
airspeed.init();
2012-08-21 23:19:51 -03:00
if (g.compass_enabled==true) {
2015-08-23 09:21:51 -03:00
bool compass_ok = compass.init() && compass.read();
#if HIL_SUPPORT
if (g.hil_mode != 0) {
2015-08-23 09:21:51 -03:00
compass_ok = true;
}
2015-08-23 09:21:51 -03:00
#endif
if (!compass_ok) {
2017-08-11 01:31:18 -03:00
hal.console->printf("Compass initialisation failed!\n");
g.compass_enabled = false;
} else {
ahrs.set_compass(&compass);
}
2012-08-21 23:19:51 -03:00
}
2015-01-02 20:09:02 -04:00
#if OPTFLOW == ENABLED
2015-01-02 20:09:02 -04:00
// make optflow available to libraries
if (optflow.enabled()) {
ahrs.set_optflow(&optflow);
}
#endif
2012-08-10 19:57:44 -03:00
// give AHRS the airspeed sensor
ahrs.set_airspeed(&airspeed);
// GPS Initialization
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
2013-12-21 07:27:15 -04:00
2012-08-21 23:19:51 -03:00
init_rc_in(); // sets up rc channels from radio
#if MOUNT == ENABLED
// initialise camera mount
camera_mount.init(serial_manager);
#endif
#if FENCE_TRIGGERED_PIN > 0
2014-06-01 20:28:27 -03:00
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
hal.gpio->write(FENCE_TRIGGERED_PIN, 0);
#endif
/*
2012-08-21 23:19:51 -03:00
* setup the 'main loop is dead' check. Note that this relies on
* the RC library being initialised.
*/
2015-05-13 03:09:36 -03:00
hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);
2015-07-31 19:39:36 -03:00
init_capabilities();
quadplane.setup();
AP_Param::reload_defaults_file(true);
2017-01-09 05:52:49 -04:00
startup_ground();
// don't initialise aux rc output until after quadplane is setup as
// that can change initial values of channels
init_rc_out_aux();
// choose the nav controller
set_nav_controller();
2016-08-13 04:54:37 -03:00
set_mode((FlightMode)g.initial_mode.get(), MODE_REASON_UNKNOWN);
2012-08-21 23:19:51 -03:00
// set the correct flight mode
// ---------------------------
reset_control_switch();
// initialise sensor
#if OPTFLOW == ENABLED
if (optflow.enabled()) {
optflow.init();
}
#endif
2018-02-22 05:13:38 -04:00
// init cargo gripper
#if GRIPPER_ENABLED == ENABLED
g2.gripper.init();
#endif
// disable safety if requested
BoardConfig.init_safety();
}
//********************************************************************************
//This function does all the calibrations, etc. that we need during a ground start
//********************************************************************************
2015-05-13 03:09:36 -03:00
void Plane::startup_ground(void)
{
2016-08-13 04:54:37 -03:00
set_mode(INITIALISING, MODE_REASON_UNKNOWN);
2012-08-21 23:19:51 -03:00
#if (GROUND_START_DELAY > 0)
gcs().send_text(MAV_SEVERITY_NOTICE,"Ground start with delay");
2012-08-21 23:19:51 -03:00
delay(GROUND_START_DELAY * 1000);
#else
gcs().send_text(MAV_SEVERITY_INFO,"Ground start");
2012-08-21 23:19:51 -03:00
#endif
//INS ground start
2012-08-21 23:19:51 -03:00
//------------------------
//
2015-03-10 20:16:59 -03:00
startup_INS_ground();
2012-08-21 23:19:51 -03:00
// Save the settings for in-air restart
// ------------------------------------
//save_EEPROM_groundstart();
// initialise mission library
mission.init();
// initialise DataFlash library
#if LOGGING_ENABLED == ENABLED
DataFlash.set_mission(&mission);
DataFlash.setVehicle_Startup_Log_Writer(
FUNCTOR_BIND(&plane, &Plane::Log_Write_Vehicle_Startup_Messages, void)
);
#endif
// reset last heartbeat time, so we don't trigger failsafe on slow
// startup
failsafe.last_heartbeat_ms = millis();
// we don't want writes to the serial port to cause us to pause
// mid-flight, so set the serial ports non-blocking once we are
// ready to fly
serial_manager.set_blocking_writes_all(false);
gcs().send_text(MAV_SEVERITY_INFO,"Ground start complete");
}
2015-05-13 03:09:36 -03:00
enum FlightMode Plane::get_previous_mode() {
return previous_mode;
}
2016-08-13 04:54:37 -03:00
void Plane::set_mode(enum FlightMode mode, mode_reason_t reason)
{
2012-08-21 23:19:51 -03:00
if(control_mode == mode) {
// don't switch modes if we are already in the correct mode.
return;
}
if(g.auto_trim > 0 && control_mode == MANUAL) {
trim_radio();
}
2012-08-21 23:19:51 -03:00
// perform any cleanup required for prev flight mode
exit_mode(control_mode);
// cancel inverted flight
auto_state.inverted_flight = false;
// don't cross-track when starting a mission
auto_state.next_wp_crosstrack = false;
// reset landing check
auto_state.checked_for_autoland = false;
// zero locked course
steer_state.locked_course_err = 0;
// reset crash detection
crash_state.is_crashed = false;
crash_state.impact_detected = false;
// reset external attitude guidance
guided_state.last_forced_rpy_ms.zero();
guided_state.last_forced_throttle_ms = 0;
// set mode
previous_mode = control_mode;
2012-08-21 23:19:51 -03:00
control_mode = mode;
2016-08-13 04:54:37 -03:00
previous_mode_reason = control_mode_reason;
control_mode_reason = reason;
2012-08-21 23:19:51 -03:00
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.update_control_mode(control_mode);
#endif
#if DEVO_TELEM_ENABLED == ENABLED
devo_telemetry.update_control_mode(control_mode);
#endif
#if CAMERA == ENABLED
camera.set_is_auto_mode(control_mode == AUTO);
#endif
if (previous_mode == AUTOTUNE && control_mode != AUTOTUNE) {
// restore last gains
autotune_restore();
}
// zero initial pitch and highest airspeed on mode change
auto_state.highest_airspeed = 0;
auto_state.initial_pitch_cd = ahrs.pitch_sensor;
// disable taildrag takeoff on mode change
auto_state.fbwa_tdrag_takeoff_mode = false;
// start with previous WP at current location
prev_WP_loc = current_loc;
// new mode means new loiter
loiter.start_time_ms = 0;
// record time of mode change
last_mode_change_ms = AP_HAL::millis();
// assume non-VTOL mode
auto_state.vtol_mode = false;
auto_state.vtol_loiter = false;
2012-08-21 23:19:51 -03:00
switch(control_mode)
{
case INITIALISING:
throttle_allows_nudging = true;
auto_throttle_mode = true;
auto_navigation_mode = false;
break;
2012-08-21 23:19:51 -03:00
case MANUAL:
case STABILIZE:
case TRAINING:
2012-08-21 23:19:51 -03:00
case FLY_BY_WIRE_A:
throttle_allows_nudging = false;
auto_throttle_mode = false;
auto_navigation_mode = false;
break;
case AUTOTUNE:
throttle_allows_nudging = false;
auto_throttle_mode = false;
auto_navigation_mode = false;
autotune_start();
break;
case ACRO:
throttle_allows_nudging = false;
auto_throttle_mode = false;
auto_navigation_mode = false;
acro_state.locked_roll = false;
acro_state.locked_pitch = false;
break;
case CRUISE:
throttle_allows_nudging = false;
auto_throttle_mode = true;
auto_navigation_mode = false;
cruise_state.locked_heading = false;
cruise_state.lock_timer_ms = 0;
// for ArduSoar soaring_controller
g2.soaring_controller.init_cruising();
set_target_altitude_current();
break;
2012-08-21 23:19:51 -03:00
case FLY_BY_WIRE_B:
throttle_allows_nudging = false;
auto_throttle_mode = true;
auto_navigation_mode = false;
// for ArduSoar soaring_controller
g2.soaring_controller.init_cruising();
set_target_altitude_current();
2012-08-21 23:19:51 -03:00
break;
case CIRCLE:
// the altitude to circle at is taken from the current altitude
throttle_allows_nudging = false;
auto_throttle_mode = true;
auto_navigation_mode = true;
next_WP_loc.alt = current_loc.alt;
break;
2012-08-21 23:19:51 -03:00
case AUTO:
throttle_allows_nudging = true;
auto_throttle_mode = true;
auto_navigation_mode = true;
if (quadplane.available() && quadplane.enable == 2) {
auto_state.vtol_mode = true;
} else {
auto_state.vtol_mode = false;
}
next_WP_loc = prev_WP_loc = current_loc;
// start or resume the mission, based on MIS_AUTORESET
mission.start_or_resume();
g2.soaring_controller.init_cruising();
2012-08-21 23:19:51 -03:00
break;
case RTL:
throttle_allows_nudging = true;
auto_throttle_mode = true;
auto_navigation_mode = true;
prev_WP_loc = current_loc;
do_RTL(get_RTL_altitude());
2012-08-21 23:19:51 -03:00
break;
case LOITER:
throttle_allows_nudging = true;
auto_throttle_mode = true;
auto_navigation_mode = true;
2012-08-21 23:19:51 -03:00
do_loiter_at_location();
if (g2.soaring_controller.is_active() &&
g2.soaring_controller.suppress_throttle()) {
g2.soaring_controller.init_thermalling();
g2.soaring_controller.get_target(next_WP_loc); // ahead on flight path
}
2012-08-21 23:19:51 -03:00
break;
case AVOID_ADSB:
2012-08-21 23:19:51 -03:00
case GUIDED:
throttle_allows_nudging = true;
auto_throttle_mode = true;
auto_navigation_mode = true;
guided_throttle_passthru = false;
/*
when entering guided mode we set the target as the current
location. This matches the behaviour of the copter code
*/
guided_WP_loc = current_loc;
2012-08-21 23:19:51 -03:00
set_guided_WP();
break;
case QSTABILIZE:
case QHOVER:
case QLOITER:
case QLAND:
case QRTL:
throttle_allows_nudging = true;
auto_navigation_mode = false;
if (!quadplane.init_mode()) {
control_mode = previous_mode;
} else {
auto_throttle_mode = false;
auto_state.vtol_mode = true;
}
break;
2012-08-21 23:19:51 -03:00
}
// start with throttle suppressed in auto_throttle modes
throttle_suppressed = auto_throttle_mode;
2016-07-10 21:23:08 -03:00
adsb.set_is_auto_mode(auto_navigation_mode);
DataFlash.Log_Write_Mode(control_mode, control_mode_reason);
// update notify with flight mode change
notify_flight_mode(control_mode);
// reset steering integrator on mode change
steerController.reset_I();
}
// exit_mode - perform any cleanup required when leaving a flight mode
2015-05-13 03:09:36 -03:00
void Plane::exit_mode(enum FlightMode mode)
{
// stop mission when we leave auto
if (mode == AUTO) {
if (mission.state() == AP_Mission::MISSION_RUNNING) {
mission.stop();
if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND &&
!quadplane.is_vtol_land(mission.get_current_nav_cmd().id))
{
landing.restart_landing_sequence();
}
}
auto_state.started_flying_in_auto_ms = 0;
}
}
2015-05-13 03:09:36 -03:00
void Plane::check_long_failsafe()
{
uint32_t tnow = millis();
2012-08-21 23:19:51 -03:00
// only act on changes
// -------------------
if (failsafe.state != FAILSAFE_LONG && failsafe.state != FAILSAFE_GCS && flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
uint32_t radio_timeout_ms = failsafe.last_valid_rc_ms;
if (failsafe.state == FAILSAFE_SHORT) {
// time is relative to when short failsafe enabled
radio_timeout_ms = failsafe.short_timer_ms;
}
if (failsafe.rc_failsafe &&
(tnow - radio_timeout_ms) > g.fs_timeout_long*1000) {
2016-08-13 04:54:37 -03:00
failsafe_long_on_event(FAILSAFE_LONG, MODE_REASON_RADIO_FAILSAFE);
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_AUTO && control_mode == AUTO &&
failsafe.last_heartbeat_ms != 0 &&
(tnow - failsafe.last_heartbeat_ms) > g.fs_timeout_long*1000) {
2016-08-13 04:54:37 -03:00
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HEARTBEAT &&
failsafe.last_heartbeat_ms != 0 &&
(tnow - failsafe.last_heartbeat_ms) > g.fs_timeout_long*1000) {
2016-08-13 04:54:37 -03:00
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI &&
2016-08-25 04:48:27 -03:00
gcs().chan(0).last_radio_status_remrssi_ms != 0 &&
(tnow - gcs().chan(0).last_radio_status_remrssi_ms) > g.fs_timeout_long*1000) {
2016-08-13 04:54:37 -03:00
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
2012-08-21 23:19:51 -03:00
}
} else {
uint32_t timeout_seconds = g.fs_timeout_long;
if (g.fs_action_short != FS_ACTION_SHORT_DISABLED) {
// avoid dropping back into short timeout
timeout_seconds = g.fs_timeout_short;
}
2012-08-21 23:19:51 -03:00
// We do not change state but allow for user to change mode
if (failsafe.state == FAILSAFE_GCS &&
(tnow - failsafe.last_heartbeat_ms) < timeout_seconds*1000) {
2017-09-22 00:31:44 -03:00
failsafe_long_off_event(MODE_REASON_GCS_FAILSAFE);
} else if (failsafe.state == FAILSAFE_LONG &&
!failsafe.rc_failsafe) {
2017-09-22 00:31:44 -03:00
failsafe_long_off_event(MODE_REASON_RADIO_FAILSAFE);
}
2012-08-21 23:19:51 -03:00
}
}
2015-05-13 03:09:36 -03:00
void Plane::check_short_failsafe()
{
2012-08-21 23:19:51 -03:00
// only act on changes
// -------------------
if (g.fs_action_short != FS_ACTION_SHORT_DISABLED &&
failsafe.state == FAILSAFE_NONE &&
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
// The condition is checked and the flag rc_failsafe is set in radio.cpp
if(failsafe.rc_failsafe) {
2016-08-13 04:54:37 -03:00
failsafe_short_on_event(FAILSAFE_SHORT, MODE_REASON_RADIO_FAILSAFE);
2012-08-21 23:19:51 -03:00
}
}
if(failsafe.state == FAILSAFE_SHORT) {
if(!failsafe.rc_failsafe || g.fs_action_short == FS_ACTION_SHORT_DISABLED) {
2016-08-13 04:54:37 -03:00
failsafe_short_off_event(MODE_REASON_RADIO_FAILSAFE);
2012-08-21 23:19:51 -03:00
}
}
}
2015-05-13 03:09:36 -03:00
void Plane::startup_INS_ground(void)
{
#if HIL_SUPPORT
if (g.hil_mode == 1) {
while (barometer.get_last_update() == 0) {
// the barometer begins updating when we get the first
// HIL_STATE message
gcs().send_text(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
hal.scheduler->delay(1000);
}
}
#endif
if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) {
gcs().send_text(MAV_SEVERITY_ALERT, "Beginning INS calibration. Do not move plane");
} else {
gcs().send_text(MAV_SEVERITY_ALERT, "Skipping INS calibration");
}
2013-01-13 01:04:18 -04:00
ahrs.init();
ahrs.set_fly_forward(true);
2014-04-21 04:12:24 -03:00
ahrs.set_vehicle_class(AHRS_VEHICLE_FIXED_WING);
2013-05-23 22:21:32 -03:00
ahrs.set_wind_estimation(true);
2013-01-13 01:04:18 -04:00
ins.init(scheduler.get_loop_rate_hz());
ahrs.reset();
2012-08-21 23:19:51 -03:00
// read Baro pressure at ground
//-----------------------------
barometer.set_log_baro_bit(MASK_LOG_IMU);
barometer.calibrate();
if (airspeed.enabled()) {
// initialize airspeed sensor
// --------------------------
airspeed.calibrate(true);
} else {
gcs().send_text(MAV_SEVERITY_WARNING,"No airspeed");
}
}
2013-08-29 00:13:58 -03:00
// updates the status of the notify objects
2013-08-24 05:58:32 -03:00
// should be called at 50hz
2015-05-13 03:09:36 -03:00
void Plane::update_notify()
{
2013-08-29 00:13:58 -03:00
notify.update();
}
// sets notify object flight mode information
void Plane::notify_flight_mode(enum FlightMode mode)
{
AP_Notify::flags.flight_mode = mode;
// set flight mode string
switch (mode) {
case MANUAL:
notify.set_flight_mode_str("MANU");
break;
case CIRCLE:
notify.set_flight_mode_str("CIRC");
break;
case STABILIZE:
notify.set_flight_mode_str("STAB");
break;
case TRAINING:
notify.set_flight_mode_str("TRAN");
break;
case ACRO:
notify.set_flight_mode_str("ACRO");
break;
case FLY_BY_WIRE_A:
notify.set_flight_mode_str("FBWA");
break;
case FLY_BY_WIRE_B:
notify.set_flight_mode_str("FBWB");
break;
case CRUISE:
notify.set_flight_mode_str("CRUS");
break;
case AUTOTUNE:
notify.set_flight_mode_str("ATUN");
break;
case AUTO:
notify.set_flight_mode_str("AUTO");
break;
case RTL:
notify.set_flight_mode_str("RTL ");
break;
case LOITER:
notify.set_flight_mode_str("LOITER");
break;
case AVOID_ADSB:
notify.set_flight_mode_str("AVOI");
break;
case GUIDED:
notify.set_flight_mode_str("GUID");
break;
case INITIALISING:
notify.set_flight_mode_str("INIT");
break;
case QSTABILIZE:
notify.set_flight_mode_str("QSTB");
break;
case QHOVER:
notify.set_flight_mode_str("QHOV");
break;
case QLOITER:
notify.set_flight_mode_str("QLOT");
break;
case QLAND:
notify.set_flight_mode_str("QLND");
break;
case QRTL:
notify.set_flight_mode_str("QRTL");
break;
default:
notify.set_flight_mode_str("----");
break;
}
}
/*
should we log a message type now?
*/
2015-05-13 03:09:36 -03:00
bool Plane::should_log(uint32_t mask)
{
#if LOGGING_ENABLED == ENABLED
return DataFlash.should_log(mask);
#else
return false;
#endif
}
/*
return throttle percentage from 0 to 100 for normal use and -100 to 100 when using reverse thrust
*/
int8_t Plane::throttle_percentage(void)
{
if (quadplane.in_vtol_mode()) {
return quadplane.throttle_percentage();
}
float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
if (aparm.throttle_min >= 0) {
return constrain_int16(throttle, 0, 100);
}
return constrain_int16(throttle, -100, 100);
}
/*
update AHRS soft arm state and log as needed
*/
2015-05-13 03:09:36 -03:00
void Plane::change_arm_state(void)
{
Log_Arm_Disarm();
update_soft_armed();
quadplane.set_armed(hal.util->get_soft_armed());
}
/*
arm motors
*/
bool Plane::arm_motors(const AP_Arming::ArmingMethod method, const bool do_arming_checks)
{
if (!arming.arm(method, do_arming_checks)) {
return false;
}
change_arm_state();
return true;
}
/*
disarm motors
*/
2015-05-13 03:09:36 -03:00
bool Plane::disarm_motors(void)
{
if (!arming.disarm()) {
return false;
}
if (control_mode != AUTO) {
// reset the mission on disarm if we are not in auto
mission.reset();
}
// suppress the throttle in auto-throttle modes
throttle_suppressed = auto_throttle_mode;
//only log if disarming was successful
change_arm_state();
// reload target airspeed which could have been modified by a mission
2016-11-17 21:07:10 -04:00
plane.aparm.airspeed_cruise_cm.load();
return true;
}