From 4b95ad12bf0e4aa00e364228a6cb5296e5d01372 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 4 May 2022 18:13:29 +1000 Subject: [PATCH] AP_Airspeed: allow backends to be compiled out --- libraries/AP_Airspeed/AP_Airspeed.cpp | 52 +++++++++++-------- libraries/AP_Airspeed/AP_Airspeed.h | 8 +-- libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp | 5 ++ libraries/AP_Airspeed/AP_Airspeed_ASP5033.h | 10 ++++ libraries/AP_Airspeed/AP_Airspeed_Backend.h | 2 - libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp | 5 ++ libraries/AP_Airspeed/AP_Airspeed_DLVR.h | 10 ++++ libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp | 4 ++ libraries/AP_Airspeed/AP_Airspeed_MS4525.h | 10 ++++ libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp | 4 ++ libraries/AP_Airspeed/AP_Airspeed_MS5525.h | 10 ++++ libraries/AP_Airspeed/AP_Airspeed_MSP.cpp | 4 +- libraries/AP_Airspeed/AP_Airspeed_MSP.h | 14 +++-- libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp | 7 ++- libraries/AP_Airspeed/AP_Airspeed_NMEA.h | 11 ++++ libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp | 5 ++ libraries/AP_Airspeed/AP_Airspeed_SDP3X.h | 11 ++++ libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp | 8 ++- libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h | 11 ++++ libraries/AP_Airspeed/AP_Airspeed_analog.cpp | 7 ++- libraries/AP_Airspeed/AP_Airspeed_analog.h | 10 ++++ 21 files changed, 168 insertions(+), 40 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 340bef649b..c8820e5d4a 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -45,15 +45,9 @@ #include "AP_Airspeed_analog.h" #include "AP_Airspeed_ASP5033.h" #include "AP_Airspeed_Backend.h" -#if HAL_ENABLE_LIBUAVCAN_DRIVERS #include "AP_Airspeed_UAVCAN.h" -#endif -#if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub) #include "AP_Airspeed_NMEA.h" -#endif -#if HAL_MSP_AIRSPEED_ENABLED #include "AP_Airspeed_MSP.h" -#endif extern const AP_HAL::HAL &hal; #ifdef HAL_AIRSPEED_TYPE_DEFAULT @@ -394,65 +388,79 @@ void AP_Airspeed::init() // nothing to do break; case TYPE_I2C_MS4525: +#if AP_AIRSPEED_MS4525_ENABLED sensor[i] = new AP_Airspeed_MS4525(*this, i); +#endif break; case TYPE_ANALOG: +#if AP_AIRSPEED_ANALOG_ENABLED sensor[i] = new AP_Airspeed_Analog(*this, i); +#endif break; case TYPE_I2C_MS5525: +#if AP_AIRSPEED_MS5525_ENABLED sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_AUTO); +#endif break; case TYPE_I2C_MS5525_ADDRESS_1: +#if AP_AIRSPEED_MS5525_ENABLED sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_1); +#endif break; case TYPE_I2C_MS5525_ADDRESS_2: +#if AP_AIRSPEED_MS5525_ENABLED sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_2); +#endif break; case TYPE_I2C_SDP3X: +#if AP_AIRSPEED_SDP3X_ENABLED sensor[i] = new AP_Airspeed_SDP3X(*this, i); +#endif break; case TYPE_I2C_DLVR_5IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 5); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_I2C_DLVR_10IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 10); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_I2C_DLVR_20IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 20); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_I2C_DLVR_30IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 30); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_I2C_DLVR_60IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 60); -#endif // !HAL_MINIMIZE_FEATURES +#endif // AP_AIRSPEED_DLVR_ENABLED break; case TYPE_I2C_ASP5033: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_ASP5033_ENABLED sensor[i] = new AP_Airspeed_ASP5033(*this, i); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_UAVCAN: -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if AP_AIRSPEED_UAVCAN_ENABLED sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i); #endif break; case TYPE_NMEA_WATER: +#if AP_AIRSPEED_NMEA_ENABLED #if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub) sensor[i] = new AP_Airspeed_NMEA(*this, i); +#endif #endif break; case TYPE_MSP: -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED sensor[i] = new AP_Airspeed_MSP(*this, i, 0); #endif break; @@ -657,7 +665,7 @@ void AP_Airspeed::update() #endif } -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED /* handle MSP airspeed data */ @@ -801,7 +809,7 @@ bool AP_Airspeed::healthy(uint8_t i) const { return false; } float AP_Airspeed::get_airspeed(uint8_t i) const { return 0.0; } float AP_Airspeed::get_differential_pressure(uint8_t i) const { return 0.0; } -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {} #endif diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index 2d0336be31..b8015cb670 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -11,6 +11,9 @@ #define AP_AIRSPEED_ENABLED 1 #endif +#ifndef AP_AIRSPEED_MSP_ENABLED +#define AP_AIRSPEED_MSP_ENABLED (AP_AIRSPEED_ENABLED && HAL_MSP_SENSORS_ENABLED) +#endif class AP_Airspeed_Backend; @@ -22,9 +25,6 @@ class AP_Airspeed_Backend; #define AP_AIRSPEED_AUTOCAL_ENABLE AP_AIRSPEED_ENABLED #endif -#ifndef HAL_MSP_AIRSPEED_ENABLED -#define HAL_MSP_AIRSPEED_ENABLED HAL_MSP_SENSORS_ENABLED -#endif class Airspeed_Calibration { public: friend class AP_Airspeed; @@ -172,7 +172,7 @@ public: return get_corrected_pressure(primary); } -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED void handle_msp(const MSP::msp_airspeed_data_message_t &pkt); #endif diff --git a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp index f687f72cc1..e727d5924c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp @@ -19,6 +19,9 @@ */ #include "AP_Airspeed_ASP5033.h" + +#if AP_AIRSPEED_ASP5033_ENABLED + #include extern const AP_HAL::HAL &hal; @@ -174,3 +177,5 @@ bool AP_Airspeed_ASP5033::get_temperature(float &temperature) return true; } + +#endif diff --git a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.h b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.h index 00aaf6f4c5..99c340ec5b 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.h +++ b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.h @@ -14,6 +14,14 @@ */ #pragma once +#include + +#ifndef AP_AIRSPEED_ASP5033_ENABLED +#define AP_AIRSPEED_ASP5033_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_ASP5033_ENABLED + /* backend driver for airspeed from I2C */ @@ -44,3 +52,5 @@ private: AP_HAL::OwnPtr dev; }; + +#endif // AP_AIRSPEED_ASP5033_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.h b/libraries/AP_Airspeed/AP_Airspeed_Backend.h index 9e9c1b6a95..86d1923178 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.h +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.h @@ -43,9 +43,7 @@ public: // return airspeed in m/s if available virtual bool get_airspeed(float& airspeed) {return false;} -#if HAL_MSP_AIRSPEED_ENABLED virtual void handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {} -#endif protected: int8_t get_pin(void) const; diff --git a/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp b/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp index dcbfed53da..211c36e328 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp @@ -18,6 +18,9 @@ */ #include "AP_Airspeed_DLVR.h" + +#if AP_AIRSPEED_DLVR_ENABLED + #include extern const AP_HAL::HAL &hal; @@ -176,3 +179,5 @@ bool AP_Airspeed_DLVR::get_temperature(float &_temperature) _temperature = temperature; return true; } + +#endif diff --git a/libraries/AP_Airspeed/AP_Airspeed_DLVR.h b/libraries/AP_Airspeed/AP_Airspeed_DLVR.h index 806e2bfeae..2e8bd1a6b9 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DLVR.h +++ b/libraries/AP_Airspeed/AP_Airspeed_DLVR.h @@ -17,6 +17,14 @@ // backend driver for AllSensors DLVR differential airspeed sensor // currently assumes a 5" of water, noise reduced, sensor +#include + +#ifndef AP_AIRSPEED_DLVR_ENABLED +#define AP_AIRSPEED_DLVR_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_DLVR_ENABLED + #include #include #include @@ -60,3 +68,5 @@ private: AP_HAL::OwnPtr dev; }; + +#endif // AP_AIRSPEED_DLVR_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp b/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp index 7524103110..d6e4c456a3 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp @@ -18,6 +18,8 @@ */ #include "AP_Airspeed_MS4525.h" +#if AP_AIRSPEED_MS4525_ENABLED + #include #include #include @@ -282,3 +284,5 @@ bool AP_Airspeed_MS4525::get_temperature(float &temperature) temperature = _temperature; return true; } + +#endif // AP_AIRSPEED_MS4525_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS4525.h b/libraries/AP_Airspeed/AP_Airspeed_MS4525.h index be11ebf25d..64ea04fb76 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS4525.h +++ b/libraries/AP_Airspeed/AP_Airspeed_MS4525.h @@ -14,6 +14,14 @@ */ #pragma once +#include + +#ifndef AP_AIRSPEED_MS4525_ENABLED +#define AP_AIRSPEED_MS4525_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_MS4525_ENABLED + /* backend driver for airspeed from I2C */ @@ -61,3 +69,5 @@ private: bool probe(uint8_t bus, uint8_t address); }; + +#endif // AP_AIRSPEED_MS4525_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp index a23c2a8cdd..811fbbd149 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp @@ -18,6 +18,8 @@ */ #include "AP_Airspeed_MS5525.h" +#if AP_AIRSPEED_MS5525_ENABLED + #include #include @@ -298,3 +300,5 @@ bool AP_Airspeed_MS5525::get_temperature(float &_temperature) _temperature = temperature; return true; } + +#endif // AP_AIRSPEED_MS5525_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS5525.h b/libraries/AP_Airspeed/AP_Airspeed_MS5525.h index 08a2eb0379..afa7d448c4 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS5525.h +++ b/libraries/AP_Airspeed/AP_Airspeed_MS5525.h @@ -18,6 +18,14 @@ backend driver for airspeed from I2C */ +#include + +#ifndef AP_AIRSPEED_MS5525_ENABLED +#define AP_AIRSPEED_MS5525_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_MS5525_ENABLED + #include #include #include @@ -76,3 +84,5 @@ private: AP_HAL::OwnPtr dev; }; + +#endif // AP_AIRSPEED_MS5525_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp b/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp index 65a4d6ee4c..cce45fb564 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp @@ -1,6 +1,6 @@ #include "AP_Airspeed_MSP.h" -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED AP_Airspeed_MSP::AP_Airspeed_MSP(AP_Airspeed &_frontend, uint8_t _instance, uint8_t _msp_instance) : AP_Airspeed_Backend(_frontend, _instance), @@ -66,4 +66,4 @@ void AP_Airspeed_MSP::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) } -#endif // HAL_MSP_AIRSPEED_ENABLED +#endif // AP_AIRSPEED_MSP_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MSP.h b/libraries/AP_Airspeed/AP_Airspeed_MSP.h index f0bf4d590f..ac26878ee5 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MSP.h +++ b/libraries/AP_Airspeed/AP_Airspeed_MSP.h @@ -3,9 +3,17 @@ */ #pragma once -#include "AP_Airspeed_Backend.h" +#include +#include +#include -#if HAL_MSP_AIRSPEED_ENABLED +#ifndef AP_AIRSPEED_MSP_ENABLED +#define AP_AIRSPEED_MSP_ENABLED HAL_MSP_SENSORS_ENABLED +#endif + +#if AP_AIRSPEED_MSP_ENABLED + +#include "AP_Airspeed_Backend.h" class AP_Airspeed_MSP : public AP_Airspeed_Backend { @@ -32,4 +40,4 @@ private: uint8_t temp_count; }; -#endif // HAL_MSP_AIRSPEED_ENABLED +#endif // AP_AIRSPEED_MSP_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp index 18698b63a6..cac1c54727 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp @@ -18,10 +18,13 @@ * https://gpsd.gitlab.io/gpsd/NMEA.html#_mtw_mean_temperature_of_water */ +#include "AP_Airspeed_NMEA.h" + +#if AP_AIRSPEED_NMEA_ENABLED + #include #if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub) -#include "AP_Airspeed_NMEA.h" #include "AP_Airspeed.h" #define TIMEOUT_MS 2000 @@ -218,3 +221,5 @@ bool AP_Airspeed_NMEA::decode_latest_term() } #endif // APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub) + +#endif // AP_AIRSPEED_NMEA_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_NMEA.h b/libraries/AP_Airspeed/AP_Airspeed_NMEA.h index f54f2b2481..47d5ed7b6f 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_NMEA.h +++ b/libraries/AP_Airspeed/AP_Airspeed_NMEA.h @@ -1,5 +1,14 @@ #pragma once +#include + +// note additional vehicle restrictions are made in the .cpp file! +#ifndef AP_AIRSPEED_NMEA_ENABLED +#define AP_AIRSPEED_NMEA_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_NMEA_ENABLED + #include "AP_Airspeed_Backend.h" #include #include @@ -65,3 +74,5 @@ private: // time last message was received uint32_t _last_update_ms; }; + +#endif // AP_AIRSPEED_NMEA_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp index 8a1438dfc2..616e634c8a 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp @@ -19,6 +19,9 @@ with thanks to https://github.com/PX4/Firmware/blob/master/src/drivers/sdp3x_airspeed */ #include "AP_Airspeed_SDP3X.h" + +#if AP_AIRSPEED_SDP3X_ENABLED + #include #include @@ -347,3 +350,5 @@ bool AP_Airspeed_SDP3X::_crc(const uint8_t data[], uint8_t size, uint8_t checksu // verify checksum return (crc_value == checksum); } + +#endif // AP_AIRSPEED_SDP3X_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h index be761335c7..6669cd1751 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h @@ -14,6 +14,14 @@ */ #pragma once +#include + +#ifndef AP_AIRSPEED_SDP3X_ENABLED +#define AP_AIRSPEED_SDP3X_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_SDP3X_ENABLED + /* backend driver for airspeed from I2C */ @@ -63,3 +71,6 @@ private: AP_HAL::OwnPtr _dev; }; + + +#endif // AP_AIRSPEED_SDP3X_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp index 9f0300c035..ad478718c6 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp @@ -1,9 +1,7 @@ -#include - -#if HAL_ENABLE_LIBUAVCAN_DRIVERS - #include "AP_Airspeed_UAVCAN.h" +#if AP_AIRSPEED_UAVCAN_ENABLED + #include #include @@ -163,4 +161,4 @@ bool AP_Airspeed_UAVCAN::get_temperature(float &temperature) return true; } -#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS +#endif // AP_AIRSPEED_UAVCAN_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h index 828a3b2fc8..ce8b861e33 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h +++ b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h @@ -1,5 +1,13 @@ #pragma once +#include + +#ifndef AP_AIRSPEED_UAVCAN_ENABLED +#define AP_AIRSPEED_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS +#endif + +#if AP_AIRSPEED_UAVCAN_ENABLED + #include "AP_Airspeed_Backend.h" #include @@ -44,3 +52,6 @@ private: static HAL_Semaphore _sem_registry; bool _have_temperature; }; + + +#endif // AP_AIRSPEED_UAVCAN_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_analog.cpp b/libraries/AP_Airspeed/AP_Airspeed_analog.cpp index cb77817eb8..ffd29087d6 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_analog.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_analog.cpp @@ -16,11 +16,14 @@ * analog airspeed driver */ +#include "AP_Airspeed_analog.h" + +#if AP_AIRSPEED_ANALOG_ENABLED + #include #include #include "AP_Airspeed.h" -#include "AP_Airspeed_analog.h" extern const AP_HAL::HAL &hal; @@ -48,3 +51,5 @@ bool AP_Airspeed_Analog::get_differential_pressure(float &pressure) pressure = _source->voltage_average_ratiometric() * VOLTS_TO_PASCAL / get_psi_range(); return true; } + +#endif // AP_AIRSPEED_ANALOG_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_analog.h b/libraries/AP_Airspeed/AP_Airspeed_analog.h index 1131a12ec0..3ee890db48 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_analog.h +++ b/libraries/AP_Airspeed/AP_Airspeed_analog.h @@ -1,5 +1,13 @@ #pragma once +#include + +#ifndef AP_AIRSPEED_ANALOG_ENABLED +#define AP_AIRSPEED_ANALOG_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_ANALOG_ENABLED + #include #include @@ -22,3 +30,5 @@ public: private: AP_HAL::AnalogSource *_source; }; + +#endif // AP_AIRSPEED_ANALOG_ENABLED