From 1fad5d46e79fce441b4613bf3a6db23d19fdc0f5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 25 Mar 2021 16:32:09 +0900 Subject: [PATCH] AP_Proximity: add #if HAL_PROXIMITY_ENABLED --- libraries/AP_Proximity/AP_Proximity.cpp | 4 ++++ libraries/AP_Proximity/AP_Proximity.h | 12 ++++++++++- .../AP_Proximity/AP_Proximity_AirSimSITL.cpp | 10 ++++++--- .../AP_Proximity/AP_Proximity_AirSimSITL.h | 5 ++++- .../AP_Proximity/AP_Proximity_Backend.cpp | 8 ++++--- libraries/AP_Proximity/AP_Proximity_Backend.h | 8 +++++-- .../AP_Proximity_Backend_Serial.cpp | 2 ++ .../AP_Proximity_Backend_Serial.h | 5 ++++- .../AP_Proximity/AP_Proximity_Boundary_3D.cpp | 21 ++++++++++++++++++- .../AP_Proximity/AP_Proximity_Boundary_3D.h | 5 +++++ .../AP_Proximity_LightWareSF40C.cpp | 6 +++++- .../AP_Proximity_LightWareSF40C.h | 5 ++++- .../AP_Proximity_LightWareSF40C_v09.cpp | 6 +++++- .../AP_Proximity_LightWareSF40C_v09.h | 4 +++- .../AP_Proximity_LightWareSF45B.cpp | 6 +++++- .../AP_Proximity_LightWareSF45B.h | 7 +++++-- .../AP_Proximity_LightWareSerial.cpp | 6 +++++- .../AP_Proximity_LightWareSerial.h | 4 +++- libraries/AP_Proximity/AP_Proximity_MAV.cpp | 6 +++++- libraries/AP_Proximity/AP_Proximity_MAV.h | 5 ++++- .../AP_Proximity/AP_Proximity_RPLidarA2.cpp | 6 +++++- .../AP_Proximity/AP_Proximity_RPLidarA2.h | 5 +++-- .../AP_Proximity/AP_Proximity_RangeFinder.cpp | 6 +++++- .../AP_Proximity/AP_Proximity_RangeFinder.h | 5 ++++- libraries/AP_Proximity/AP_Proximity_SITL.cpp | 7 ++++++- libraries/AP_Proximity/AP_Proximity_SITL.h | 4 ++++ .../AP_Proximity_TeraRangerTower.cpp | 6 +++++- .../AP_Proximity_TeraRangerTower.h | 4 +++- .../AP_Proximity_TeraRangerTowerEvo.cpp | 4 ++++ .../AP_Proximity_TeraRangerTowerEvo.h | 4 ++++ 30 files changed, 155 insertions(+), 31 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index d86424dc2d..3e596d8442 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -14,6 +14,8 @@ */ #include "AP_Proximity.h" + +#if HAL_PROXIMITY_ENABLED #include "AP_Proximity_LightWareSF40C_v09.h" #include "AP_Proximity_RPLidarA2.h" #include "AP_Proximity_TeraRangerTower.h" @@ -502,3 +504,5 @@ AP_Proximity *proximity() } } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity.h b/libraries/AP_Proximity/AP_Proximity.h index 8c43fea494..17d46f4155 100644 --- a/libraries/AP_Proximity/AP_Proximity.h +++ b/libraries/AP_Proximity/AP_Proximity.h @@ -14,8 +14,16 @@ */ #pragma once -#include #include +#include + +#ifndef HAL_PROXIMITY_ENABLED +#define HAL_PROXIMITY_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) +#endif + +#if HAL_PROXIMITY_ENABLED + +#include #include #include #include @@ -187,3 +195,5 @@ private: namespace AP { AP_Proximity *proximity(); }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp index 9f8434b791..d7b42649ab 100644 --- a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp @@ -13,9 +13,11 @@ along with this program. If not, see . */ -#include -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include "AP_Proximity_AirSimSITL.h" + +#if HAL_PROXIMITY_ENABLED +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include #include extern const AP_HAL::HAL& hal; @@ -93,4 +95,6 @@ bool AP_Proximity_AirSimSITL::get_upward_distance(float &distance) const return false; } -#endif // CONFIG_HAL_BOARD +#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h index b4163049d8..495bb785a1 100644 --- a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h +++ b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h @@ -15,9 +15,10 @@ #pragma once -#include "AP_Proximity.h" #include "AP_Proximity_Backend.h" +#if HAL_PROXIMITY_ENABLED + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include @@ -43,3 +44,5 @@ private: }; #endif // CONFIG_HAL_BOARD + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Backend.cpp b/libraries/AP_Proximity/AP_Proximity_Backend.cpp index ac2395b8c4..6ba7858803 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Backend.cpp @@ -13,14 +13,14 @@ along with this program. If not, see . */ +#include "AP_Proximity_Backend.h" + +#if HAL_PROXIMITY_ENABLED #include #include #include #include #include -#include "AP_Proximity.h" -#include "AP_Proximity_Backend.h" -#include extern const AP_HAL::HAL& hal; @@ -205,3 +205,5 @@ void AP_Proximity_Backend::database_push(float angle, float pitch, float distanc oaDb->queue_push(temp_pos, timestamp_ms, distance); } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Backend.h b/libraries/AP_Proximity/AP_Proximity_Backend.h index 931da06894..cddfe43f46 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend.h +++ b/libraries/AP_Proximity/AP_Proximity_Backend.h @@ -14,9 +14,11 @@ */ #pragma once -#include -#include #include "AP_Proximity.h" + +#if HAL_PROXIMITY_ENABLED +#include +#include #include #include "AP_Proximity_Boundary_3D.h" @@ -118,3 +120,5 @@ protected: // Methods to manipulate 3D boundary in this class AP_Proximity_Boundary_3D boundary; }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Backend_Serial.cpp b/libraries/AP_Proximity/AP_Proximity_Backend_Serial.cpp index cc7b3cdc2c..f328f24110 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend_Serial.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Backend_Serial.cpp @@ -15,6 +15,7 @@ #include "AP_Proximity_Backend_Serial.h" +#if HAL_PROXIMITY_ENABLED #include /* @@ -41,3 +42,4 @@ bool AP_Proximity_Backend_Serial::detect() return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0) != nullptr; } +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Backend_Serial.h b/libraries/AP_Proximity/AP_Proximity_Backend_Serial.h index 6e31677adb..af05334509 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend_Serial.h +++ b/libraries/AP_Proximity/AP_Proximity_Backend_Serial.h @@ -1,8 +1,9 @@ #pragma once -#include "AP_Proximity.h" #include "AP_Proximity_Backend.h" +#if HAL_PROXIMITY_ENABLED + class AP_Proximity_Backend_Serial : public AP_Proximity_Backend { public: @@ -16,3 +17,5 @@ protected: AP_HAL::UARTDriver *_uart; // uart for communicating with sensor }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Boundary_3D.cpp b/libraries/AP_Proximity/AP_Proximity_Boundary_3D.cpp index d6519d64fc..2935dc2870 100644 --- a/libraries/AP_Proximity/AP_Proximity_Boundary_3D.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Boundary_3D.cpp @@ -1,6 +1,23 @@ -#include "AP_Proximity_Backend.h" +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + #include "AP_Proximity_Boundary_3D.h" +#if HAL_PROXIMITY_ENABLED +#include "AP_Proximity_Backend.h" + /* Constructor. This incorporates initialisation as well. @@ -357,3 +374,5 @@ bool AP_Proximity_Boundary_3D::get_layer_distances(uint8_t layer_number, float d return valid_distances; } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Boundary_3D.h b/libraries/AP_Proximity/AP_Proximity_Boundary_3D.h index 4137e0fdb8..95a72e3c14 100644 --- a/libraries/AP_Proximity/AP_Proximity_Boundary_3D.h +++ b/libraries/AP_Proximity/AP_Proximity_Boundary_3D.h @@ -15,6 +15,10 @@ #pragma once +#include "AP_Proximity.h" + +#if HAL_PROXIMITY_ENABLED + #include #define PROXIMITY_NUM_SECTORS 8 // number of sectors @@ -156,3 +160,4 @@ private: LowPassFilterFloat _filtered_distance[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // low pass filter }; +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp index 40150b6cb6..a7fe1e5c06 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp @@ -13,11 +13,13 @@ along with this program. If not, see . */ +#include "AP_Proximity_LightWareSF40C.h" + +#if HAL_PROXIMITY_ENABLED #include #include #include #include -#include "AP_Proximity_LightWareSF40C.h" extern const AP_HAL::HAL& hal; @@ -418,3 +420,5 @@ uint16_t AP_Proximity_LightWareSF40C::buff_to_uint16(uint8_t b0, uint8_t b1) con uint16_t leval = (uint16_t)b0 | (uint16_t)b1 << 8; return leval; } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h index 4a3f0ce9c0..2dc00e4b88 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h @@ -1,8 +1,9 @@ #pragma once -#include "AP_Proximity.h" #include "AP_Proximity_Backend_Serial.h" +#if HAL_PROXIMITY_ENABLED + #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) #define PROXIMITY_SF40C_COMBINE_READINGS 7 // combine this many readings together to improve efficiency @@ -150,3 +151,5 @@ private: uint32_t buff_to_uint32(uint8_t b0, uint8_t b1, uint8_t b2, uint8_t b3) const; uint16_t buff_to_uint16(uint8_t b0, uint8_t b1) const; }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C_v09.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C_v09.cpp index c8183dc5c1..e2d5860421 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C_v09.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C_v09.cpp @@ -13,8 +13,10 @@ along with this program. If not, see . */ -#include #include "AP_Proximity_LightWareSF40C_v09.h" + +#if HAL_PROXIMITY_ENABLED +#include #include #include @@ -360,3 +362,5 @@ void AP_Proximity_LightWareSF40C_v09::clear_buffers() element_num = 0; memset(element_buf, 0, sizeof(element_buf)); } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C_v09.h b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C_v09.h index 088ad7e39f..dcde3644d1 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C_v09.h +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C_v09.h @@ -1,8 +1,8 @@ #pragma once -#include "AP_Proximity.h" #include "AP_Proximity_Backend_Serial.h" +#if HAL_PROXIMITY_ENABLED #define PROXIMITY_SF40C_TIMEOUT_MS 200 // requests timeout after 0.2 seconds class AP_Proximity_LightWareSF40C_v09 : public AP_Proximity_Backend_Serial @@ -88,3 +88,5 @@ private: uint8_t _motor_direction = 99; // motor direction as reported by lidar int16_t _forward_direction = 999; // forward direction as reported by lidar }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp index 06c1968af3..6359de85df 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp @@ -16,10 +16,12 @@ http://support.lightware.co.za/sf45/#/commands */ +#include "AP_Proximity_LightWareSF45B.h" +#if HAL_PROXIMITY_ENABLED + #include #include #include -#include "AP_Proximity_LightWareSF45B.h" extern const AP_HAL::HAL& hal; @@ -197,3 +199,5 @@ 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 diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h index 725c3e6af6..8438126d24 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h @@ -1,9 +1,10 @@ #pragma once -#include -#include "AP_Proximity.h" #include "AP_Proximity_LightWareSerial.h" +#if HAL_PROXIMITY_ENABLED +#include + class AP_Proximity_LightWareSF45B : public AP_Proximity_LightWareSerial { @@ -100,3 +101,5 @@ private: } _sensor_state; }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSerial.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSerial.cpp index 22b8a0664e..72f4c08329 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSerial.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSerial.cpp @@ -13,11 +13,13 @@ along with this program. If not, see . */ +#include "AP_Proximity_LightWareSerial.h" + +#if HAL_PROXIMITY_ENABLED #include #include #include #include -#include "AP_Proximity_LightWareSerial.h" #include extern const AP_HAL::HAL& hal; @@ -138,3 +140,5 @@ bool AP_Proximity_LightWareSerial::parse_byte(uint8_t b) return false; } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSerial.h b/libraries/AP_Proximity/AP_Proximity_LightWareSerial.h index 936bf2cddd..f8da7dfa26 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSerial.h +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSerial.h @@ -1,8 +1,8 @@ #pragma once -#include "AP_Proximity.h" #include "AP_Proximity_Backend_Serial.h" +#if HAL_PROXIMITY_ENABLED #define PROXIMITY_LIGHTWARE_PAYLOAD_LEN_MAX 256 // maximum payload size we can accept (in some configurations sensor may send as large as 1023) class AP_Proximity_LightWareSerial : public AP_Proximity_Backend_Serial @@ -48,3 +48,5 @@ protected: uint8_t crc_high; // crc high byte } _msg; }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.cpp b/libraries/AP_Proximity/AP_Proximity_MAV.cpp index fadb0c6eb6..2982be7d0b 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.cpp +++ b/libraries/AP_Proximity/AP_Proximity_MAV.cpp @@ -13,8 +13,10 @@ along with this program. If not, see . */ -#include #include "AP_Proximity_MAV.h" + +#if HAL_PROXIMITY_ENABLED +#include #include #include @@ -261,3 +263,5 @@ void AP_Proximity_MAV::handle_obstacle_distance_3d_msg(const mavlink_message_t & } return; } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.h b/libraries/AP_Proximity/AP_Proximity_MAV.h index 13f80a2e63..97482d5f9d 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.h +++ b/libraries/AP_Proximity/AP_Proximity_MAV.h @@ -1,8 +1,9 @@ #pragma once -#include "AP_Proximity.h" #include "AP_Proximity_Backend.h" +#if HAL_PROXIMITY_ENABLED + class AP_Proximity_MAV : public AP_Proximity_Backend { @@ -42,3 +43,5 @@ private: uint32_t _last_upward_update_ms; // system time of last update of upward distance float _distance_upward; // upward distance in meters }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp index 0447e3846d..9d2aa1dc70 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp @@ -26,8 +26,10 @@ * */ -#include #include "AP_Proximity_RPLidarA2.h" + +#if HAL_PROXIMITY_ENABLED +#include #include #include @@ -358,3 +360,5 @@ void AP_Proximity_RPLidarA2::parse_response_data() break; } } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h index c512f2b367..a78d02cee5 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h @@ -29,10 +29,9 @@ #pragma once -#include "AP_Proximity.h" #include "AP_Proximity_Backend_Serial.h" -#include ///< for UARTDriver +#if HAL_PROXIMITY_ENABLED class AP_Proximity_RPLidarA2 : public AP_Proximity_Backend_Serial { @@ -121,3 +120,5 @@ private: _sensor_health sensor_health; } payload; }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp index 8abf802a95..c3e310a75f 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp @@ -13,8 +13,10 @@ along with this program. If not, see . */ -#include #include "AP_Proximity_RangeFinder.h" + +#if HAL_PROXIMITY_ENABLED +#include #include #include #include @@ -90,3 +92,5 @@ bool AP_Proximity_RangeFinder::get_upward_distance(float &distance) const } return false; } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.h b/libraries/AP_Proximity/AP_Proximity_RangeFinder.h index e624f0c70e..635cc1bd29 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.h +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.h @@ -1,8 +1,9 @@ #pragma once -#include "AP_Proximity.h" #include "AP_Proximity_Backend.h" +#if HAL_PROXIMITY_ENABLED + #define PROXIMITY_RANGEFIDER_TIMEOUT_MS 200 // requests timeout after 0.2 seconds class AP_Proximity_RangeFinder : public AP_Proximity_Backend @@ -33,3 +34,5 @@ private: uint32_t _last_upward_update_ms; // system time of last update distance float _distance_upward = -1; // upward distance in meters, negative if the last reading was out of range }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.cpp b/libraries/AP_Proximity/AP_Proximity_SITL.cpp index 4e5f2e42da..07e77f45c9 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_SITL.cpp @@ -13,11 +13,14 @@ along with this program. If not, see . */ +#include "AP_Proximity_SITL.h" +#if HAL_PROXIMITY_ENABLED #include + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include -#include "AP_Proximity_SITL.h" + #include #include @@ -124,3 +127,5 @@ bool AP_Proximity_SITL::get_upward_distance(float &distance) const } #endif // CONFIG_HAL_BOARD + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.h b/libraries/AP_Proximity/AP_Proximity_SITL.h index bad2cc7d2f..6909a6b4fd 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.h +++ b/libraries/AP_Proximity/AP_Proximity_SITL.h @@ -1,6 +1,8 @@ #pragma once #include "AP_Proximity.h" + +#if HAL_PROXIMITY_ENABLED #include "AP_Proximity_Backend.h" #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include @@ -37,3 +39,5 @@ private: }; #endif // CONFIG_HAL_BOARD + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp index 3ab05383d8..aad39b6cca 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp @@ -13,8 +13,10 @@ along with this program. If not, see . */ -#include #include "AP_Proximity_TeraRangerTower.h" + +#if HAL_PROXIMITY_ENABLED +#include #include #include #include @@ -103,3 +105,5 @@ void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_ } _last_distance_received_ms = AP_HAL::millis(); } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h index 5728504477..bcbd40baad 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h @@ -1,8 +1,8 @@ #pragma once -#include "AP_Proximity.h" #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 @@ -32,3 +32,5 @@ private: // request related variables uint32_t _last_distance_received_ms; // system time of last distance measurement received from sensor }; + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp index d56bc2889f..3f6e985534 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp @@ -15,6 +15,8 @@ #include #include "AP_Proximity_TeraRangerTowerEvo.h" + +#if HAL_PROXIMITY_ENABLED #include #include #include @@ -158,3 +160,5 @@ void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint } _last_distance_received_ms = AP_HAL::millis(); } + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h index 6412bbcf03..59261bf15e 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h @@ -1,6 +1,8 @@ #pragma once #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 @@ -56,3 +58,5 @@ private: // const uint8_t REFRESH_500_HZ[5] = { (uint8_t)0x00, (uint8_t)0x52, (uint8_t)0x03, (uint8_t)0x05, (uint8_t)0xD6}; // 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