diff --git a/libraries/AP_HAL_AVR_SITL/SITL_State.cpp b/libraries/AP_HAL_AVR_SITL/SITL_State.cpp
index 01c06c1fdfc2a4b452b2996298f8510a07c6b3c1..1155f3127c029320c571f7669479cefc9068c812 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 8d7b74471e3a6090f0d857a55ec3d1309bb4622a..ca5c8e1ef22eaf51f08fadf8165317e00312f857 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;