diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index a7e1fe797d..bceb2da9f7 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -189,12 +189,24 @@ static AP_Int8 *flight_modes = &g.flight_mode1; #error Unrecognised GPS_PROTOCOL setting. #endif // GPS PROTOCOL +#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000 +AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN ); +#else +AP_InertialSensor_Oilpan ins(&adc); +#endif +AP_IMU_INS imu(&ins, Parameters::k_param_IMU_calibration); +AP_DCM dcm(&imu, g_gps); +AP_TimerProcess timer_scheduler; + #elif HIL_MODE == HIL_MODE_SENSORS // sensor emulators AP_ADC_HIL adc; APM_BMP085_HIL_Class barometer; AP_Compass_HIL compass; AP_GPS_HIL g_gps_driver(NULL); + AP_IMU_Shim imu; + AP_DCM dcm(&imu, g_gps); + AP_TimerProcess timer_scheduler; #elif HIL_MODE == HIL_MODE_ATTITUDE AP_ADC_HIL adc; @@ -210,24 +222,7 @@ static AP_Int8 *flight_modes = &g.flight_mode1; #error Unrecognised HIL_MODE setting. #endif // HIL MODE -AP_TimerProcess timer_scheduler; -#if HIL_MODE != HIL_MODE_ATTITUDE - #if HIL_MODE != HIL_MODE_SENSORS - // Normal - #if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000 - AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN ); - #else - AP_InertialSensor_Oilpan ins(&adc); - #endif - AP_IMU_INS imu(&ins, Parameters::k_param_IMU_calibration); - #else - // hil imu - AP_IMU_Shim imu; - #endif - // normal dcm - AP_DCM dcm(&imu, g_gps); -#endif //////////////////////////////////////////////////////////////////////////////// // GCS selection diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 3edefc1515..ded3b8738b 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -161,12 +161,25 @@ AP_GPS_None g_gps_driver(NULL); #error Unrecognised GPS_PROTOCOL setting. #endif // GPS PROTOCOL +# if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000 + AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN ); +# else + AP_InertialSensor_Oilpan ins( &adc ); +#endif // CONFIG_IMU_TYPE +AP_IMU_INS imu( &ins, Parameters::k_param_IMU_calibration ); +AP_DCM dcm(&imu, g_gps); +AP_TimerProcess timer_scheduler; + #elif HIL_MODE == HIL_MODE_SENSORS // sensor emulators AP_ADC_HIL adc; APM_BMP085_HIL_Class barometer; AP_Compass_HIL compass; AP_GPS_HIL g_gps_driver(NULL); +AP_InertialSensor_Oilpan ins( &adc ); +AP_IMU_Shim imu; +AP_DCM dcm(&imu, g_gps); +AP_TimerProcess timer_scheduler; #elif HIL_MODE == HIL_MODE_ATTITUDE AP_ADC_HIL adc; @@ -179,24 +192,6 @@ AP_IMU_Shim imu; // never used #error Unrecognised HIL_MODE setting. #endif // HIL MODE -AP_TimerProcess timer_scheduler; - -#if HIL_MODE != HIL_MODE_ATTITUDE - #if HIL_MODE != HIL_MODE_SENSORS - // Normal - #if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000 - AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN ); - #else - AP_InertialSensor_Oilpan ins( &adc ); - #endif - AP_IMU_INS imu( &ins, Parameters::k_param_IMU_calibration ); - #else - // hil imu - AP_IMU_Shim imu; - #endif - // normal dcm - AP_DCM dcm(&imu, g_gps); -#endif //////////////////////////////////////////////////////////////////////////////// // GCS selection