mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Baro: added GND_EXT_BUS option
this is needed to enable probing for a MS5611 on external I2C bus. The MS5611 looks the same as a MS5525 airspeed sensor, so we can't just auto-probe. Users will need to enable external barometers
This commit is contained in:
parent
57facb4a9d
commit
eea7758a63
@ -78,6 +78,13 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PRIMARY", 6, AP_Baro, _primary_baro, 0),
|
||||
|
||||
// @Param: EXT_BUS
|
||||
// @DisplayName: External baro bus
|
||||
// @Description: This selects the bus number for looking for an I2C barometer
|
||||
// @Values: -1:Disabled,0:Bus0:1:Bus1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("EXT_BUS", 7, AP_Baro, _ext_bus, -1),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -331,11 +338,6 @@ void AP_Baro::init(void)
|
||||
std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME))));
|
||||
ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
|
||||
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
|
||||
// can have baro on I2C too
|
||||
ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
|
||||
std::move(hal.i2c_mgr->get_device(0, HAL_BARO_MS5611_I2C_ADDR))));
|
||||
ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
|
||||
std::move(hal.i2c_mgr->get_device(1, HAL_BARO_MS5611_I2C_ADDR))));
|
||||
} else if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXRACER) {
|
||||
ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
|
||||
std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_INT_NAME))));
|
||||
@ -372,6 +374,12 @@ void AP_Baro::init(void)
|
||||
_num_drivers = 1;
|
||||
#endif
|
||||
|
||||
// can optionally have baro on I2C too
|
||||
if (_ext_bus >= 0) {
|
||||
ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
|
||||
std::move(hal.i2c_mgr->get_device(_ext_bus, HAL_BARO_MS5611_I2C_ADDR))));
|
||||
}
|
||||
|
||||
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) {
|
||||
AP_HAL::panic("Baro: unable to initialise driver");
|
||||
}
|
||||
|
@ -161,6 +161,7 @@ private:
|
||||
AP_Float _alt_offset;
|
||||
float _alt_offset_active;
|
||||
AP_Int8 _primary_baro; // primary chosen by user
|
||||
AP_Int8 _ext_bus; // bus number for external barometer
|
||||
float _last_altitude_EAS2TAS;
|
||||
float _EAS2TAS;
|
||||
float _external_temperature;
|
||||
|
@ -90,13 +90,16 @@ bool AP_Baro_MS56XX::_init()
|
||||
|
||||
uint16_t prom[8];
|
||||
bool prom_read_ok = false;
|
||||
|
||||
|
||||
const char *name = "MS5611";
|
||||
switch (_ms56xx_type) {
|
||||
case BARO_MS5607:
|
||||
name = "MS5607";
|
||||
case BARO_MS5611:
|
||||
prom_read_ok = _read_prom_5611(prom);
|
||||
break;
|
||||
case BARO_MS5637:
|
||||
name = "MS5637";
|
||||
prom_read_ok = _read_prom_5637(prom);
|
||||
break;
|
||||
}
|
||||
@ -106,6 +109,8 @@ bool AP_Baro_MS56XX::_init()
|
||||
return false;
|
||||
}
|
||||
|
||||
printf("%s found on bus %u address 0x%02x\n", name, _dev->bus_num(), _dev->get_bus_address());
|
||||
|
||||
_dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0);
|
||||
hal.scheduler->delay(4);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user