Copter: add option to disable SPORT flight mode

Saves about 1,500 bytes
This commit is contained in:
Peter Barker 2018-02-23 14:48:02 +11:00 committed by Randy Mackay
parent 7154f4dea4
commit e5056f8d40
4 changed files with 11 additions and 0 deletions

View File

@ -27,6 +27,7 @@
//#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support
//#define MODE_POSHOLD_ENABLED DISABLED // disable poshold mode support
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
//#define MODE_SPORT_ENABLED DISABLED // disable sport mode support
// features below are disabled by default on all boards

View File

@ -980,7 +980,9 @@ private:
#else
ModeStabilize mode_stabilize;
#endif
#if MODE_SPORT_ENABLED == ENABLED
ModeSport mode_sport;
#endif
#if ADSB_ENABLED == ENABLED
ModeAvoidADSB mode_avoid_adsb;
#endif

View File

@ -291,6 +291,12 @@
# define MODE_SMARTRTL_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Sport - fly vehicle in rate-controlled (earth-frame) mode
#ifndef MODE_SPORT_ENABLED
# define MODE_SPORT_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION
//////////////////////////////////////////////////////////////////////////////

View File

@ -82,9 +82,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
ret = &mode_drift;
break;
#if MODE_SPORT_ENABLED == ENABLED
case SPORT:
ret = &mode_sport;
break;
#endif
case FLIP:
ret = &mode_flip;