2016-02-17 21:25:23 -04:00
|
|
|
#pragma once
|
2012-12-14 21:55:38 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_Empty.h"
|
2012-12-14 21:55:38 -04:00
|
|
|
|
2015-12-07 14:53:55 -04:00
|
|
|
class Empty::I2CDriver : public AP_HAL::I2CDriver {
|
2012-12-17 19:22:05 -04:00
|
|
|
public:
|
2015-12-07 14:53:55 -04:00
|
|
|
I2CDriver(AP_HAL::Semaphore* semaphore) : _semaphore(semaphore) {}
|
2015-12-13 23:19:34 -04:00
|
|
|
void begin() override;
|
|
|
|
void end() override;
|
|
|
|
void setTimeout(uint16_t ms) override;
|
|
|
|
void setHighSpeed(bool active) override;
|
2012-12-14 21:55:38 -04:00
|
|
|
|
|
|
|
/* write: for i2c devices which do not obey register conventions */
|
2015-12-13 23:19:34 -04:00
|
|
|
uint8_t write(uint8_t addr, uint8_t len, uint8_t* data) override;
|
|
|
|
|
2012-12-14 21:55:38 -04:00
|
|
|
/* writeRegister: write a single 8-bit value to a register */
|
2015-12-13 23:19:34 -04:00
|
|
|
uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val) override;
|
|
|
|
|
2016-05-12 14:01:45 -03:00
|
|
|
/* writeRegisters: write bytes to contiguous registers */
|
2012-12-14 21:55:38 -04:00
|
|
|
uint8_t writeRegisters(uint8_t addr, uint8_t reg,
|
2015-12-13 23:19:34 -04:00
|
|
|
uint8_t len, uint8_t* data) override;
|
2012-12-14 21:55:38 -04:00
|
|
|
|
|
|
|
/* read: for i2c devices which do not obey register conventions */
|
2015-12-13 23:19:34 -04:00
|
|
|
uint8_t read(uint8_t addr, uint8_t len, uint8_t* data) override;
|
|
|
|
|
2012-12-14 21:55:38 -04:00
|
|
|
/* readRegister: read from a device register - writes the register,
|
|
|
|
* then reads back an 8-bit value. */
|
2015-12-13 23:19:34 -04:00
|
|
|
uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data) override;
|
|
|
|
|
2016-05-12 14:01:45 -03:00
|
|
|
/* readRegister: read contiguous device registers - writes the first
|
2012-12-14 21:55:38 -04:00
|
|
|
* register, then reads back multiple bytes */
|
|
|
|
uint8_t readRegisters(uint8_t addr, uint8_t reg,
|
2015-12-13 23:19:34 -04:00
|
|
|
uint8_t len, uint8_t* data) override;
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
2016-05-12 14:01:45 -03:00
|
|
|
/* readRegistersMultiple: read contiguous device registers.
|
2015-12-13 23:19:34 -04:00
|
|
|
Equivalent to count calls to readRegisters() */
|
|
|
|
virtual uint8_t readRegistersMultiple(uint8_t addr, uint8_t reg,
|
|
|
|
uint8_t len, uint8_t count,
|
|
|
|
uint8_t* data) override;
|
|
|
|
#endif
|
|
|
|
|
2012-12-14 21:55:38 -04:00
|
|
|
uint8_t lockup_count();
|
|
|
|
|
2013-01-04 20:19:51 -04:00
|
|
|
AP_HAL::Semaphore* get_semaphore() { return _semaphore; }
|
|
|
|
|
|
|
|
private:
|
|
|
|
AP_HAL::Semaphore* _semaphore;
|
2012-12-14 21:55:38 -04:00
|
|
|
};
|