From 94f3c64df950547cdd75a770d2f5044f8f550aea Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 8 Jan 2015 13:19:29 +1100 Subject: [PATCH] HAL_SITL: fixed for changes in AP_InertialSensor API --- libraries/AP_HAL_AVR_SITL/SITL_State.cpp | 4 ++-- libraries/AP_HAL_AVR_SITL/SITL_State.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_AVR_SITL/SITL_State.cpp b/libraries/AP_HAL_AVR_SITL/SITL_State.cpp index 01c06c1fdf..1155f3127c 100644 --- a/libraries/AP_HAL_AVR_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_AVR_SITL/SITL_State.cpp @@ -65,7 +65,7 @@ uint16_t SITL_State::current_pin_value; float SITL_State::_current; AP_Baro_HIL *SITL_State::_barometer; -AP_InertialSensor_HIL *SITL_State::_ins; +AP_InertialSensor *SITL_State::_ins; SITLScheduler *SITL_State::_scheduler; AP_Compass_HIL *SITL_State::_compass; @@ -212,7 +212,7 @@ void SITL_State::_sitl_setup(void) // find the barometer object if it exists _sitl = (SITL *)AP_Param::find_object("SIM_"); _barometer = (AP_Baro_HIL *)AP_Param::find_object("GND_"); - _ins = (AP_InertialSensor_HIL *)AP_Param::find_object("INS_"); + _ins = (AP_InertialSensor *)AP_Param::find_object("INS_"); _compass = (AP_Compass_HIL *)AP_Param::find_object("COMPASS_"); if (_sitl != NULL) { diff --git a/libraries/AP_HAL_AVR_SITL/SITL_State.h b/libraries/AP_HAL_AVR_SITL/SITL_State.h index 8d7b74471e..ca5c8e1ef2 100644 --- a/libraries/AP_HAL_AVR_SITL/SITL_State.h +++ b/libraries/AP_HAL_AVR_SITL/SITL_State.h @@ -121,7 +121,7 @@ private: static bool _motors_on; static AP_Baro_HIL *_barometer; - static AP_InertialSensor_HIL *_ins; + static AP_InertialSensor *_ins; static SITLScheduler *_scheduler; static AP_Compass_HIL *_compass;