diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp index 2e6e3613d8..ed7a02cfce 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp @@ -17,13 +17,13 @@ #if AP_RANGEFINDER_SIM_ENABLED #include +#include /* constructor - registers instance at top RangeFinder driver */ AP_RangeFinder_SITL::AP_RangeFinder_SITL(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, uint8_t instance) : AP_RangeFinder_Backend(_state, _params), - sitl(AP::sitl()), _instance(instance) {} @@ -32,7 +32,7 @@ AP_RangeFinder_SITL::AP_RangeFinder_SITL(RangeFinder::RangeFinder_State &_state, */ void AP_RangeFinder_SITL::update(void) { - const float dist = sitl->get_rangefinder(_instance); + const float dist = AP::sitl()->get_rangefinder(_instance); // negative distance means nothing is connected if (is_negative(dist)) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.h b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.h index e11763a26f..7ae23b0df6 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.h @@ -24,8 +24,6 @@ #if AP_RANGEFINDER_SIM_ENABLED -#include - class AP_RangeFinder_SITL : public AP_RangeFinder_Backend { public: // constructor. This incorporates initialisation as well. @@ -40,9 +38,6 @@ protected: return MAV_DISTANCE_SENSOR_UNKNOWN; } -private: - SITL::SIM *sitl; - uint8_t _instance; };