AP_Baro: remove unused baro probe lines

This commit is contained in:
Andrew Tridgell 2019-08-27 21:36:58 +10:00
parent 7fa6eeaaed
commit 6cecf15e6a
1 changed files with 0 additions and 40 deletions

View File

@ -563,40 +563,6 @@ void AP_Baro::init(void)
#elif HAL_BARO_DEFAULT == HAL_BARO_HIL
drivers[0] = new AP_Baro_HIL(*this);
_num_drivers = 1;
#elif HAL_BARO_DEFAULT == HAL_BARO_BMP085
ADD_BACKEND(AP_Baro_BMP085::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_BMP085_BUS, HAL_BARO_BMP085_I2C_ADDR))));
#elif HAL_BARO_DEFAULT == HAL_BARO_BMP280_I2C
ADD_BACKEND(AP_Baro_BMP280::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_BMP280_BUS, HAL_BARO_BMP280_I2C_ADDR))));
#elif HAL_BARO_DEFAULT == HAL_BARO_BMP280_SPI
ADD_BACKEND(AP_Baro_BMP280::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_BMP280_NAME))));
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_I2C
ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR))));
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_SPI
ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME))));
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5607_I2C
ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)),
AP_Baro_MS56XX::BARO_MS5607));
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5637_I2C
ADD_BACKEND(AP_Baro_MS56XX::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5637_I2C_BUS, HAL_BARO_MS5637_I2C_ADDR)),
AP_Baro_MS56XX::BARO_MS5637));
#elif HAL_BARO_DEFAULT == HAL_BARO_FBM320_I2C
ADD_BACKEND(AP_Baro_FBM320::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_FBM320_I2C_BUS, HAL_BARO_FBM320_I2C_ADDR))));
#elif HAL_BARO_DEFAULT == HAL_BARO_DPS280_I2C
ADD_BACKEND(AP_Baro_DPS280::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_DPS280_I2C_BUS, HAL_BARO_DPS280_I2C_ADDR))));
#elif HAL_BARO_DEFAULT == HAL_BARO_DPS280_SPI
ADD_BACKEND(AP_Baro_DPS280::probe(*this, std::move(hal.spi->get_device("dps280"))));
#elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H
ADD_BACKEND(AP_Baro_LPS2XH::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_LPS25H_I2C_BUS, HAL_BARO_LPS25H_I2C_ADDR))));
#elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H_IMU_I2C
ADD_BACKEND(AP_Baro_LPS2XH::probe_InvensenseIMU(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_LPS25H_I2C_BUS, HAL_BARO_LPS25H_I2C_ADDR)),
@ -609,12 +575,6 @@ void AP_Baro::init(void)
ADD_BACKEND(AP_Baro_ICM20789::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_20789_I2C_BUS, HAL_BARO_20789_I2C_ADDR_PRESS)),
std::move(hal.spi->get_device("icm20789"))));
#elif HAL_BARO_DEFAULT == HAL_BARO_LPS22H_SPI
ADD_BACKEND(AP_Baro_LPS2XH::probe(*this,
std::move(hal.spi->get_device(HAL_BARO_LPS22H_NAME))));
#elif HAL_BARO_DEFAULT == HAL_BARO_LPS22H_I2C
ADD_BACKEND(AP_Baro_LPS2XH::probe(*this,
std::move(hal.i2c_mgr->get_device(HAL_BARO_LPS22H_I2C_BUS, HAL_BARO_LPS22H_I2C_ADDR))));
#endif
// can optionally have baro on I2C too