Copter: add option to disable DRIFT flight mode

Saves about 1kB of space
This commit is contained in:
Peter Barker 2018-02-23 14:55:51 +11:00 committed by Randy Mackay
parent e5056f8d40
commit 0ddeb56a05
4 changed files with 11 additions and 0 deletions

View File

@ -24,6 +24,7 @@
//#define SPRAYER DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
//#define WINCH_ENABLED DISABLED // disable winch support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
//#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

View File

@ -964,7 +964,9 @@ private:
#endif
ModeBrake mode_brake;
ModeCircle mode_circle;
#if MODE_DRIFT_ENABLED == ENABLED
ModeDrift mode_drift;
#endif
ModeFlip mode_flip;
ModeGuided mode_guided;
ModeLand mode_land;

View File

@ -273,6 +273,12 @@
# define MODE_AUTO_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Drift - fly vehicle in altitude-held, coordinated-turn mode
#ifndef MODE_DRIFT_ENABLED
# define MODE_DRIFT_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Loiter mode - allows vehicle to hold global position
#ifndef MODE_LOITER_ENABLED

View File

@ -78,9 +78,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
ret = &mode_rtl;
break;
#if MODE_DRIFT_ENABLED == ENABLED
case DRIFT:
ret = &mode_drift;
break;
#endif
#if MODE_SPORT_ENABLED == ENABLED
case SPORT: