diff --git a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp index fcf0dbec5a..44a1efde9d 100644 --- a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp @@ -23,16 +23,6 @@ extern const AP_HAL::HAL& hal; #define PROXIMITY_MAX_RANGE 100.0f #define PROXIMITY_ACCURACY 0.1f -/* - The constructor also initialises the proximity sensor. -*/ -AP_Proximity_AirSimSITL::AP_Proximity_AirSimSITL(AP_Proximity &_frontend, - AP_Proximity::Proximity_State &_state): - AP_Proximity_Backend(_frontend, _state), - sitl(AP::sitl()) -{ -} - // update the state of the sensor void AP_Proximity_AirSimSITL::update(void) { diff --git a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h index b398417cd4..c2edf94888 100644 --- a/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h +++ b/libraries/AP_Proximity/AP_Proximity_AirSimSITL.h @@ -26,7 +26,7 @@ class AP_Proximity_AirSimSITL : public AP_Proximity_Backend public: // constructor - AP_Proximity_AirSimSITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); + using AP_Proximity_Backend::AP_Proximity_Backend; // update state void update(void) override; @@ -39,6 +39,6 @@ public: bool get_upward_distance(float &distance) const override; private: - SITL::SITL *sitl; + SITL::SITL *sitl = AP::sitl(); }; #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.cpp b/libraries/AP_Proximity/AP_Proximity_MAV.cpp index 428fe7f0b4..e764e25ffb 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.cpp +++ b/libraries/AP_Proximity/AP_Proximity_MAV.cpp @@ -23,17 +23,6 @@ extern const AP_HAL::HAL& hal; #define PROXIMITY_MAV_TIMEOUT_MS 500 // distance messages must arrive within this many milliseconds -/* - The constructor also initialises the proximity sensor. Note that this - constructor is not called until detect() returns true, so we - already know that we should setup the proximity sensor -*/ -AP_Proximity_MAV::AP_Proximity_MAV(AP_Proximity &_frontend, - AP_Proximity::Proximity_State &_state) : - AP_Proximity_Backend(_frontend, _state) -{ -} - // update the state of the sensor void AP_Proximity_MAV::update(void) { diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.h b/libraries/AP_Proximity/AP_Proximity_MAV.h index 26e0f698fa..af8360fa46 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.h +++ b/libraries/AP_Proximity/AP_Proximity_MAV.h @@ -8,7 +8,7 @@ class AP_Proximity_MAV : public AP_Proximity_Backend public: // constructor - AP_Proximity_MAV(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); + using AP_Proximity_Backend::AP_Proximity_Backend; // update state void update(void) override; diff --git a/libraries/AP_Proximity/AP_Proximity_MorseSITL.cpp b/libraries/AP_Proximity/AP_Proximity_MorseSITL.cpp index 1cd54d370d..42f0c15444 100644 --- a/libraries/AP_Proximity/AP_Proximity_MorseSITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_MorseSITL.cpp @@ -24,16 +24,6 @@ extern const AP_HAL::HAL& hal; #define PROXIMITY_MAX_RANGE 200.0f #define PROXIMITY_ACCURACY 0.1f -/* - The constructor also initialises the proximity sensor. -*/ -AP_Proximity_MorseSITL::AP_Proximity_MorseSITL(AP_Proximity &_frontend, - AP_Proximity::Proximity_State &_state): - AP_Proximity_Backend(_frontend, _state), - sitl(AP::sitl()) -{ -} - // update the state of the sensor void AP_Proximity_MorseSITL::update(void) { diff --git a/libraries/AP_Proximity/AP_Proximity_MorseSITL.h b/libraries/AP_Proximity/AP_Proximity_MorseSITL.h index 412e92e168..5d107e19b6 100644 --- a/libraries/AP_Proximity/AP_Proximity_MorseSITL.h +++ b/libraries/AP_Proximity/AP_Proximity_MorseSITL.h @@ -11,7 +11,7 @@ class AP_Proximity_MorseSITL : public AP_Proximity_Backend public: // constructor - AP_Proximity_MorseSITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); + using AP_Proximity_Backend::AP_Proximity_Backend; // update state void update(void) override; @@ -24,7 +24,7 @@ public: bool get_upward_distance(float &distance) const override; private: - SITL::SITL *sitl; + SITL::SITL *sitl = AP::sitl(); float distance_maximum; }; #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp index 229c974eb1..46c1ac833d 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp @@ -20,15 +20,6 @@ #include #include -extern const AP_HAL::HAL& hal; - -AP_Proximity_RangeFinder::AP_Proximity_RangeFinder(AP_Proximity &_frontend, - AP_Proximity::Proximity_State &_state) : - AP_Proximity_Backend(_frontend, _state), - _distance_upward(-1) -{ -} - // update the state of the sensor void AP_Proximity_RangeFinder::update(void) { diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.h b/libraries/AP_Proximity/AP_Proximity_RangeFinder.h index f6d7ed59f5..e624f0c70e 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.h +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.h @@ -10,7 +10,7 @@ class AP_Proximity_RangeFinder : public AP_Proximity_Backend public: // constructor - AP_Proximity_RangeFinder(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); + using AP_Proximity_Backend::AP_Proximity_Backend; // update state void update(void) override; @@ -31,5 +31,5 @@ private: // upward distance support uint32_t _last_upward_update_ms; // system time of last update distance - float _distance_upward; // upward distance in meters, negative if the last reading was out of range + float _distance_upward = -1; // upward distance in meters, negative if the last reading was out of range };