Copter: updates for new AP_Baro API

This commit is contained in:
Andrew Tridgell 2015-01-05 22:28:00 +11:00
parent f8962d2439
commit c151f24672
2 changed files with 3 additions and 16 deletions

View File

@ -259,21 +259,8 @@ static GPS_Glitch gps_glitch(gps);
// flight modes convenience array // flight modes convenience array
static AP_Int8 *flight_modes = &g.flight_mode1; static AP_Int8 *flight_modes = &g.flight_mode1;
#if CONFIG_BARO == HAL_BARO_BMP085 static AP_Baro barometer;
static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == HAL_BARO_PX4
static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == HAL_BARO_VRBRAIN
static AP_Baro_VRBRAIN barometer;
#elif CONFIG_BARO == HAL_BARO_HIL
static AP_Baro_HIL barometer;
#elif CONFIG_BARO == HAL_BARO_MS5611
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#elif CONFIG_BARO == HAL_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#else
#error Unrecognized CONFIG_BARO setting
#endif
static Baro_Glitch baro_glitch(barometer); static Baro_Glitch baro_glitch(barometer);
#if CONFIG_COMPASS == HAL_COMPASS_PX4 #if CONFIG_COMPASS == HAL_COMPASS_PX4

View File

@ -16,7 +16,7 @@ static void init_barometer(bool full_calibration)
// return barometric altitude in centimeters // return barometric altitude in centimeters
static void read_barometer(void) static void read_barometer(void)
{ {
barometer.read(); barometer.update();
if (should_log(MASK_LOG_IMU)) { if (should_log(MASK_LOG_IMU)) {
Log_Write_Baro(); Log_Write_Baro();
} }