2016-02-17 21:25:25 -04:00
|
|
|
#pragma once
|
2012-08-20 15:37:46 -03:00
|
|
|
|
2012-08-24 19:32:38 -03:00
|
|
|
#include <stdint.h>
|
|
|
|
|
2012-08-20 15:37:46 -03:00
|
|
|
#include "AP_HAL_Namespace.h"
|
|
|
|
|
|
|
|
class AP_HAL::I2CDriver {
|
|
|
|
public:
|
2012-08-24 19:32:38 -03:00
|
|
|
virtual void begin() = 0;
|
|
|
|
virtual void end() = 0;
|
|
|
|
virtual void setTimeout(uint16_t ms) = 0;
|
|
|
|
virtual void setHighSpeed(bool active) = 0;
|
|
|
|
|
2012-11-27 18:22:06 -04:00
|
|
|
/* write: for i2c devices which do not obey register conventions */
|
|
|
|
virtual uint8_t write(uint8_t addr, uint8_t len, uint8_t* data) = 0;
|
|
|
|
/* writeRegister: write a single 8-bit value to a register */
|
2012-08-24 19:32:38 -03:00
|
|
|
virtual uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val) = 0;
|
2016-05-12 13:58:35 -03:00
|
|
|
/* writeRegisters: write bytes to contiguous registers */
|
2012-08-24 19:32:38 -03:00
|
|
|
virtual uint8_t writeRegisters(uint8_t addr, uint8_t reg,
|
|
|
|
uint8_t len, uint8_t* data) = 0;
|
2012-11-27 18:22:06 -04:00
|
|
|
|
|
|
|
/* read: for i2c devices which do not obey register conventions */
|
|
|
|
virtual uint8_t read(uint8_t addr, uint8_t len, uint8_t* data) = 0;
|
|
|
|
/* readRegister: read from a device register - writes the register,
|
|
|
|
* then reads back an 8-bit value. */
|
2012-08-24 19:32:38 -03:00
|
|
|
virtual uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data) = 0;
|
2014-05-21 07:09:57 -03:00
|
|
|
|
2016-05-12 13:58:35 -03:00
|
|
|
/* readRegisters: read contiguous device registers - writes the first
|
2012-11-27 18:22:06 -04:00
|
|
|
* register, then reads back multiple bytes */
|
2012-08-24 19:32:38 -03:00
|
|
|
virtual uint8_t readRegisters(uint8_t addr, uint8_t reg,
|
|
|
|
uint8_t len, uint8_t* data) = 0;
|
|
|
|
|
2014-07-06 23:03:07 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
2016-05-12 13:58:35 -03:00
|
|
|
/* readRegistersMultiple: read contiguous device registers.
|
2014-05-21 07:09:57 -03: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) = 0;
|
2014-07-06 23:03:07 -03:00
|
|
|
#endif
|
2014-05-21 07:09:57 -03:00
|
|
|
|
2015-11-26 09:27:34 -04:00
|
|
|
virtual bool do_transfer(uint8_t address, const uint8_t *send,
|
|
|
|
uint32_t send_len, uint8_t *recv,
|
2015-11-30 16:18:10 -04:00
|
|
|
uint32_t recv_len) { return false;}
|
2012-12-17 19:21:47 -04:00
|
|
|
virtual uint8_t lockup_count() = 0;
|
2013-10-21 05:26:54 -03:00
|
|
|
void ignore_errors(bool b) { _ignore_errors = b; }
|
2013-01-04 18:26:26 -04:00
|
|
|
virtual AP_HAL::Semaphore* get_semaphore() = 0;
|
2013-10-21 05:26:54 -03:00
|
|
|
protected:
|
|
|
|
bool _ignore_errors;
|
2012-08-20 15:37:46 -03:00
|
|
|
};
|