mirror of https://github.com/ArduPilot/ardupilot
Plane: updates for new AP_Baro API
This commit is contained in:
parent
8a3d3bed72
commit
035b1302ed
|
@ -193,21 +193,7 @@ static AP_GPS gps;
|
|||
// flight modes convenience array
|
||||
static AP_Int8 *flight_modes = &g.flight_mode1;
|
||||
|
||||
#if CONFIG_BARO == HAL_BARO_BMP085
|
||||
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 AP_Baro barometer;
|
||||
|
||||
#if CONFIG_COMPASS == HAL_COMPASS_PX4
|
||||
static AP_Compass_PX4 compass;
|
||||
|
@ -1511,7 +1497,7 @@ static void set_flight_stage(AP_SpdHgtControl::FlightStage fs)
|
|||
|
||||
static void update_alt()
|
||||
{
|
||||
barometer.read();
|
||||
barometer.update();
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
Log_Write_Baro();
|
||||
}
|
||||
|
|
|
@ -577,7 +577,7 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
while(1) {
|
||||
hal.scheduler->delay(100);
|
||||
barometer.read();
|
||||
barometer.update();
|
||||
|
||||
if (!barometer.healthy()) {
|
||||
cliSerial->println_P(PSTR("not healthy"));
|
||||
|
|
Loading…
Reference in New Issue