Browse Source

Copter: add option to disable GUIDED_NOGPS flight mode

Saves about 6.3kB of flash
master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
e4898e1d60
  1. 1
      ArduCopter/APM_Config.h
  2. 2
      ArduCopter/Copter.h
  3. 6
      ArduCopter/config.h
  4. 2
      ArduCopter/mode.cpp

1
ArduCopter/APM_Config.h

@ -27,6 +27,7 @@ @@ -27,6 +27,7 @@
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
//#define MODE_DRIFT_ENABLED DISABLED // disable drift 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_POSHOLD_ENABLED DISABLED // disable poshold mode support
//#define MODE_RTL_ENABLED DISABLED // disable rtl mode support

2
ArduCopter/Copter.h

@ -995,7 +995,9 @@ private: @@ -995,7 +995,9 @@ private:
ModeAvoidADSB mode_avoid_adsb;
#endif
ModeThrow mode_throw;
#if MODE_GUIDED_NOGPS_ENABLED == ENABLED
ModeGuidedNoGPS mode_guided_nogps;
#endif
#if MODE_SMARTRTL_ENABLED == ENABLED
ModeSmartRTL mode_smartrtl;
#endif

6
ArduCopter/config.h

@ -291,6 +291,12 @@ @@ -291,6 +291,12 @@
# define MODE_GUIDED_ENABLED ENABLED
#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
#ifndef MODE_LOITER_ENABLED

2
ArduCopter/mode.cpp

@ -126,9 +126,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode) @@ -126,9 +126,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
break;
#endif
#if MODE_GUIDED_NOGPS_ENABLED == ENABLED
case GUIDED_NOGPS:
ret = &mode_guided_nogps;
break;
#endif
#if MODE_SMARTRTL_ENABLED == ENABLED
case SMART_RTL:

Loading…
Cancel
Save