From 34430e9d6c5f65a04c1cae9a90512917b53dd085 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 1 Sep 2020 17:54:29 +1000 Subject: [PATCH] AP_RangeFinder: allow separate enable of MSP rangefinder --- libraries/AP_RangeFinder/AP_RangeFinder.h | 2 +- libraries/AP_RangeFinder/AP_RangeFinder_Backend.h | 2 +- libraries/AP_RangeFinder/AP_RangeFinder_MSP.cpp | 5 +++-- libraries/AP_RangeFinder/AP_RangeFinder_MSP.h | 5 +++-- 4 files changed, 8 insertions(+), 6 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index 5bc059712d..7cbbaebd21 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -143,7 +143,7 @@ public: #if HAL_MSP_RANGEFINDER_ENABLED // Handle an incoming DISTANCE_SENSOR message (from a MSP enabled range finder) void handle_msp(const MSP::msp_rangefinder_sensor_t &pkt); -#endif //HAL_MSP_RANGEFINDER_ENABLED +#endif // return true if we have a range finder with the specified orientation bool has_orientation(enum Rotation orientation) const; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h index c4d65b922d..195af797d7 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h @@ -32,7 +32,7 @@ public: virtual void update() = 0; virtual void handle_msg(const mavlink_message_t &msg) { return; } -#if HAL_MSP_ENABLED +#if HAL_MSP_RANGEFINDER_ENABLED virtual void handle_msp(const MSP::msp_rangefinder_sensor_t &pkt) { return; } #endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.cpp index 2d735edc6b..e47579ff8f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.cpp @@ -16,7 +16,7 @@ #include "AP_RangeFinder_MSP.h" #include -#if HAL_MSP_ENABLED +#if HAL_MSP_RANGEFINDER_ENABLED extern const AP_HAL::HAL& hal; @@ -68,4 +68,5 @@ void AP_RangeFinder_MSP::update(void) } } -#endif //HAL_MSP_ENABLED \ No newline at end of file +#endif //HAL_MSP_RANGEFINDER_ENABLED + diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h index b612983b2e..273815f289 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h @@ -3,7 +3,7 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" -#if HAL_MSP_ENABLED +#if HAL_MSP_RANGEFINDER_ENABLED // Data timeout #define AP_RANGEFINDER_MSP_TIMEOUT_MS 500 @@ -38,4 +38,5 @@ private: static bool get_reading(uint16_t &reading_cm); }; -#endif //HAL_MSP_ENABLED \ No newline at end of file +#endif //HAL_MSP_RANGEFINDER_ENABLED +