mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: Use SITL singleton
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
e456655932
commit
0c06bf89e5
|
@ -28,9 +28,9 @@ AP_InertialSensor_Backend *AP_InertialSensor_SITL::detect(AP_InertialSensor &_im
|
||||||
return sensor;
|
return sensor;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_InertialSensor_SITL::init_sensor(void)
|
bool AP_InertialSensor_SITL::init_sensor(void)
|
||||||
{
|
{
|
||||||
sitl = (SITL::SITL *)AP_Param::find_object("SIM_");
|
sitl = AP::sitl();
|
||||||
if (sitl == nullptr) {
|
if (sitl == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue