Skip to content
Snippets Groups Projects
Commit 8359c082 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

AP_Baro: fixed baro on NavIO

don't use the 1kHz timer as it conflicts with other I2C devices
parent b85001bf
No related branches found
No related tags found
No related merge requests found
...@@ -248,14 +248,15 @@ void AP_Baro::init(void) ...@@ -248,14 +248,15 @@ void AP_Baro::init(void)
} }
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611 #elif HAL_BARO_DEFAULT == HAL_BARO_MS5611
{ {
drivers[0] = new AP_Baro_MS5611(*this, new AP_SerialBus_I2C(MS5611_I2C_ADDR)); drivers[0] = new AP_Baro_MS5611(*this, new AP_SerialBus_I2C(MS5611_I2C_ADDR), false);
_num_drivers = 1; _num_drivers = 1;
} }
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_SPI #elif HAL_BARO_DEFAULT == HAL_BARO_MS5611_SPI
{ {
drivers[0] = new AP_Baro_MS5611(*this, drivers[0] = new AP_Baro_MS5611(*this,
new AP_SerialBus_SPI(AP_HAL::SPIDevice_MS5611, new AP_SerialBus_SPI(AP_HAL::SPIDevice_MS5611,
AP_HAL::SPIDeviceDriver::SPI_SPEED_HIGH)); AP_HAL::SPIDeviceDriver::SPI_SPEED_HIGH),
true);
_num_drivers = 1; _num_drivers = 1;
} }
#endif #endif
......
...@@ -154,12 +154,13 @@ void AP_SerialBus_I2C::sem_give() ...@@ -154,12 +154,13 @@ void AP_SerialBus_I2C::sem_give()
/* /*
constructor constructor
*/ */
AP_Baro_MS5611::AP_Baro_MS5611(AP_Baro &baro, AP_SerialBus *serial) : AP_Baro_MS5611::AP_Baro_MS5611(AP_Baro &baro, AP_SerialBus *serial, bool use_timer) :
AP_Baro_Backend(baro), AP_Baro_Backend(baro),
_serial(serial), _serial(serial),
_updated(false), _updated(false),
_state(0), _state(0),
_last_timer(0) _last_timer(0),
_use_timer(use_timer)
{ {
_instance = _frontend.register_sensor(); _instance = _frontend.register_sensor();
_serial->init(); _serial->init();
...@@ -195,7 +196,9 @@ AP_Baro_MS5611::AP_Baro_MS5611(AP_Baro &baro, AP_SerialBus *serial) : ...@@ -195,7 +196,9 @@ AP_Baro_MS5611::AP_Baro_MS5611(AP_Baro &baro, AP_SerialBus *serial) :
_serial->sem_give(); _serial->sem_give();
hal.scheduler->register_timer_process( AP_HAL_MEMBERPROC(&AP_Baro_MS5611::_timer)); if (_use_timer) {
hal.scheduler->register_timer_process( AP_HAL_MEMBERPROC(&AP_Baro_MS5611::_timer));
}
} }
/** /**
...@@ -310,6 +313,12 @@ void AP_Baro_MS5611::_timer(void) ...@@ -310,6 +313,12 @@ void AP_Baro_MS5611::_timer(void)
void AP_Baro_MS5611::update() void AP_Baro_MS5611::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) { if (!_updated) {
return; return;
} }
...@@ -370,3 +379,17 @@ void AP_Baro_MS5611::_calculate() ...@@ -370,3 +379,17 @@ void AP_Baro_MS5611::_calculate()
float temperature = (TEMP + 2000) * 0.01f; float temperature = (TEMP + 2000) * 0.01f;
_copy_to_frontend(_instance, pressure, temperature); _copy_to_frontend(_instance, 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_MS5611::accumulate(void)
{
if (!_use_timer) {
// the timer isn't being called as a timer, so we need to call
// it in accumulate()
_timer();
}
}
...@@ -76,8 +76,9 @@ private: ...@@ -76,8 +76,9 @@ private:
class AP_Baro_MS5611 : public AP_Baro_Backend class AP_Baro_MS5611 : public AP_Baro_Backend
{ {
public: public:
AP_Baro_MS5611(AP_Baro &baro, AP_SerialBus *serial); AP_Baro_MS5611(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
void update(); void update();
void accumulate();
private: private:
AP_SerialBus *_serial; AP_SerialBus *_serial;
...@@ -96,6 +97,8 @@ private: ...@@ -96,6 +97,8 @@ private:
uint8_t _state; uint8_t _state;
uint32_t _last_timer; uint32_t _last_timer;
bool _use_timer;
// Internal calibration registers // Internal calibration registers
uint16_t C1,C2,C3,C4,C5,C6; uint16_t C1,C2,C3,C4,C5,C6;
float D1,D2; float D1,D2;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment