mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_RangeFinder: remove sitl pointer from header
similar to what we do elsewhere, just grab the singleton in the cpp file rather than taking a pointer to it
This commit is contained in:
parent
6be8d9cd06
commit
5e7ae1213f
@ -17,13 +17,13 @@
|
||||
#if AP_RANGEFINDER_SIM_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
/*
|
||||
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)) {
|
||||
|
@ -24,8 +24,6 @@
|
||||
|
||||
#if AP_RANGEFINDER_SIM_ENABLED
|
||||
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
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;
|
||||
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user