mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
Copter: add option to disable GUIDED_NOGPS flight mode
Saves about 6.3kB of flash
This commit is contained in:
parent
86b162e32f
commit
e4898e1d60
@ -27,6 +27,7 @@
|
|||||||
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
|
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
|
||||||
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
|
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
|
||||||
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
|
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
|
||||||
|
//#define MODE_GUIDED_NOGPS_ENABLED DISABLED // disable guided/nogps 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_RTL_ENABLED DISABLED // disable rtl mode support
|
||||||
|
@ -995,7 +995,9 @@ private:
|
|||||||
ModeAvoidADSB mode_avoid_adsb;
|
ModeAvoidADSB mode_avoid_adsb;
|
||||||
#endif
|
#endif
|
||||||
ModeThrow mode_throw;
|
ModeThrow mode_throw;
|
||||||
|
#if MODE_GUIDED_NOGPS_ENABLED == ENABLED
|
||||||
ModeGuidedNoGPS mode_guided_nogps;
|
ModeGuidedNoGPS mode_guided_nogps;
|
||||||
|
#endif
|
||||||
#if MODE_SMARTRTL_ENABLED == ENABLED
|
#if MODE_SMARTRTL_ENABLED == ENABLED
|
||||||
ModeSmartRTL mode_smartrtl;
|
ModeSmartRTL mode_smartrtl;
|
||||||
#endif
|
#endif
|
||||||
|
@ -291,6 +291,12 @@
|
|||||||
# define MODE_GUIDED_ENABLED ENABLED
|
# define MODE_GUIDED_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// GuidedNoGPS mode - control vehicle's angles from GCS
|
||||||
|
#ifndef MODE_GUIDED_NOGPS_ENABLED
|
||||||
|
# define MODE_GUIDED_NOGPS_ENABLED ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Loiter mode - allows vehicle to hold global position
|
// Loiter mode - allows vehicle to hold global position
|
||||||
#ifndef MODE_LOITER_ENABLED
|
#ifndef MODE_LOITER_ENABLED
|
||||||
|
@ -126,9 +126,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
|
|||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if MODE_GUIDED_NOGPS_ENABLED == ENABLED
|
||||||
case GUIDED_NOGPS:
|
case GUIDED_NOGPS:
|
||||||
ret = &mode_guided_nogps;
|
ret = &mode_guided_nogps;
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if MODE_SMARTRTL_ENABLED == ENABLED
|
#if MODE_SMARTRTL_ENABLED == ENABLED
|
||||||
case SMART_RTL:
|
case SMART_RTL:
|
||||||
|
Loading…
Reference in New Issue
Block a user