2011-12-28 05:32:21 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2011-11-05 22:11:25 -03:00
|
|
|
|
2011-11-27 01:49:17 -04:00
|
|
|
#ifndef __AP_BARO_MS5611_H__
|
|
|
|
#define __AP_BARO_MS5611_H__
|
2011-11-05 22:11:25 -03:00
|
|
|
|
2012-11-19 21:23:26 -04:00
|
|
|
#include <AP_HAL.h>
|
2011-11-30 00:31:10 -04:00
|
|
|
#include "AP_Baro.h"
|
2011-11-05 22:11:25 -03:00
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
/** Abstract serial bus device driver for I2C/SPI. */
|
|
|
|
class AP_SerialBus
|
2013-01-03 14:06:22 -04:00
|
|
|
{
|
|
|
|
public:
|
|
|
|
/** Initialize the driver. */
|
|
|
|
virtual void init() = 0;
|
|
|
|
|
|
|
|
/** Read a 16-bit value from register "reg". */
|
|
|
|
virtual uint16_t read_16bits(uint8_t reg) = 0;
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
/** Read a 24-bit value */
|
|
|
|
virtual uint32_t read_24bits(uint8_t reg) = 0;
|
2013-01-03 14:06:22 -04:00
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
/** Write to a register with no data. */
|
2013-01-03 14:06:22 -04:00
|
|
|
virtual void write(uint8_t reg) = 0;
|
|
|
|
|
2013-01-03 15:05:00 -04:00
|
|
|
/** Acquire the internal semaphore for this device.
|
|
|
|
* take_nonblocking should be used from the timer process,
|
|
|
|
* take_blocking from synchronous code (i.e. init) */
|
2014-10-19 16:22:51 -03:00
|
|
|
virtual bool sem_take_nonblocking() = 0;
|
|
|
|
virtual bool sem_take_blocking() = 0;
|
2013-01-03 14:06:22 -04:00
|
|
|
|
|
|
|
/** Release the internal semaphore for this device. */
|
2014-10-19 16:22:51 -03:00
|
|
|
virtual void sem_give() = 0;
|
2013-01-03 14:06:22 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
/** SPI serial device. */
|
2014-10-19 16:22:51 -03:00
|
|
|
class AP_SerialBus_SPI : public AP_SerialBus
|
2013-01-03 14:06:22 -04:00
|
|
|
{
|
|
|
|
public:
|
2014-10-19 16:22:51 -03:00
|
|
|
AP_SerialBus_SPI(enum AP_HAL::SPIDevice device, enum AP_HAL::SPIDeviceDriver::bus_speed speed);
|
|
|
|
void init();
|
|
|
|
uint16_t read_16bits(uint8_t reg);
|
|
|
|
uint32_t read_24bits(uint8_t reg);
|
|
|
|
uint32_t read_adc(uint8_t reg);
|
|
|
|
void write(uint8_t reg);
|
|
|
|
bool sem_take_nonblocking();
|
|
|
|
bool sem_take_blocking();
|
|
|
|
void sem_give();
|
2013-01-03 14:06:22 -04:00
|
|
|
|
|
|
|
private:
|
2014-10-19 16:22:51 -03:00
|
|
|
enum AP_HAL::SPIDevice _device;
|
2015-04-24 02:13:02 -03:00
|
|
|
enum AP_HAL::SPIDeviceDriver::bus_speed _speed;
|
2013-01-03 14:06:22 -04:00
|
|
|
AP_HAL::SPIDeviceDriver *_spi;
|
|
|
|
AP_HAL::Semaphore *_spi_sem;
|
|
|
|
};
|
|
|
|
|
|
|
|
/** I2C serial device. */
|
2014-10-19 16:22:51 -03:00
|
|
|
class AP_SerialBus_I2C : public AP_SerialBus
|
2013-01-03 14:06:22 -04:00
|
|
|
{
|
|
|
|
public:
|
2015-07-10 00:56:06 -03:00
|
|
|
AP_SerialBus_I2C(AP_HAL::I2CDriver *i2c, uint8_t addr);
|
2014-10-19 16:22:51 -03:00
|
|
|
void init();
|
|
|
|
uint16_t read_16bits(uint8_t reg);
|
|
|
|
uint32_t read_24bits(uint8_t reg);
|
|
|
|
void write(uint8_t reg);
|
|
|
|
bool sem_take_nonblocking();
|
|
|
|
bool sem_take_blocking();
|
|
|
|
void sem_give();
|
2013-01-04 18:26:26 -04:00
|
|
|
|
|
|
|
private:
|
2015-07-10 00:56:06 -03:00
|
|
|
AP_HAL::I2CDriver *_i2c;
|
2014-10-19 16:22:51 -03:00
|
|
|
uint8_t _addr;
|
2013-01-04 18:26:26 -04:00
|
|
|
AP_HAL::Semaphore *_i2c_sem;
|
2013-01-03 14:06:22 -04:00
|
|
|
};
|
|
|
|
|
2015-07-10 00:56:06 -03:00
|
|
|
class AP_Baro_MS56XX : public AP_Baro_Backend
|
2011-11-27 01:43:34 -04:00
|
|
|
{
|
2012-08-17 03:09:24 -03:00
|
|
|
public:
|
2015-07-10 00:56:06 -03:00
|
|
|
AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
|
2014-10-19 16:22:51 -03:00
|
|
|
void update();
|
2015-01-06 01:28:11 -04:00
|
|
|
void accumulate();
|
2013-01-03 14:06:22 -04:00
|
|
|
|
2012-08-17 03:09:24 -03:00
|
|
|
private:
|
2015-07-10 00:56:06 -03:00
|
|
|
virtual void _calculate() = 0;
|
2014-10-19 16:22:51 -03:00
|
|
|
AP_SerialBus *_serial;
|
2014-07-07 00:11:41 -03:00
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
bool _check_crc();
|
|
|
|
|
|
|
|
void _timer();
|
2014-07-07 00:11:41 -03:00
|
|
|
|
2012-08-17 03:09:24 -03:00
|
|
|
/* Asynchronous state: */
|
2014-10-19 16:22:51 -03:00
|
|
|
volatile bool _updated;
|
|
|
|
volatile uint8_t _d1_count;
|
|
|
|
volatile uint8_t _d2_count;
|
|
|
|
volatile uint32_t _s_D1, _s_D2;
|
|
|
|
uint8_t _state;
|
|
|
|
uint32_t _last_timer;
|
2012-11-19 21:23:26 -04:00
|
|
|
|
2015-01-06 01:28:11 -04:00
|
|
|
bool _use_timer;
|
|
|
|
|
2015-07-10 00:56:06 -03:00
|
|
|
protected:
|
2014-10-19 16:22:51 -03:00
|
|
|
// Internal calibration registers
|
2015-07-10 00:56:06 -03:00
|
|
|
uint16_t _C1,_C2,_C3,_C4,_C5,_C6;
|
|
|
|
float _D1,_D2;
|
|
|
|
uint8_t _instance;
|
2011-11-05 22:11:25 -03:00
|
|
|
};
|
|
|
|
|
2015-07-10 00:56:06 -03:00
|
|
|
class AP_Baro_MS5611 : public AP_Baro_MS56XX
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_Baro_MS5611(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
|
|
|
|
private:
|
|
|
|
void _calculate();
|
|
|
|
};
|
|
|
|
|
|
|
|
class AP_Baro_MS5607 : public AP_Baro_MS56XX
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_Baro_MS5607(AP_Baro &baro, AP_SerialBus *serial, bool use_timer);
|
|
|
|
private:
|
|
|
|
void _calculate();
|
|
|
|
};
|
2011-11-27 01:49:17 -04:00
|
|
|
#endif // __AP_BARO_MS5611_H__
|