mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Baro: MS5611: always use timer thread
Remove support to run MS5611 on main thread since we shouldn't be doing I2C transactions there and we are moving to "thread per bus" nonetheless.
This commit is contained in:
parent
7b7e73680f
commit
929348ff75
@ -299,23 +299,19 @@ void AP_Baro::init(void)
|
||||
_num_drivers = 1;
|
||||
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_I2C
|
||||
drivers[0] = new AP_Baro_MS5611(*this,
|
||||
std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR)),
|
||||
HAL_BARO_MS5611_USE_TIMER);
|
||||
std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR)));
|
||||
_num_drivers = 1;
|
||||
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_SPI
|
||||
drivers[0] = new AP_Baro_MS5611(*this,
|
||||
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)),
|
||||
true);
|
||||
std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)));
|
||||
_num_drivers = 1;
|
||||
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5607_I2C
|
||||
drivers[0] = new AP_Baro_MS5607(*this,
|
||||
std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)),
|
||||
true);
|
||||
std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)));
|
||||
_num_drivers = 1;
|
||||
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5637_I2C
|
||||
drivers[0] = new AP_Baro_MS5637(*this,
|
||||
std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5637_I2C_BUS, HAL_BARO_MS5637_I2C_ADDR)),
|
||||
true);
|
||||
std::move(hal.i2c_mgr->get_device(HAL_BARO_MS5637_I2C_BUS, HAL_BARO_MS5637_I2C_ADDR)));
|
||||
_num_drivers = 1;
|
||||
#elif HAL_BARO_DEFAULT == HAL_BARO_QFLIGHT
|
||||
drivers[0] = new AP_Baro_QFLIGHT(*this);
|
||||
|
@ -51,10 +51,9 @@ static const uint8_t ADDR_CMD_CONVERT_TEMPERATURE = ADDR_CMD_CONVERT_D2_OSR1024;
|
||||
/*
|
||||
constructor
|
||||
*/
|
||||
AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer)
|
||||
AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: AP_Baro_Backend(baro)
|
||||
, _dev(std::move(dev))
|
||||
, _use_timer(use_timer)
|
||||
{
|
||||
}
|
||||
|
||||
@ -104,10 +103,8 @@ void AP_Baro_MS56XX::_init()
|
||||
|
||||
hal.scheduler->resume_timer_procs();
|
||||
|
||||
if (_use_timer) {
|
||||
/* timer needs to be called every 10ms so set the freq_div to 10 */
|
||||
_timesliced = hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void), 10);
|
||||
}
|
||||
/* timer needs to be called every 10ms so set the freq_div to 10 */
|
||||
_timesliced = hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void), 10);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -284,12 +281,6 @@ void AP_Baro_MS56XX::_timer(void)
|
||||
|
||||
void AP_Baro_MS56XX::update()
|
||||
{
|
||||
if (!_use_timer) {
|
||||
// if we're not using the timer then accumulate one more time
|
||||
// to cope with the calibration loop and minimise lag
|
||||
accumulate();
|
||||
}
|
||||
|
||||
if (!_updated) {
|
||||
return;
|
||||
}
|
||||
@ -316,8 +307,8 @@ void AP_Baro_MS56XX::update()
|
||||
}
|
||||
|
||||
/* MS5611 class */
|
||||
AP_Baro_MS5611::AP_Baro_MS5611(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer)
|
||||
: AP_Baro_MS56XX(baro, std::move(dev), use_timer)
|
||||
AP_Baro_MS5611::AP_Baro_MS5611(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: AP_Baro_MS56XX(baro, std::move(dev))
|
||||
{
|
||||
_init();
|
||||
}
|
||||
@ -358,8 +349,8 @@ void AP_Baro_MS5611::_calculate()
|
||||
}
|
||||
|
||||
/* MS5607 Class */
|
||||
AP_Baro_MS5607::AP_Baro_MS5607(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer)
|
||||
: AP_Baro_MS56XX(baro, std::move(dev), use_timer)
|
||||
AP_Baro_MS5607::AP_Baro_MS5607(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: AP_Baro_MS56XX(baro, std::move(dev))
|
||||
{
|
||||
_init();
|
||||
}
|
||||
@ -400,8 +391,8 @@ void AP_Baro_MS5607::_calculate()
|
||||
}
|
||||
|
||||
/* MS5637 Class */
|
||||
AP_Baro_MS5637::AP_Baro_MS5637(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer)
|
||||
: AP_Baro_MS56XX(baro, std::move(dev), use_timer)
|
||||
AP_Baro_MS5637::AP_Baro_MS5637(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||
: AP_Baro_MS56XX(baro, std::move(dev))
|
||||
{
|
||||
_init();
|
||||
}
|
||||
@ -438,17 +429,3 @@ void AP_Baro_MS5637::_calculate()
|
||||
float temperature = TEMP * 0.01f;
|
||||
_copy_to_frontend(_instance, (float)pressure, temperature);
|
||||
}
|
||||
|
||||
/*
|
||||
Read the sensor from main code. This is only used for I2C MS5611 to
|
||||
avoid conflicts on the semaphore from calling it in a timer, which
|
||||
conflicts with the compass driver use of I2C
|
||||
*/
|
||||
void AP_Baro_MS56XX::accumulate(void)
|
||||
{
|
||||
if (!_use_timer) {
|
||||
// the timer isn't being called as a timer, so we need to call
|
||||
// it in accumulate()
|
||||
_timer();
|
||||
}
|
||||
}
|
||||
|
@ -10,10 +10,9 @@ class AP_Baro_MS56XX : public AP_Baro_Backend
|
||||
{
|
||||
public:
|
||||
void update();
|
||||
void accumulate();
|
||||
|
||||
protected:
|
||||
AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer);
|
||||
AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
void _init();
|
||||
|
||||
virtual void _calculate() = 0;
|
||||
@ -35,8 +34,6 @@ protected:
|
||||
uint32_t _last_timer;
|
||||
bool _timesliced;
|
||||
|
||||
bool _use_timer;
|
||||
|
||||
// Internal calibration registers
|
||||
uint16_t _c1,_c2,_c3,_c4,_c5,_c6;
|
||||
float _D1, _D2;
|
||||
@ -46,7 +43,7 @@ protected:
|
||||
class AP_Baro_MS5611 : public AP_Baro_MS56XX
|
||||
{
|
||||
public:
|
||||
AP_Baro_MS5611(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer);
|
||||
AP_Baro_MS5611(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
protected:
|
||||
void _calculate();
|
||||
};
|
||||
@ -54,7 +51,7 @@ protected:
|
||||
class AP_Baro_MS5607 : public AP_Baro_MS56XX
|
||||
{
|
||||
public:
|
||||
AP_Baro_MS5607(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer);
|
||||
AP_Baro_MS5607(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
protected:
|
||||
void _calculate();
|
||||
};
|
||||
@ -62,7 +59,7 @@ protected:
|
||||
class AP_Baro_MS5637 : public AP_Baro_MS56XX
|
||||
{
|
||||
public:
|
||||
AP_Baro_MS5637(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer);
|
||||
AP_Baro_MS5637(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
protected:
|
||||
void _calculate();
|
||||
bool _read_prom(uint16_t prom[8]) override;
|
||||
|
Loading…
Reference in New Issue
Block a user