always declare a timer_scheduler

we should always run this code
This commit is contained in:
Andrew Tridgell 2011-12-21 23:23:17 +11:00
parent 8780a60234
commit 89561d49d0
1 changed files with 3 additions and 2 deletions

View File

@ -186,7 +186,6 @@ AP_GPS_None g_gps_driver(NULL);
#endif // CONFIG_IMU_TYPE #endif // CONFIG_IMU_TYPE
AP_IMU_INS imu( &ins, Parameters::k_param_IMU_calibration ); AP_IMU_INS imu( &ins, Parameters::k_param_IMU_calibration );
AP_DCM dcm(&imu, g_gps); AP_DCM dcm(&imu, g_gps);
AP_TimerProcess timer_scheduler;
#elif HIL_MODE == HIL_MODE_SENSORS #elif HIL_MODE == HIL_MODE_SENSORS
// sensor emulators // sensor emulators
@ -197,7 +196,6 @@ AP_GPS_HIL g_gps_driver(NULL);
AP_InertialSensor_Oilpan ins( &adc ); AP_InertialSensor_Oilpan ins( &adc );
AP_IMU_Shim imu; AP_IMU_Shim imu;
AP_DCM dcm(&imu, g_gps); AP_DCM dcm(&imu, g_gps);
AP_TimerProcess timer_scheduler;
#elif HIL_MODE == HIL_MODE_ATTITUDE #elif HIL_MODE == HIL_MODE_ATTITUDE
AP_ADC_HIL adc; AP_ADC_HIL adc;
@ -210,6 +208,9 @@ AP_IMU_Shim imu; // never used
#error Unrecognised HIL_MODE setting. #error Unrecognised HIL_MODE setting.
#endif // HIL MODE #endif // HIL MODE
// we always have a timer scheduler
AP_TimerProcess timer_scheduler;
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// GCS selection // GCS selection