From d04f4d8178a5440829f1ab1b6bfe15879886a1bf Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 19 Oct 2022 14:39:45 +1100 Subject: [PATCH] Copter: correct defines gating flowhold mode We have an explicit define for this mode now --- ArduCopter/Parameters.h | 2 +- ArduCopter/RC_Channel.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 1c4e3f03ad..06539a404b 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -573,7 +573,7 @@ public: ToyMode toy_mode; #endif -#if AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED // we need a pointer to the mode for the G2 table void *mode_flowhold_ptr; #endif diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index dfad573d6e..b9066f0828 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -513,7 +513,7 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi break; case AUX_FUNC::FLOWHOLD: -#if AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED do_aux_function_change_mode(Mode::Number::FLOWHOLD, ch_flag); #endif break;