re-organiser sensor declarations

this tries to make the #ifdef nesting easier to understand
This commit is contained in:
Andrew Tridgell 2011-11-13 17:15:45 +11:00 committed by Pat Hickey
parent e0488e134f
commit 1c20efe4b8
2 changed files with 25 additions and 35 deletions

View File

@ -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

View File

@ -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