diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index 274361f7bc..2cc0f158be 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -1,5 +1,8 @@ #include #include "AP_OpticalFlow.h" + +#if AP_OPTICALFLOW_ENABLED + #include "AP_OpticalFlow_Onboard.h" #include "AP_OpticalFlow_SITL.h" #include "AP_OpticalFlow_Pixart.h" @@ -247,3 +250,5 @@ OpticalFlow *opticalflow() } } + +#endif // AP_OPTICALFLOW_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow.h index 98c5a5d001..84012bf735 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.h @@ -14,6 +14,18 @@ */ #pragma once +#include + +#ifndef AP_OPTICALFLOW_ENABLED +#define AP_OPTICALFLOW_ENABLED 1 +#endif + +#ifndef HAL_MSP_OPTICALFLOW_ENABLED +#define HAL_MSP_OPTICALFLOW_ENABLED (AP_OPTICALFLOW_ENABLED && (HAL_MSP_ENABLED && !HAL_MINIMIZE_FEATURES)) +#endif + +#if AP_OPTICALFLOW_ENABLED + /* * AP_OpticalFlow.h - OpticalFlow Base Class for Ardupilot * Code by Randy Mackay. DIYDrones.com @@ -25,10 +37,6 @@ #include -#ifndef HAL_MSP_OPTICALFLOW_ENABLED -#define HAL_MSP_OPTICALFLOW_ENABLED HAL_MSP_ENABLED && !HAL_MINIMIZE_FEATURES -#endif - class OpticalFlow_backend; class AP_AHRS; @@ -143,3 +151,5 @@ namespace AP { } #include "AP_OpticalFlow_Backend.h" + +#endif // AP_OPTICALFLOW_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.cpp index 4a48afecab..20eb879895 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.cpp @@ -15,6 +15,8 @@ #include "AP_OpticalFlow.h" +#if AP_OPTICALFLOW_ENABLED + extern const AP_HAL::HAL& hal; OpticalFlow_backend::OpticalFlow_backend(OpticalFlow &_frontend) : @@ -46,3 +48,5 @@ void OpticalFlow_backend::_applyYaw(Vector2f &v) v.x = cosYaw * x - sinYaw * y; v.y = sinYaw * x + cosYaw * y; } + +#endif diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp index 57c0cc5a35..0e120df34e 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp @@ -30,8 +30,11 @@ sensor sends packets at 25hz */ -#include #include "AP_OpticalFlow_CXOF.h" + +#if AP_OPTICALFLOW_CXOF_ENABLED + +#include #include #include #include @@ -199,3 +202,5 @@ void AP_OpticalFlow_CXOF::update(void) gyro_sum.zero(); gyro_sum_count = 0; } + +#endif // AP_OPTICALFLOW_CXOF_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.h index aec5a85393..32b61af2c5 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.h @@ -1,6 +1,13 @@ #pragma once #include "AP_OpticalFlow.h" + +#ifndef AP_OPTICALFLOW_CXOF_ENABLED +#define AP_OPTICALFLOW_CXOF_ENABLED AP_OPTICALFLOW_ENABLED +#endif + +#if AP_OPTICALFLOW_CXOF_ENABLED + #include class AP_OpticalFlow_CXOF : public OpticalFlow_backend @@ -27,3 +34,5 @@ private: Vector2f gyro_sum; // sum of gyro sensor values since last frame from flow sensor uint16_t gyro_sum_count; // number of gyro sensor values in sum }; + +#endif // AP_OPTICALFLOW_CXOF_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp index bf80ca230c..944c1fd368 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp @@ -1,8 +1,8 @@ -#include +#include "AP_OpticalFlow_HereFlow.h" -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if AP_OPTICALFLOW_HEREFLOW_ENABLED -#include "AP_OpticalFlow_HereFlow.h" +#include #include #include @@ -101,5 +101,4 @@ void AP_OpticalFlow_HereFlow::_push_state(void) new_data = false; } -#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS - +#endif // AP_OPTICALFLOW_HEREFLOW_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h index 3c9ed02551..77d86ff73e 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h @@ -1,7 +1,12 @@ #pragma once -#include "AP_OpticalFlow_Backend.h" -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#include "AP_OpticalFlow.h" + +#ifndef AP_OPTICALFLOW_HEREFLOW_ENABLED +#define AP_OPTICALFLOW_HEREFLOW_ENABLED (AP_OPTICALFLOW_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS) +#endif + +#if AP_OPTICALFLOW_HEREFLOW_ENABLED #include @@ -32,4 +37,5 @@ private: void _push_state(void); }; -#endif //HAL_ENABLE_LIBUAVCAN_DRIVERS + +#endif // AP_OPTICALFLOW_HEREFLOW_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp index a7b739c444..9b90bb42b3 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp @@ -13,9 +13,12 @@ along with this program. If not, see . */ +#include "AP_OpticalFlow_MAV.h" + +#if AP_OPTICALFLOW_MAV_ENABLED + #include #include -#include "AP_OpticalFlow_MAV.h" #define OPTFLOW_MAV_TIMEOUT_SEC 0.5f @@ -104,3 +107,5 @@ void AP_OpticalFlow_MAV::handle_msg(const mavlink_message_t &msg) // take sensor id from message sensor_id = packet.sensor_id; } + +#endif // AP_OPTICALFLOW_MAV_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h index 5ba90ae784..ba1a7872af 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h @@ -1,6 +1,13 @@ #pragma once #include "AP_OpticalFlow.h" + +#ifndef AP_OPTICALFLOW_MAV_ENABLED +#define AP_OPTICALFLOW_MAV_ENABLED AP_OPTICALFLOW_ENABLED +#endif + +#if AP_OPTICALFLOW_MAV_ENABLED + #include class AP_OpticalFlow_MAV : public OpticalFlow_backend @@ -32,3 +39,5 @@ private: Vector2f gyro_sum; // sum of gyro sensor values since last frame from flow sensor uint16_t gyro_sum_count; // number of gyro sensor values in sum }; + +#endif // AP_OPTICALFLOW_MAV_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.cpp index c441f7cf36..8b5896a9dd 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.cpp @@ -14,6 +14,8 @@ */ #include "AP_OpticalFlow_Onboard.h" +#if AP_OPTICALFLOW_ONBOARD_ENABLED + #include #include "AP_OpticalFlow.h" @@ -98,3 +100,5 @@ void AP_OpticalFlow_Onboard::update() } #endif + +#endif // AP_OPTICALFLOW_ONBOARD_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.h index 7b28c64ad0..b152741ddf 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.h @@ -14,6 +14,14 @@ */ #pragma once +#include + +#ifndef AP_OPTICALFLOW_ONBOARD_ENABLED +#define AP_OPTICALFLOW_ONBOARD_ENABLED AP_OPTICALFLOW_ENABLED +#endif + +#if AP_OPTICALFLOW_ONBOARD_ENABLED + #include #include #include @@ -30,3 +38,5 @@ public: private: uint32_t _last_read_ms; }; + +#endif // AP_OPTICALFLOW_ONBOARD_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp index 8808534e4c..1e3f634520 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp @@ -16,8 +16,11 @@ driver for PX4Flow optical flow sensor */ -#include #include "AP_OpticalFlow_PX4Flow.h" + +#if AP_OPTICALFLOW_PX4FLOW_ENABLED + +#include #include #include #include @@ -135,3 +138,5 @@ void AP_OpticalFlow_PX4Flow::timer(void) _update_frontend(state); } + +#endif // AP_OPTICALFLOW_PX4FLOW_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.h index eeeecb7bbf..ebda790c20 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.h @@ -1,6 +1,13 @@ #pragma once #include "AP_OpticalFlow.h" + +#ifndef AP_OPTICALFLOW_PX4FLOW_ENABLED +#define AP_OPTICALFLOW_PX4FLOW_ENABLED AP_OPTICALFLOW_ENABLED +#endif + +#if AP_OPTICALFLOW_PX4FLOW_ENABLED + #include class AP_OpticalFlow_PX4Flow : public OpticalFlow_backend @@ -46,3 +53,5 @@ private: void timer(void); }; + +#endif // AP_OPTICALFLOW_PX4FLOW_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp index 9de917fd4e..55ae7946e2 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp @@ -20,12 +20,15 @@ timing for register reads and writes is critical */ +#include "AP_OpticalFlow_Pixart.h" + +#if AP_OPTICALFLOW_PIXART_ENABLED + #include #include #include #include #include "AP_OpticalFlow.h" -#include "AP_OpticalFlow_Pixart.h" #include "AP_OpticalFlow_Pixart_SROM.h" #include @@ -360,3 +363,5 @@ void AP_OpticalFlow_Pixart::update(void) // copy results to front end _update_frontend(state); } + +#endif // AP_OPTICALFLOW_PIXART_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.h index 82b2f14a68..b2e8a4d179 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.h @@ -1,6 +1,13 @@ #pragma once #include "AP_OpticalFlow.h" + +#ifndef AP_OPTICALFLOW_PIXART_ENABLED +#define AP_OPTICALFLOW_PIXART_ENABLED AP_OPTICALFLOW_ENABLED +#endif + +#if AP_OPTICALFLOW_PIXART_ENABLED + #include class AP_OpticalFlow_Pixart : public OpticalFlow_backend @@ -75,3 +82,5 @@ private: uint32_t last_burst_us; uint32_t last_update_ms; }; + +#endif // AP_OPTICALFLOW_PIXART_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp index ce85a2a4d3..3e7253071f 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp @@ -33,8 +33,11 @@ byte13:footer (0x55) */ -#include #include "AP_OpticalFlow_UPFLOW.h" + +#if AP_OPTICALFLOW_UPFLOW_ENABLED + +#include #include #include #include @@ -187,3 +190,5 @@ void AP_OpticalFlow_UPFLOW::update(void) gyro_sum.zero(); gyro_sum_count = 0; } + +#endif // AP_OPTICALFLOW_UPFLOW_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.h index d00aa3b31f..5cf16f182c 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.h @@ -1,6 +1,13 @@ #pragma once #include "AP_OpticalFlow.h" + +#ifndef AP_OPTICALFLOW_UPFLOW_ENABLED +#define AP_OPTICALFLOW_UPFLOW_ENABLED AP_OPTICALFLOW_ENABLED +#endif + +#if AP_OPTICALFLOW_UPFLOW_ENABLED + #include class AP_OpticalFlow_UPFLOW : public OpticalFlow_backend @@ -34,3 +41,5 @@ private: Vector2f gyro_sum; // sum of gyro sensor values since last frame from flow sensor uint16_t gyro_sum_count; // number of gyro sensor values in sum }; + +#endif // AP_OPTICALFLOW_UPFLOW_ENABLED