From 58cb4cbfb182ad64f62a02c4cc26afd63d3ae69e Mon Sep 17 00:00:00 2001 From: Stephen Dade Date: Wed, 17 Aug 2022 12:18:38 +1000 Subject: [PATCH] Copter: Make mode flowhold a build option via MODE_FLOWHOLD_ENABLED --- ArduCopter/Copter.h | 2 +- ArduCopter/Parameters.cpp | 4 ++-- ArduCopter/config.h | 6 ++++++ ArduCopter/mode.cpp | 2 +- ArduCopter/mode.h | 4 ++-- ArduCopter/mode_flowhold.cpp | 4 ++-- 6 files changed, 14 insertions(+), 8 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 6fb0ea93b3..7aa514ac69 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -983,7 +983,7 @@ private: #if MODE_SMARTRTL_ENABLED == ENABLED ModeSmartRTL mode_smartrtl; #endif -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED ModeFlowHold mode_flowhold; #endif #if MODE_ZIGZAG_ENABLED == ENABLED diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index db8d5c582b..641d527c64 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -885,7 +885,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000), -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED // @Group: FHLD // @Path: mode_flowhold.cpp AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, ModeFlowHold), @@ -1160,7 +1160,7 @@ ParametersG2::ParametersG2(void) #if MODE_SMARTRTL_ENABLED == ENABLED ,smart_rtl() #endif -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED ,mode_flowhold_ptr(&copter.mode_flowhold) #endif #if MODE_FOLLOW_ENABLED == ENABLED diff --git a/ArduCopter/config.h b/ArduCopter/config.h index cb87f65dc3..10eb35943c 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -319,6 +319,12 @@ # define MODE_TURTLE_ENABLED !HAL_MINIMIZE_FEATURES && !defined(DISABLE_DSHOT) && FRAME_CONFIG != HELI_FRAME #endif +////////////////////////////////////////////////////////////////////////////// +// Flowhold - use optical flow to hover in place +#ifndef MODE_FLOWHOLD_ENABLED +# define MODE_FLOWHOLD_ENABLED !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#endif + ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 9e2083fc5d..cbeabbdbc5 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -139,7 +139,7 @@ Mode *Copter::mode_from_mode_num(const Mode::Number mode) break; #endif -#if AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED case Mode::Number::FLOWHOLD: ret = (Mode *)g2.mode_flowhold_ptr; break; diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 66f47644b1..f49f788fb7 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -836,7 +836,7 @@ private: }; -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED /* class to support FLOWHOLD mode, which is a position hold mode using optical flow directly, avoiding the need for a rangefinder @@ -922,7 +922,7 @@ private: // last time there was significant stick input uint32_t last_stick_input_ms; }; -#endif // AP_OPTICALFLOW_ENABLED +#endif // MODE_FLOWHOLD_ENABLED class ModeGuided : public Mode { diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index cb4c9fde1e..91814ab45f 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -1,7 +1,7 @@ #include "Copter.h" #include -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED /* implement FLOWHOLD mode, for position hold using optical flow @@ -509,4 +509,4 @@ void ModeFlowHold::update_height_estimate(void) last_ins_height = ins_height; } -#endif // AP_OPTICALFLOW_ENABLED +#endif // MODE_FLOWHOLD_ENABLED