diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 866e5b3460..3ef0db827e 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -121,10 +121,12 @@ void AP_Proximity::init() // instantiate backends uint8_t serial_instance = 0; + (void)serial_instance; // in case no serial backends are compiled in for (uint8_t instance=0; instance. */ +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_AIRSIMSITL_ENABLED + #include "AP_Proximity_AirSimSITL.h" -#if HAL_PROXIMITY_ENABLED -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL -#include -#include - -extern const AP_HAL::HAL& hal; - #define PROXIMITY_MAX_RANGE 100.0f #define PROXIMITY_ACCURACY 0.1f // minimum distance (in meters) between objects sent to object database @@ -98,6 +95,4 @@ bool AP_Proximity_AirSimSITL::get_upward_distance(float &distance) const return false; } -#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL - -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_AIRSIMSITL_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h index cf343734ff..200f534b76 100644 --- a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h +++ b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h @@ -15,11 +15,12 @@ #pragma once +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_AIRSIMSITL_ENABLED + #include "AP_Proximity_Backend.h" -#if HAL_PROXIMITY_ENABLED - -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include class AP_Proximity_AirSimSITL : public AP_Proximity_Backend @@ -44,6 +45,6 @@ private: AP_Proximity_Temp_Boundary temp_boundary; }; -#endif // CONFIG_HAL_BOARD -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_AIRSIMSITL_ENABLED + diff --git a/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.cpp b/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.cpp index 5a81f3fe4a..8d4e1959b3 100644 --- a/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.cpp @@ -1,6 +1,8 @@ -#include "AP_Proximity_Cygbot_D1.h" +#include "AP_Proximity_config.h" -#if HAL_PROXIMITY_ENABLED && AP_PROXIMITY_CYGBOT_ENABLED +#if AP_PROXIMITY_CYGBOT_ENABLED + +#include "AP_Proximity_Cygbot_D1.h" // update the state of the sensor void AP_Proximity_Cygbot_D1::update() @@ -182,4 +184,4 @@ void AP_Proximity_Cygbot_D1::reset() _temp_boundary.reset(); } -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_CYGBOT_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.h b/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.h index aaa1de91c8..e9e7bed7fa 100644 --- a/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.h +++ b/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.h @@ -1,8 +1,9 @@ #pragma once -#include "AP_Proximity.h" +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_CYGBOT_ENABLED -#if (HAL_PROXIMITY_ENABLED && AP_PROXIMITY_CYGBOT_ENABLED) #include "AP_Proximity_Backend_Serial.h" #define CYGBOT_MAX_MSG_SIZE 350 @@ -80,4 +81,4 @@ private: }; -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_CYGBOT_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp index b5b3e8265a..09f751491e 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp @@ -191,5 +191,4 @@ void AP_Proximity_DroneCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const C } } - #endif // AP_PROXIMITY_DRONECAN_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h index a5c3c731d1..deee2b77df 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h @@ -1,15 +1,13 @@ #pragma once +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_DRONECAN_ENABLED + #include "AP_Proximity_Backend.h" #include -#ifndef AP_PROXIMITY_DRONECAN_ENABLED -#define AP_PROXIMITY_DRONECAN_ENABLED (HAL_ENABLE_DRONECAN_DRIVERS && HAL_PROXIMITY_ENABLED) -#endif - -#if AP_PROXIMITY_DRONECAN_ENABLED - class AP_Proximity_DroneCAN : public AP_Proximity_Backend { public: diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp index 8204a08001..2addb7cd01 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp @@ -13,9 +13,12 @@ along with this program. If not, see . */ +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED + #include "AP_Proximity_LightWareSF40C.h" -#if HAL_PROXIMITY_ENABLED #include #include #include @@ -421,4 +424,4 @@ uint16_t AP_Proximity_LightWareSF40C::buff_to_uint16(uint8_t b0, uint8_t b1) con return leval; } -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h index 2dc00e4b88..87ae4d3f5e 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h @@ -1,8 +1,10 @@ #pragma once -#include "AP_Proximity_Backend_Serial.h" +#include "AP_Proximity_config.h" -#if HAL_PROXIMITY_ENABLED +#if AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED + +#include "AP_Proximity_Backend_Serial.h" #define PROXIMITY_SF40C_TIMEOUT_MS 200 // requests timeout after 0.2 seconds #define PROXIMITY_SF40C_PAYLOAD_LEN_MAX 256 // maximum payload size we can accept (in some configurations sensor may send as large as 1023) @@ -152,4 +154,4 @@ private: uint16_t buff_to_uint16(uint8_t b0, uint8_t b1) const; }; -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp index 79db05c6ae..47e0e28e8e 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp @@ -16,8 +16,11 @@ http://support.lightware.co.za/sf45/#/commands */ +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_LIGHTWARE_SF45B_ENABLED + #include "AP_Proximity_LightWareSF45B.h" -#if HAL_PROXIMITY_ENABLED #include #include @@ -200,4 +203,4 @@ uint8_t AP_Proximity_LightWareSF45B::convert_angle_to_minisector(float angle_deg return wrap_360(angle_deg + (PROXIMITY_SF45B_COMBINE_READINGS_DEG * 0.5f)) / PROXIMITY_SF45B_COMBINE_READINGS_DEG; } -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_LIGHTWARE_SF45B_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h index 2a3e2d2cbd..203c59bea6 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h @@ -1,8 +1,11 @@ #pragma once +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_LIGHTWARE_SF45B_ENABLED + #include "AP_Proximity_LightWareSerial.h" -#if HAL_PROXIMITY_ENABLED #include class AP_Proximity_LightWareSF45B : public AP_Proximity_LightWareSerial @@ -104,4 +107,4 @@ private: }; -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_LIGHTWARE_SF45B_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.cpp b/libraries/AP_Proximity/AP_Proximity_MAV.cpp index 254f1f36d7..0a31893e26 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.cpp +++ b/libraries/AP_Proximity/AP_Proximity_MAV.cpp @@ -13,9 +13,11 @@ along with this program. If not, see . */ -#include "AP_Proximity_MAV.h" +#include "AP_Proximity_config.h" -#if HAL_PROXIMITY_ENABLED +#if AP_PROXIMITY_MAV_ENABLED + +#include "AP_Proximity_MAV.h" #include #include #include @@ -272,4 +274,4 @@ void AP_Proximity_MAV::handle_obstacle_distance_3d_msg(const mavlink_message_t & return; } -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_MAV_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.h b/libraries/AP_Proximity/AP_Proximity_MAV.h index 7d594cf884..3ef8976fe2 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.h +++ b/libraries/AP_Proximity/AP_Proximity_MAV.h @@ -1,8 +1,10 @@ #pragma once -#include "AP_Proximity_Backend.h" +#include "AP_Proximity_config.h" -#if HAL_PROXIMITY_ENABLED +#if AP_PROXIMITY_MAV_ENABLED + +#include "AP_Proximity_Backend.h" class AP_Proximity_MAV : public AP_Proximity_Backend { @@ -46,4 +48,4 @@ private: float _distance_upward; // upward distance in meters }; -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_MAV_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp index ab3d1ad05a..26d75185a9 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp @@ -26,9 +26,12 @@ * */ +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_RPLIDARA2_ENABLED + #include "AP_Proximity_RPLidarA2.h" -#if HAL_PROXIMITY_ENABLED #include #include #include @@ -361,4 +364,4 @@ void AP_Proximity_RPLidarA2::parse_response_data() } } -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_RPLIDARA2_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h index a78d02cee5..9fd20108a3 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h @@ -29,9 +29,11 @@ #pragma once -#include "AP_Proximity_Backend_Serial.h" +#include "AP_Proximity_config.h" -#if HAL_PROXIMITY_ENABLED +#if AP_PROXIMITY_RPLIDARA2_ENABLED + +#include "AP_Proximity_Backend_Serial.h" class AP_Proximity_RPLidarA2 : public AP_Proximity_Backend_Serial { @@ -121,4 +123,4 @@ private: } payload; }; -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_RPLIDARA2_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp index ebcca88be7..4ec86b7f6e 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp @@ -13,9 +13,12 @@ along with this program. If not, see . */ +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_RANGEFINDER_ENABLED + #include "AP_Proximity_RangeFinder.h" -#if HAL_PROXIMITY_ENABLED #include #include #include @@ -94,4 +97,4 @@ bool AP_Proximity_RangeFinder::get_upward_distance(float &distance) const return false; } -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_RANGEFINDER_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.h b/libraries/AP_Proximity/AP_Proximity_RangeFinder.h index 635cc1bd29..828b3a2d73 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.h +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.h @@ -1,8 +1,10 @@ #pragma once -#include "AP_Proximity_Backend.h" +#include "AP_Proximity_config.h" -#if HAL_PROXIMITY_ENABLED +#if AP_PROXIMITY_RANGEFINDER_ENABLED + +#include "AP_Proximity_Backend.h" #define PROXIMITY_RANGEFIDER_TIMEOUT_MS 200 // requests timeout after 0.2 seconds @@ -35,4 +37,4 @@ private: float _distance_upward = -1; // upward distance in meters, negative if the last reading was out of range }; -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_RANGEFINDER_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.cpp b/libraries/AP_Proximity/AP_Proximity_SITL.cpp index f5a71de2f3..1d72a8ebed 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_SITL.cpp @@ -13,14 +13,14 @@ along with this program. If not, see . */ +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_SITL_ENABLED + #include "AP_Proximity_SITL.h" -#if HAL_PROXIMITY_ENABLED #include - -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include - #include #include @@ -135,6 +135,4 @@ bool AP_Proximity_SITL::get_upward_distance(float &distance) const return true; } -#endif // CONFIG_HAL_BOARD - -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_SITL_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.h b/libraries/AP_Proximity/AP_Proximity_SITL.h index ba85dd966d..5fbe24f6ec 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.h +++ b/libraries/AP_Proximity/AP_Proximity_SITL.h @@ -1,12 +1,13 @@ #pragma once +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_SITL_ENABLED + #include "AP_Proximity.h" -#if HAL_PROXIMITY_ENABLED #include "AP_Proximity_Backend.h" -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include -#include #include class AP_Proximity_SITL : public AP_Proximity_Backend @@ -35,6 +36,5 @@ private: bool get_distance_to_fence(float angle_deg, float &distance) const; }; -#endif // CONFIG_HAL_BOARD -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_SITL_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp index a5c2027c35..f467045035 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp @@ -13,9 +13,12 @@ along with this program. If not, see . */ +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_TERARANGERTOWER_ENABLED + #include "AP_Proximity_TeraRangerTower.h" -#if HAL_PROXIMITY_ENABLED #include #include #include @@ -109,4 +112,4 @@ void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_ _last_distance_received_ms = AP_HAL::millis(); } -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_TERARANGERTOWER_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h index 35006cad84..c060e022b6 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h @@ -1,8 +1,11 @@ #pragma once +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_TERARANGERTOWER_ENABLED + #include "AP_Proximity_Backend_Serial.h" -#if HAL_PROXIMITY_ENABLED #define PROXIMITY_TRTOWER_TIMEOUT_MS 300 // requests timeout after 0.3 seconds class AP_Proximity_TeraRangerTower : public AP_Proximity_Backend_Serial @@ -33,4 +36,4 @@ private: uint32_t _last_distance_received_ms; // system time of last distance measurement received from sensor }; -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_TERARANGERTOWER_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp index db527417df..476d47415a 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp @@ -13,10 +13,13 @@ along with this program. If not, see . */ +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_TERARANGERTOWEREVO_ENABLED + #include #include "AP_Proximity_TeraRangerTowerEvo.h" -#if HAL_PROXIMITY_ENABLED #include #include #include @@ -164,4 +167,4 @@ void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint _last_distance_received_ms = AP_HAL::millis(); } -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_TERARANGERTOWEREVO_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h index 4b12d3fab6..5804344636 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h @@ -1,8 +1,11 @@ #pragma once +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_TERARANGERTOWEREVO_ENABLED + #include "AP_Proximity.h" -#if HAL_PROXIMITY_ENABLED #include "AP_Proximity_Backend_Serial.h" #define PROXIMITY_TRTOWER_TIMEOUT_MS 300 // requests timeout after 0.3 seconds @@ -59,4 +62,4 @@ private: // const uint8_t REFRESH_600_HZ[5] = { (uint8_t)0x00, (uint8_t)0x52, (uint8_t)0x03, (uint8_t)0x06, (uint8_t)0xDF}; }; -#endif // HAL_PROXIMITY_ENABLED +#endif // AP_PROXIMITY_TERARANGERTOWEREVO_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_config.h b/libraries/AP_Proximity/AP_Proximity_config.h index c6ca9e0291..e34f3dd306 100644 --- a/libraries/AP_Proximity/AP_Proximity_config.h +++ b/libraries/AP_Proximity/AP_Proximity_config.h @@ -1,11 +1,57 @@ #pragma once #include +#include +#include #ifndef HAL_PROXIMITY_ENABLED #define HAL_PROXIMITY_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) #endif -#ifndef AP_PROXIMITY_CYGBOT_ENABLED -#define AP_PROXIMITY_CYGBOT_ENABLED HAL_PROXIMITY_ENABLED +#ifndef AP_PROXIMITY_BACKEND_DEFAULT_ENABLED +#define AP_PROXIMITY_BACKEND_DEFAULT_ENABLED HAL_PROXIMITY_ENABLED +#endif + +#ifndef AP_PROXIMITY_AIRSIMSITL_ENABLED +#define AP_PROXIMITY_AIRSIMSITL_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#ifndef AP_PROXIMITY_CYGBOT_ENABLED +#define AP_PROXIMITY_CYGBOT_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_PROXIMITY_DRONECAN_ENABLED +#define AP_PROXIMITY_DRONECAN_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS +#endif + +#ifndef AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED +#define AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_PROXIMITY_LIGHTWARE_SF45B_ENABLED +#define AP_PROXIMITY_LIGHTWARE_SF45B_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_PROXIMITY_MAV_ENABLED +#define AP_PROXIMITY_MAV_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED +#endif + +#ifndef AP_PROXIMITY_RANGEFINDER_ENABLED +#define AP_PROXIMITY_RANGEFINDER_ENABLED AP_RANGEFINDER_ENABLED && AP_PROXIMITY_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_PROXIMITY_RPLIDARA2_ENABLED +#define AP_PROXIMITY_RPLIDARA2_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_PROXIMITY_SITL_ENABLED +#define AP_PROXIMITY_SITL_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#ifndef AP_PROXIMITY_TERARANGERTOWER_ENABLED +#define AP_PROXIMITY_TERARANGERTOWER_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_PROXIMITY_TERARANGERTOWEREVO_ENABLED +#define AP_PROXIMITY_TERARANGERTOWEREVO_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED #endif