ArduCopter: fix issues with HAL/HIL mixup and baro/compass instances

This commit is contained in:
Pat Hickey 2012-12-14 11:02:09 -08:00 committed by Andrew Tridgell
parent 21d0da84a6
commit 5e63491994
2 changed files with 13 additions and 27 deletions

View File

@ -186,22 +186,24 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
#if HIL_MODE == HIL_MODE_DISABLED #if HIL_MODE == HIL_MODE_DISABLED
// real sensors
#if CONFIG_ADC == ENABLED #if CONFIG_ADC == ENABLED
AP_ADC_ADS7844 adc; AP_ADC_ADS7844 adc;
#endif #endif
#if CONFIG_HIL_BOARD == HIL_BOARD_AVR_SITL #if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
AP_InertialSensor_MPU6000 ins;
#else
AP_InertialSensor_Oilpan ins(&adc);
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
// When building for SITL we use the HIL barometer and compass drivers
AP_Baro_BMP085_HIL barometer; AP_Baro_BMP085_HIL barometer;
AP_Compass_HIL compass; AP_Compass_HIL compass;
#else #else
// Otherwise, instantiate a real barometer and compass driver
#if CONFIG_BARO == AP_BARO_BMP085 #if CONFIG_BARO == AP_BARO_BMP085
# if CONFIG_HAL_BOARD == HAL_BOARD_APM2 AP_Baro_BMP085 barometer;
AP_Baro_BMP085 barometer(true);
# else
AP_Baro_BMP085 barometer(false);
# endif
#elif CONFIG_BARO == AP_BARO_MS5611 #elif CONFIG_BARO == AP_BARO_MS5611
AP_Baro_MS5611 barometer; AP_Baro_MS5611 barometer;
#endif #endif
@ -210,11 +212,7 @@ AP_Compass_HMC5843 compass;
#endif #endif
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 AP_OpticalFlow_ADNS3080 optflow;
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN);
#else
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN);
#endif
#else #else
AP_OpticalFlow optflow; AP_OpticalFlow optflow;
#endif #endif
@ -245,16 +243,6 @@ AP_GPS_None g_gps_driver(NULL);
#error Unrecognised GPS_PROTOCOL setting. #error Unrecognised GPS_PROTOCOL setting.
#endif // GPS PROTOCOL #endif // GPS PROTOCOL
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
AP_InertialSensor_MPU6000 ins;
#else
AP_InertialSensor_Oilpan ins(&adc);
#endif
// we don't want to use gps for yaw correction on ArduCopter, so pass
// a NULL GPS object pointer
static GPS *g_gps_null;
#if DMP_ENABLED == ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_APM2 #if DMP_ENABLED == ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_APM2
AP_AHRS_MPU6000 ahrs(&ins, g_gps); // only works with APM2 AP_AHRS_MPU6000 ahrs(&ins, g_gps); // only works with APM2
#else #else
@ -288,9 +276,9 @@ AP_Baro_BMP085_HIL barometer;
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 #if CONFIG_HAL_BOARD == HAL_BOARD_APM2
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN); AP_OpticalFlow_ADNS3080 optflow;
#else #else
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN); AP_OpticalFlow_ADNS3080 optflow;
#endif // CONFIG_HAL_BOARD == HAL_BOARD_APM2 #endif // CONFIG_HAL_BOARD == HAL_BOARD_APM2
#endif // OPTFLOW == ENABLED #endif // OPTFLOW == ENABLED

View File

@ -143,7 +143,6 @@
# define PUSHBUTTON_PIN 41 # define PUSHBUTTON_PIN 41
# define USB_MUX_PIN -1 # define USB_MUX_PIN -1
# define CLI_SLIDER_ENABLED DISABLED # define CLI_SLIDER_ENABLED DISABLED
# define OPTFLOW_CS_PIN 34
# define BATTERY_VOLT_PIN 0 // Battery voltage on A0 # define BATTERY_VOLT_PIN 0 // Battery voltage on A0
# define BATTERY_CURR_PIN 1 // Battery current on A1 # define BATTERY_CURR_PIN 1 // Battery current on A1
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 #elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
@ -156,7 +155,6 @@
# define PUSHBUTTON_PIN (-1) # define PUSHBUTTON_PIN (-1)
# define CLI_SLIDER_ENABLED DISABLED # define CLI_SLIDER_ENABLED DISABLED
# define USB_MUX_PIN 23 # define USB_MUX_PIN 23
# define OPTFLOW_CS_PIN 57 // Optflow CS on A3
# define BATTERY_VOLT_PIN 1 // Battery voltage on A1 # define BATTERY_VOLT_PIN 1 // Battery voltage on A1
# define BATTERY_CURR_PIN 2 // Battery current on A2 # define BATTERY_CURR_PIN 2 // Battery current on A2
#endif #endif