diff --git a/libraries/AP_Proximity/AP_Proximity.h b/libraries/AP_Proximity/AP_Proximity.h index 4c50823227..1555ef6771 100644 --- a/libraries/AP_Proximity/AP_Proximity.h +++ b/libraries/AP_Proximity/AP_Proximity.h @@ -18,7 +18,7 @@ #include #include #include -#include +#include #define PROXIMITY_MAX_INSTANCES 1 // Maximum number of proximity sensor instances available on this platform #define PROXIMITY_MAX_IGNORE 6 // up to six areas can be ignored @@ -71,10 +71,6 @@ public: // update state of all proximity sensors. Should be called at high rate from main loop void update(void); - // set pointer to rangefinder object - void set_rangefinder(const class RangeFinder *rangefinder) { _rangefinder = rangefinder; } - const RangeFinder *get_rangefinder() const { return _rangefinder; } - // return sensor orientation and yaw correction uint8_t get_orientation(uint8_t instance) const; int16_t get_yaw_correction(uint8_t instance) const; @@ -147,7 +143,6 @@ private: static AP_Proximity *_singleton; Proximity_State state[PROXIMITY_MAX_INSTANCES]; AP_Proximity_Backend *drivers[PROXIMITY_MAX_INSTANCES]; - const RangeFinder *_rangefinder; uint8_t primary_instance; uint8_t num_instances; diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp index 9d281d4f3d..229c974eb1 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp @@ -15,9 +15,9 @@ #include #include "AP_Proximity_RangeFinder.h" -#include #include #include +#include #include extern const AP_HAL::HAL& hal; @@ -33,7 +33,7 @@ AP_Proximity_RangeFinder::AP_Proximity_RangeFinder(AP_Proximity &_frontend, void AP_Proximity_RangeFinder::update(void) { // exit immediately if no rangefinder object - const RangeFinder *rngfnd = frontend.get_rangefinder(); + const RangeFinder *rngfnd = AP::rangefinder(); if (rngfnd == nullptr) { set_status(AP_Proximity::Status::NoData); return;