diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index bc13a85ea8..800b68d904 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -274,7 +274,6 @@ AP_AHRS_MPU6000 ahrs(&imu, g_gps, &ins); // only works with APM2 AP_AHRS_DCM ahrs(&imu, g_gps); #endif -AP_TimerProcess timer_scheduler; #elif HIL_MODE == HIL_MODE_SENSORS // sensor emulators AP_ADC_HIL adc; @@ -283,20 +282,18 @@ AP_Compass_HIL compass; AP_GPS_HIL g_gps_driver(NULL); AP_IMU_Shim imu; AP_AHRS_DCM ahrs(&imu, g_gps); -AP_PeriodicProcessStub timer_scheduler; AP_InertialSensor_Stub ins; static int32_t gps_base_alt; #elif HIL_MODE == HIL_MODE_ATTITUDE AP_ADC_HIL adc; -AP_IMU_Shim imu; // never used +AP_IMU_Shim imu; AP_AHRS_HIL ahrs(&imu, g_gps); AP_GPS_HIL g_gps_driver(NULL); AP_Compass_HIL compass; // never used AP_Baro_BMP085_HIL barometer; AP_InertialSensor_Stub ins; -AP_PeriodicProcessStub timer_scheduler; #ifdef OPTFLOW_ENABLED AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN); #endif @@ -309,7 +306,8 @@ static int32_t gps_base_alt; #error Unrecognised HIL_MODE setting. #endif // HIL MODE - +// we always have a timer scheduler +AP_TimerProcess timer_scheduler; //////////////////////////////////////////////////////////////////////////////// // GCS selection diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 02129ba5e2..0e6867033d 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -381,14 +381,12 @@ static void startup_ground(void) { gcs_send_text_P(SEVERITY_LOW,PSTR("GROUND START")); -#if HIL_MODE != HIL_MODE_ATTITUDE // Warm up and read Gyro offsets // ----------------------------- imu.init(IMU::COLD_START, mavlink_delay, flash_leds, &timer_scheduler); #if CLI_ENABLED == ENABLED report_imu(); #endif -#endif // initialise ahrs (may push imu calibration into the mpu6000 if using that device). ahrs.init(); diff --git a/libraries/AP_IMU/AP_IMU_Shim.h b/libraries/AP_IMU/AP_IMU_Shim.h index 5100735525..024714fae3 100644 --- a/libraries/AP_IMU/AP_IMU_Shim.h +++ b/libraries/AP_IMU/AP_IMU_Shim.h @@ -26,7 +26,9 @@ public: void (*callback)(unsigned long t) = delay, void (*flash_leds_cb)(bool on) = NULL, AP_PeriodicProcess * scheduler = NULL) { - scheduler->register_process( AP_IMU_Shim::read ); + if( scheduler != NULL ) { + scheduler->register_process( AP_IMU_Shim::read ); + } }; virtual void init_accel(void (*callback)(unsigned long t) = delay, void (*flash_leds_cb)(bool on) = NULL) {