From 7154f4dea4bb4f78e1f75ad146e6e97b836870a1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 22 Feb 2018 16:23:35 +1100 Subject: [PATCH] Copter: add option to disable LOITER mode --- ArduCopter/APM_Config.h | 1 + ArduCopter/Copter.h | 2 ++ ArduCopter/config.h | 6 ++++++ ArduCopter/mode.cpp | 2 ++ ArduCopter/switches.cpp | 2 +- 5 files changed, 12 insertions(+), 1 deletion(-) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 332704f4d1..3268a6a500 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -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 diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 2b23883932..13121a0a6f 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -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 diff --git a/ArduCopter/config.h b/ArduCopter/config.h index b89091a535..e17925f94a 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -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 diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index cee4783e29..8ae4d6ec53 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -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; diff --git a/ArduCopter/switches.cpp b/ArduCopter/switches.cpp index 1a87ab8c63..27453f7ddd 100644 --- a/ArduCopter/switches.cpp +++ b/ArduCopter/switches.cpp @@ -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);