2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-11-22 20:10:57 -04:00
|
|
|
#include <vector>
|
|
|
|
|
|
|
|
#include <AP_HAL/utility/OwnPtr.h>
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_Linux.h"
|
2015-11-22 20:10:57 -04:00
|
|
|
#include "I2CDevice.h"
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
class Linux::I2CDriver : public AP_HAL::I2CDriver {
|
2013-09-22 03:01:24 -03:00
|
|
|
public:
|
2015-11-22 20:10:57 -04:00
|
|
|
I2CDriver(uint8_t bus);
|
|
|
|
I2CDriver(std::vector<const char *> devpaths);
|
2013-09-27 21:00:49 -03:00
|
|
|
|
2015-11-22 20:10:57 -04:00
|
|
|
void begin() { }
|
|
|
|
void end() { }
|
2013-09-22 03:01:24 -03:00
|
|
|
void setTimeout(uint16_t ms);
|
|
|
|
void setHighSpeed(bool active);
|
|
|
|
|
|
|
|
/* write: for i2c devices which do not obey register conventions */
|
|
|
|
uint8_t write(uint8_t addr, uint8_t len, uint8_t* data);
|
|
|
|
/* writeRegister: write a single 8-bit value to a register */
|
|
|
|
uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val);
|
2016-05-12 14:03:45 -03:00
|
|
|
/* writeRegisters: write bytes to contiguous registers */
|
2013-09-22 03:01:24 -03:00
|
|
|
uint8_t writeRegisters(uint8_t addr, uint8_t reg,
|
|
|
|
uint8_t len, uint8_t* data);
|
|
|
|
|
|
|
|
/* read: for i2c devices which do not obey register conventions */
|
|
|
|
uint8_t read(uint8_t addr, uint8_t len, uint8_t* data);
|
|
|
|
/* readRegister: read from a device register - writes the register,
|
|
|
|
* then reads back an 8-bit value. */
|
|
|
|
uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data);
|
2014-05-21 07:09:57 -03:00
|
|
|
|
2016-05-12 14:03:45 -03:00
|
|
|
/* readRegister: read contiguous device registers - writes the first
|
2013-09-22 03:01:24 -03:00
|
|
|
* register, then reads back multiple bytes */
|
|
|
|
uint8_t readRegisters(uint8_t addr, uint8_t reg,
|
|
|
|
uint8_t len, uint8_t* data);
|
|
|
|
|
2014-05-21 07:09:57 -03:00
|
|
|
uint8_t readRegistersMultiple(uint8_t addr, uint8_t reg,
|
|
|
|
uint8_t len, uint8_t count,
|
|
|
|
uint8_t* data);
|
|
|
|
|
2013-09-22 03:01:24 -03:00
|
|
|
uint8_t lockup_count();
|
|
|
|
|
2015-11-22 20:10:57 -04:00
|
|
|
AP_HAL::Semaphore *get_semaphore();
|
|
|
|
|
2015-11-26 09:25:40 -04:00
|
|
|
bool do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len,
|
|
|
|
uint8_t *recv, uint32_t recv_len)override;
|
2013-09-22 03:01:24 -03:00
|
|
|
|
|
|
|
private:
|
2013-09-27 21:00:49 -03:00
|
|
|
bool set_address(uint8_t addr);
|
2015-11-22 20:10:57 -04:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _fake_dev;
|
2015-06-24 19:01:13 -03:00
|
|
|
char *_device = NULL;
|
2013-09-27 21:00:49 -03:00
|
|
|
uint8_t _addr;
|
2015-09-28 05:46:41 -03:00
|
|
|
bool _print_ioctl_error = true;
|
2013-09-22 03:01:24 -03:00
|
|
|
};
|