diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index bf8e401396..fc760e250b 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -217,8 +217,8 @@ AP_TimerProcess timer_scheduler; AP_GPS_HIL g_gps_driver(NULL); AP_Compass_HIL compass; // never used AP_IMU_Shim imu; // never used - AP_InertialSensorStub ins; - AP_PeriodicProcessStub timer_scheduler; + AP_InertialSensor_Stub ins; + AP_PeriodicProcessStub timer_scheduler; #ifdef OPTFLOW_ENABLED AP_OpticalFlow_ADNS3080 optflow; #endif diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp index dfc3c224a5..933b7a5627 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp @@ -5,7 +5,7 @@ void AP_InertialSensor_Stub::init( AP_PeriodicProcess * scheduler ) {} /*================ AP_INERTIALSENSOR PUBLIC INTERFACE ==================== */ -bool AP_InertialSensor_Stub::update( void ) {} +bool AP_InertialSensor_Stub::update( void ) { return true; } float AP_InertialSensor_Stub::gx() { return 0.0f; }