Copter: add option to disable RTL flight mode

This commit is contained in:
Peter Barker 2018-02-23 16:33:49 +11:00 committed by Randy Mackay
parent b8c432b1a1
commit a7fe242e31
5 changed files with 13 additions and 0 deletions

View File

@ -28,6 +28,7 @@
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
//#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support
//#define MODE_POSHOLD_ENABLED DISABLED // disable poshold mode support
//#define MODE_RTL_ENABLED DISABLED // disable rtl mode support
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
//#define MODE_SPORT_ENABLED DISABLED // disable sport mode support

View File

@ -978,7 +978,9 @@ private:
#if MODE_POSHOLD_ENABLED == ENABLED
ModePosHold mode_poshold;
#endif
#if MODE_RTL_ENABLED == ENABLED
ModeRTL mode_rtl;
#endif
#if FRAME_CONFIG == HELI_FRAME
ModeStabilize_Heli mode_stabilize;
#else

View File

@ -297,6 +297,12 @@
# define MODE_POSHOLD_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// RTL - Return To Launch
#ifndef MODE_RTL_ENABLED
# define MODE_RTL_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// SmartRTL - allows vehicle to retrace a (loop-eliminated) breadcrumb home
#ifndef MODE_SMARTRTL_ENABLED

View File

@ -189,8 +189,10 @@ void Copter::failsafe_terrain_on_event()
if (should_disarm_on_failsafe()) {
init_disarm_motors();
#if MODE_RTL_ENABLED == ENABLED
} else if (control_mode == RTL) {
mode_rtl.restart_without_terrain();
#endif
} else {
set_mode_RTL_or_land_with_pause(MODE_REASON_TERRAIN_FAILSAFE);
}

View File

@ -76,9 +76,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
ret = &mode_land;
break;
#if MODE_RTL_ENABLED == ENABLED
case RTL:
ret = &mode_rtl;
break;
#endif
#if MODE_DRIFT_ENABLED == ENABLED
case DRIFT: