Copter: treat Auto RTL the same as Auto

This commit is contained in:
Iampete1 2021-07-25 11:27:51 +01:00 committed by Randy Mackay
parent 885b12f179
commit cc53db406d
5 changed files with 5 additions and 1 deletions

View File

@ -58,6 +58,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
switch (copter.flightmode->mode_number()) {
case Mode::Number::AUTO:
case Mode::Number::AUTO_RTL:
case Mode::Number::AVOID_ADSB:
case Mode::Number::GUIDED:
case Mode::Number::LOITER:

View File

@ -23,6 +23,7 @@ MAV_MODE GCS_MAVLINK_Copter::base_mode() const
// ArduPlane documentation
switch (copter.flightmode->mode_number()) {
case Mode::Number::AUTO:
case Mode::Number::AUTO_RTL:
case Mode::Number::RTL:
case Mode::Number::LOITER:
case Mode::Number::AVOID_ADSB:

View File

@ -212,7 +212,7 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) {
// do not allow saving new waypoints while we're in auto or disarmed
if (copter.flightmode->mode_number() == Mode::Number::AUTO || !copter.motors->armed()) {
if (copter.flightmode->mode_number() == Mode::Number::AUTO || copter.flightmode->mode_number() == Mode::Number::AUTO_RTL || !copter.motors->armed()) {
break;
}

View File

@ -63,6 +63,7 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void)
{
switch (copter.flightmode->mode_number()) {
case Mode::Number::AUTO:
case Mode::Number::AUTO_RTL:
case Mode::Number::GUIDED:
case Mode::Number::RTL:
case Mode::Number::LAND:

View File

@ -365,6 +365,7 @@ bool Copter::should_disarm_on_failsafe() {
// if throttle is zero OR vehicle is landed disarm motors
return ap.throttle_zero || ap.land_complete;
case Mode::Number::AUTO:
case Mode::Number::AUTO_RTL:
// if mission has not started AND vehicle is landed, disarm motors
return !ap.auto_armed && ap.land_complete;
default: