diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index 9ed6d10d1e..7d3b252feb 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -41,10 +41,6 @@ #define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 50 #endif -#ifndef HAL_MSP_RANGEFINDER_ENABLED -#define HAL_MSP_RANGEFINDER_ENABLED HAL_MSP_ENABLED -#endif - class AP_RangeFinder_Backend; class RangeFinder diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h index a52f042f77..f60ea1d023 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h @@ -1,14 +1,11 @@ #pragma once -#include "AP_RangeFinder.h" - -#ifndef AP_RANGEFINDER_BENEWAKE_ENABLED -#define AP_RANGEFINDER_BENEWAKE_ENABLED AP_RANGEFINDER_ENABLED -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_BENEWAKE_ENABLED #include "AP_RangeFinder_Backend_Serial.h" +#include "AP_RangeFinder.h" class AP_RangeFinder_Benewake : public AP_RangeFinder_Backend_Serial { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h index 7075598e33..7830ab99b0 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h @@ -1,15 +1,12 @@ #pragma once -#include "AP_RangeFinder_Backend.h" - -#include - -#ifndef AP_RANGEFINDER_BENEWAKE_CAN_ENABLED -#define AP_RANGEFINDER_BENEWAKE_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED +#include "AP_RangeFinder_Backend.h" +#include + class Benewake_MultiCAN; class AP_RangeFinder_Benewake_CAN : public AP_RangeFinder_Backend { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h index 207eed4f27..f6b62d4ac2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h @@ -1,13 +1,11 @@ #pragma once -#include "AP_RangeFinder_Benewake.h" - -#ifndef AP_RANGEFINDER_BENEWAKE_TF02_ENABLED -#define AP_RANGEFINDER_BENEWAKE_TF02_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED +#include "AP_RangeFinder_Benewake.h" + class AP_RangeFinder_Benewake_TF02 : public AP_RangeFinder_Benewake { public: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h index 8353307fc3..2e2318ae22 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h @@ -1,13 +1,11 @@ #pragma once -#include "AP_RangeFinder_Benewake.h" - -#ifndef AP_RANGEFINDER_BENEWAKE_TF03_ENABLED -#define AP_RANGEFINDER_BENEWAKE_TF03_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED +#include "AP_RangeFinder_Benewake.h" + class AP_RangeFinder_Benewake_TF03 : public AP_RangeFinder_Benewake { public: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h index 1116f748a6..451cdfe525 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h @@ -1,13 +1,11 @@ #pragma once -#include "AP_RangeFinder_Benewake.h" - -#ifndef AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED -#define AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED +#include "AP_RangeFinder_Benewake.h" + class AP_RangeFinder_Benewake_TFMini : public AP_RangeFinder_Benewake { public: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.h index b3cd7e6a51..8a874c710a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.h @@ -16,15 +16,13 @@ */ #pragma once -#include "AP_RangeFinder.h" -#include "AP_RangeFinder_Backend.h" - -#ifndef AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED -#define AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED +#include "AP_RangeFinder.h" +#include "AP_RangeFinder_Backend.h" + #define TFMINIPLUS_ADDR_DEFAULT 0x10 // TFMini default device id #include diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h index 62b01782de..6d763b2b97 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h @@ -1,13 +1,10 @@ #pragma once -#include "AP_RangeFinder_Backend.h" - -#ifndef AP_RANGEFINDER_DRONECAN_ENABLED -#define AP_RANGEFINDER_DRONECAN_ENABLED (HAL_ENABLE_DRONECAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_DRONECAN_ENABLED +#include "AP_RangeFinder_Backend.h" #include class MeasurementCb; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h index 8e0d9281d3..7347e649e1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h @@ -1,13 +1,10 @@ #pragma once -#include "AP_RangeFinder.h" - -#ifndef AP_RANGEFINDER_GYUS42V2_ENABLED -#define AP_RANGEFINDER_GYUS42V2_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_GYUS42V2_ENABLED +#include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" class AP_RangeFinder_GYUS42v2 : public AP_RangeFinder_Backend_Serial diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.h b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.h index 5ef460f6bb..0c582e5bfc 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_HC_SR04_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" -#ifndef AP_RANGEFINDER_HC_SR04_ENABLED -#define AP_RANGEFINDER_HC_SR04_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_HC_SR04_ENABLED - #include "AP_RangeFinder_Params.h" class AP_RangeFinder_HC_SR04 : public AP_RangeFinder_Backend diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h index d65b607c8a..0a655c5183 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_LANBAO_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" -#ifndef AP_RANGEFINDER_LANBAO_ENABLED -#define AP_RANGEFINDER_LANBAO_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_LANBAO_ENABLED - class AP_RangeFinder_Lanbao : public AP_RangeFinder_Backend_Serial { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h index 8d5d96686a..43ee3f09ba 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_LEDDARONE_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" -#ifndef AP_RANGEFINDER_LEDDARONE_ENABLED -#define AP_RANGEFINDER_LEDDARONE_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_LEDDARONE_ENABLED - // defines #define LEDDARONE_DEFAULT_ADDRESS 0x01 #define LEDDARONE_MODOBUS_FUNCTION_CODE 0x04 diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h index f4492557da..68db11394e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_LEDDARVU8_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" -#ifndef AP_RANGEFINDER_LEDDARVU8_ENABLED -#define AP_RANGEFINDER_LEDDARVU8_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_LEDDARVU8_ENABLED - #define LEDDARVU8_PAYLOAD_LENGTH (8*2) class AP_RangeFinder_LeddarVu8 : public AP_RangeFinder_Backend_Serial diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h index ebc5e760ce..ab15b6a9e5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_LWI2C_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" -#ifndef AP_RANGEFINDER_LWI2C_ENABLED -#define AP_RANGEFINDER_LWI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_LWI2C_ENABLED - #include #define NUM_SF20_DATA_STREAMS 1 diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h index a5fb37f356..17b5ef46ea 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" -#ifndef AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED -#define AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED - class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend_Serial { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h index 94a3e63373..b38c6fcc49 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_MAVLINK_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" -#ifndef AP_RANGEFINDER_MAVLINK_ENABLED -#define AP_RANGEFINDER_MAVLINK_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_MAVLINK_ENABLED - // Data timeout #define AP_RANGEFINDER_MAVLINK_TIMEOUT_MS 500 diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h index 325c3d63d7..59643fe696 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h @@ -1,10 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if HAL_MSP_RANGEFINDER_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" -#if HAL_MSP_RANGEFINDER_ENABLED - // Data timeout #define AP_RANGEFINDER_MSP_TIMEOUT_MS 500 diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h index 7cae78c326..7648133963 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" -#ifndef AP_RANGEFINDER_MAXSONARI2CXL_ENABLED -#define AP_RANGEFINDER_MAXSONARI2CXL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED - #include #define AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR 0x70 diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h index 041d74c933..b0693c11e3 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" -#ifndef AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED -#define AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED - class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend_Serial { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h index 8f9cf0406a..d8c7ff3d14 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h @@ -15,15 +15,13 @@ #pragma once -#include "AP_RangeFinder.h" -#include "AP_RangeFinder_Backend_Serial.h" - -#ifndef AP_RANGEFINDER_NMEA_ENABLED -#define AP_RANGEFINDER_NMEA_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_NMEA_ENABLED +#include "AP_RangeFinder.h" +#include "AP_RangeFinder_Backend_Serial.h" + class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend_Serial { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h b/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h index deaeb96a4d..e40fe11dd6 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.h @@ -1,13 +1,10 @@ #pragma once -#include "AP_RangeFinder.h" - -#ifndef AP_RANGEFINDER_NOOPLOOP_ENABLED -#define AP_RANGEFINDER_NOOPLOOP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024 -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_NOOPLOOP_ENABLED +#include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" class AP_RangeFinder_NoopLoop : public AP_RangeFinder_Backend_Serial diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.h b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.h index 597861d1d0..60cd5e56a7 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.h @@ -14,17 +14,13 @@ */ #pragma once -#include "AP_RangeFinder.h" -#include "AP_RangeFinder_Backend.h" - -#ifndef AP_RANGEFINDER_PWM_ENABLED -#define AP_RANGEFINDER_PWM_ENABLED \ - (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && \ - AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_PWM_ENABLED +#include "AP_RangeFinder.h" +#include "AP_RangeFinder_Backend.h" + class AP_RangeFinder_PWM : public AP_RangeFinder_Backend { public: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h index 8f6d40e200..650c440809 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" -#ifndef AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED -#define AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED - #include /* Connection diagram diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h index 09bdb5f0a7..18e7c0ed64 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_TRI2C_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" -#ifndef AP_RANGEFINDER_TRI2C_ENABLED -#define AP_RANGEFINDER_TRI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_TRI2C_ENABLED - #include class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h index 6840849e07..aba2d08df8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" -#ifndef AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED -#define AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED - class AP_RangeFinder_TeraRanger_Serial : public AP_RangeFinder_Backend_Serial { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h index 2d38a4c498..4ca6890fbe 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_USD1_CAN_ENABLED + #include "AP_RangeFinder_Backend.h" #include -#ifndef AP_RANGEFINDER_USD1_CAN_ENABLED -#define AP_RANGEFINDER_USD1_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) -#endif - -#if AP_RANGEFINDER_USD1_CAN_ENABLED - class USD1_MultiCAN; class AP_RangeFinder_USD1_CAN : public AP_RangeFinder_Backend { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h index 9ffa4f96e5..98a77d5b0f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h @@ -1,15 +1,13 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_VL53L0X_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" #include -#ifndef AP_RANGEFINDER_VL53L0X_ENABLED -#define AP_RANGEFINDER_VL53L0X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_VL53L0X_ENABLED - class AP_RangeFinder_VL53L0X : public AP_RangeFinder_Backend { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h index f073781d4c..037a320d39 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_VL53L1X_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" -#ifndef AP_RANGEFINDER_VL53L1X_ENABLED -#define AP_RANGEFINDER_VL53L1X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_VL53L1X_ENABLED - #include class AP_RangeFinder_VL53L1X : public AP_RangeFinder_Backend diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h index 876e0cd41a..e0a3e15ca2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h @@ -1,14 +1,12 @@ #pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_WASP_ENABLED + #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" -#ifndef AP_RANGEFINDER_WASP_ENABLED -#define AP_RANGEFINDER_WASP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_RANGEFINDER_WASP_ENABLED - // WASP 200 LRF // http://www.attolloengineering.com/wasp-200-lrf.html diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_config.h b/libraries/AP_RangeFinder/AP_RangeFinder_config.h index bb51ee21bf..ed10e44160 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_config.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_config.h @@ -2,6 +2,8 @@ #include #include +#include +#include #ifndef AP_RANGEFINDER_ENABLED #define AP_RANGEFINDER_ENABLED 1 @@ -22,6 +24,30 @@ ) #endif +#ifndef AP_RANGEFINDER_BENEWAKE_ENABLED +#define AP_RANGEFINDER_BENEWAKE_ENABLED AP_RANGEFINDER_ENABLED +#endif + +#ifndef AP_RANGEFINDER_BENEWAKE_CAN_ENABLED +#define AP_RANGEFINDER_BENEWAKE_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#ifndef AP_RANGEFINDER_BENEWAKE_TF02_ENABLED +#define AP_RANGEFINDER_BENEWAKE_TF02_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#ifndef AP_RANGEFINDER_BENEWAKE_TF03_ENABLED +#define AP_RANGEFINDER_BENEWAKE_TF03_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#ifndef AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED +#define AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#ifndef AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED +#define AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + #ifndef AP_RANGEFINDER_BLPING_ENABLED #define AP_RANGEFINDER_BLPING_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED #endif @@ -34,10 +60,98 @@ defined(HAVE_LIBIIO) #endif +#ifndef AP_RANGEFINDER_DRONECAN_ENABLED +#define AP_RANGEFINDER_DRONECAN_ENABLED (HAL_ENABLE_DRONECAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#ifndef AP_RANGEFINDER_GYUS42V2_ENABLED +#define AP_RANGEFINDER_GYUS42V2_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_HC_SR04_ENABLED +#define AP_RANGEFINDER_HC_SR04_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_LANBAO_ENABLED +#define AP_RANGEFINDER_LANBAO_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_LEDDARONE_ENABLED +#define AP_RANGEFINDER_LEDDARONE_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_LEDDARVU8_ENABLED +#define AP_RANGEFINDER_LEDDARVU8_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_LWI2C_ENABLED +#define AP_RANGEFINDER_LWI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED +#define AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + #ifndef AP_RANGEFINDER_LUA_ENABLED #define AP_RANGEFINDER_LUA_ENABLED AP_SCRIPTING_ENABLED #endif +#ifndef AP_RANGEFINDER_MAVLINK_ENABLED +#define AP_RANGEFINDER_MAVLINK_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED +#define AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_MAXSONARI2CXL_ENABLED +#define AP_RANGEFINDER_MAXSONARI2CXL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef HAL_MSP_RANGEFINDER_ENABLED +#define HAL_MSP_RANGEFINDER_ENABLED HAL_MSP_ENABLED +#endif + +#ifndef AP_RANGEFINDER_NMEA_ENABLED +#define AP_RANGEFINDER_NMEA_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_NOOPLOOP_ENABLED +#define AP_RANGEFINDER_NOOPLOOP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024 +#endif + +#ifndef AP_RANGEFINDER_PWM_ENABLED +#define AP_RANGEFINDER_PWM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#ifndef AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED +#define AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + #ifndef AP_RANGEFINDER_SIM_ENABLED #define AP_RANGEFINDER_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) #endif + +#ifndef AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED +#define AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_TRI2C_ENABLED +#define AP_RANGEFINDER_TRI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_USD1_CAN_ENABLED +#define AP_RANGEFINDER_USD1_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#ifndef AP_RANGEFINDER_VL53L0X_ENABLED +#define AP_RANGEFINDER_VL53L0X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_VL53L1X_ENABLED +#define AP_RANGEFINDER_VL53L1X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_RANGEFINDER_WASP_ENABLED +#define AP_RANGEFINDER_WASP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif