From 8416730a8cbf6f535f5a2b69cd6286c9f4aa96f8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 12 Jul 2023 16:23:33 +1000 Subject: [PATCH] AP_OpticalFlow: add and use AP_OPTICALFLOW_CALIBRATOR_ENABLED --- libraries/AP_OpticalFlow/AP_OpticalFlow.cpp | 4 ++++ libraries/AP_OpticalFlow/AP_OpticalFlow.h | 3 ++- libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp | 7 +++++++ libraries/AP_OpticalFlow/AP_OpticalFlow_config.h | 4 ++++ 4 files changed, 17 insertions(+), 1 deletion(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index 61896831fb..8739e0282f 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -193,6 +193,7 @@ void AP_OpticalFlow::update(void) // only healthy if the data is less than 0.5s old _flags.healthy = (AP_HAL::millis() - _last_update_ms < 500); +#if AP_OPTICALFLOW_CALIBRATOR_ENABLED // update calibrator and save resulting scaling if (_calibrator != nullptr) { if (_calibrator->update()) { @@ -207,6 +208,7 @@ void AP_OpticalFlow::update(void) GCS_SEND_TEXT(MAV_SEVERITY_INFO, "FlowCal: FLOW_FXSCALER=%d, FLOW_FYSCALER=%d", (int)_flowScalerX, (int)_flowScalerY); } } +#endif } void AP_OpticalFlow::handle_msg(const mavlink_message_t &msg) @@ -235,6 +237,7 @@ void AP_OpticalFlow::handle_msp(const MSP::msp_opflow_data_message_t &pkt) } #endif //HAL_MSP_OPTICALFLOW_ENABLED +#if AP_OPTICALFLOW_CALIBRATOR_ENABLED // start calibration void AP_OpticalFlow::start_calibration() { @@ -257,6 +260,7 @@ void AP_OpticalFlow::stop_calibration() _calibrator->stop(); } } +#endif void AP_OpticalFlow::update_state(const OpticalFlow_state &state) { diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow.h index d071436f8c..c27498c6da 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.h @@ -139,9 +139,10 @@ private: void Log_Write_Optflow(); uint32_t _log_bit = -1; // bitmask bit which indicates if we should log. -1 means we always log +#if AP_OPTICALFLOW_CALIBRATOR_ENABLED // calibrator AP_OpticalFlow_Calibrator *_calibrator; - +#endif }; namespace AP { diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp index 84de1759d6..ff4cba123f 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp @@ -13,7 +13,12 @@ along with this program. If not, see . */ +#include "AP_OpticalFlow_config.h" + +#if AP_OPTICALFLOW_CALIBRATOR_ENABLED + #include "AP_OpticalFlow_Calibrator.h" + #include #include @@ -329,3 +334,5 @@ void AP_OpticalFlow_Calibrator::log_sample(uint8_t axis, uint8_t sample_num, flo (double)los_pred); } #endif // HAL_LOGGING_ENABLED + +#endif // AP_OPTICALFLOW_CALIBRATOR_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_config.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_config.h index 35bf0ea4ad..e70e391cf5 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_config.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_config.h @@ -8,6 +8,10 @@ #define AP_OPTICALFLOW_ENABLED 1 #endif +#ifndef AP_OPTICALFLOW_CALIBRATOR_ENABLED +#define AP_OPTICALFLOW_CALIBRATOR_ENABLED AP_OPTICALFLOW_ENABLED +#endif + #ifndef AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED #define AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED AP_OPTICALFLOW_ENABLED #endif