Browse Source

Copter: add option to disable RTL flight mode

master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
a7fe242e31
  1. 1
      ArduCopter/APM_Config.h
  2. 2
      ArduCopter/Copter.h
  3. 6
      ArduCopter/config.h
  4. 2
      ArduCopter/events.cpp
  5. 2
      ArduCopter/mode.cpp

1
ArduCopter/APM_Config.h

@ -28,6 +28,7 @@
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support //#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
//#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support //#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support
//#define MODE_POSHOLD_ENABLED DISABLED // disable poshold 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_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
//#define MODE_SPORT_ENABLED DISABLED // disable sport mode support //#define MODE_SPORT_ENABLED DISABLED // disable sport mode support

2
ArduCopter/Copter.h

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

6
ArduCopter/config.h

@ -297,6 +297,12 @@
# define MODE_POSHOLD_ENABLED ENABLED # define MODE_POSHOLD_ENABLED ENABLED
#endif #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 // SmartRTL - allows vehicle to retrace a (loop-eliminated) breadcrumb home
#ifndef MODE_SMARTRTL_ENABLED #ifndef MODE_SMARTRTL_ENABLED

2
ArduCopter/events.cpp

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

2
ArduCopter/mode.cpp

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

Loading…
Cancel
Save