Copter: add option to disable LOITER mode
This commit is contained in:
parent
9b440d6b25
commit
7154f4dea4
@ -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 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 WINCH_ENABLED DISABLED // disable winch support
|
||||||
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode 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_POSHOLD_ENABLED DISABLED // disable poshold mode support
|
||||||
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
|
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
|
||||||
|
|
||||||
|
@ -968,7 +968,9 @@ private:
|
|||||||
ModeFlip mode_flip;
|
ModeFlip mode_flip;
|
||||||
ModeGuided mode_guided;
|
ModeGuided mode_guided;
|
||||||
ModeLand mode_land;
|
ModeLand mode_land;
|
||||||
|
#if MODE_LOITER_ENABLED == ENABLED
|
||||||
ModeLoiter mode_loiter;
|
ModeLoiter mode_loiter;
|
||||||
|
#endif
|
||||||
#if MODE_POSHOLD_ENABLED == ENABLED
|
#if MODE_POSHOLD_ENABLED == ENABLED
|
||||||
ModePosHold mode_poshold;
|
ModePosHold mode_poshold;
|
||||||
#endif
|
#endif
|
||||||
|
@ -273,6 +273,12 @@
|
|||||||
# define MODE_AUTO_ENABLED ENABLED
|
# define MODE_AUTO_ENABLED ENABLED
|
||||||
#endif
|
#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
|
// Position Hold - enable holding of global position
|
||||||
#ifndef MODE_POSHOLD_ENABLED
|
#ifndef MODE_POSHOLD_ENABLED
|
||||||
|
@ -60,9 +60,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
|
|||||||
ret = &mode_circle;
|
ret = &mode_circle;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
#if MODE_LOITER_ENABLED == ENABLED
|
||||||
case LOITER:
|
case LOITER:
|
||||||
ret = &mode_loiter;
|
ret = &mode_loiter;
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
case GUIDED:
|
case GUIDED:
|
||||||
ret = &mode_guided;
|
ret = &mode_guided;
|
||||||
|
@ -569,7 +569,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case AUXSW_PRECISION_LOITER:
|
case AUXSW_PRECISION_LOITER:
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if PRECISION_LANDING == ENABLED && MODE_LOITER_ENABLED == ENABLED
|
||||||
switch (ch_flag) {
|
switch (ch_flag) {
|
||||||
case AUX_SWITCH_HIGH:
|
case AUX_SWITCH_HIGH:
|
||||||
mode_loiter.set_precision_loiter_enabled(true);
|
mode_loiter.set_precision_loiter_enabled(true);
|
||||||
|
Loading…
Reference in New Issue
Block a user