Copter: add option to disable LOITER mode

This commit is contained in:
Peter Barker 2018-02-22 16:23:35 +11:00 committed by Randy Mackay
parent 9b440d6b25
commit 7154f4dea4
5 changed files with 12 additions and 1 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_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

@ -968,7 +968,9 @@ private:
ModeFlip mode_flip;
ModeGuided mode_guided;
ModeLand mode_land;
#if MODE_LOITER_ENABLED == ENABLED
ModeLoiter mode_loiter;
#endif
#if MODE_POSHOLD_ENABLED == ENABLED
ModePosHold mode_poshold;
#endif

View File

@ -273,6 +273,12 @@
# define MODE_AUTO_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Loiter mode - allows vehicle to hold global position
#ifndef MODE_LOITER_ENABLED
# define MODE_LOITER_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Position Hold - enable holding of global position
#ifndef MODE_POSHOLD_ENABLED

View File

@ -60,9 +60,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
ret = &mode_circle;
break;
#if MODE_LOITER_ENABLED == ENABLED
case LOITER:
ret = &mode_loiter;
break;
#endif
case GUIDED:
ret = &mode_guided;

View File

@ -569,7 +569,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
break;
case AUXSW_PRECISION_LOITER:
#if PRECISION_LANDING == ENABLED
#if PRECISION_LANDING == ENABLED && MODE_LOITER_ENABLED == ENABLED
switch (ch_flag) {
case AUX_SWITCH_HIGH:
mode_loiter.set_precision_loiter_enabled(true);