mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
Copter: add option to disable POSHOLD mode
Saves about 4k of Flash
This commit is contained in:
parent
b9ad2bc8db
commit
3a61b86e65
@ -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_POSHOLD_ENABLED DISABLED // disable poshold mode support
|
||||
|
||||
// features below are disabled by default on all boards
|
||||
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
|
||||
|
@ -969,7 +969,9 @@ private:
|
||||
ModeGuided mode_guided;
|
||||
ModeLand mode_land;
|
||||
ModeLoiter mode_loiter;
|
||||
#if MODE_POSHOLD_ENABLED == ENABLED
|
||||
ModePosHold mode_poshold;
|
||||
#endif
|
||||
ModeRTL mode_rtl;
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
ModeStabilize_Heli mode_stabilize;
|
||||
|
@ -273,6 +273,12 @@
|
||||
# define MODE_AUTO_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Position Hold - enable holding of global position
|
||||
#ifndef MODE_POSHOLD_ENABLED
|
||||
# define MODE_POSHOLD_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RADIO CONFIGURATION
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -94,9 +94,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if MODE_POSHOLD_ENABLED == ENABLED
|
||||
case POSHOLD:
|
||||
ret = &mode_poshold;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case BRAKE:
|
||||
ret = &mode_brake;
|
||||
|
Loading…
Reference in New Issue
Block a user