ardupilot/libraries/AP_HAL_Linux/I2CDriver.h
Lucas De Marchi e40785b002 AP_HAL_Linux: Add fake device to I2CDriver
This allows us to re-use I2CDevice from I2CDriver while the drivers are
converted.  We create a fake device with addr = 0 for each I2CDriver but
we only use the register/unregister logic. The transfer logic still uses
the methods from I2CDriver in order to use the right address.

Now we can interoperate I2CDevice drivers with the ones base in
I2CDriver since they are going to use the same semaphore and bus.

The I2CDriver constructors were changed to re-use the logic in I2CDevice
(it uses a number rather than an string) and the semaphore doesn't live
outside anymore, its embedded in the fake I2CDevice, as well as the
bus's file descritor.
2016-02-16 19:49:09 -02:00

61 lines
2.0 KiB
C++

#ifndef __AP_HAL_LINUX_I2CDRIVER_H__
#define __AP_HAL_LINUX_I2CDRIVER_H__
#include <vector>
#include <AP_HAL/utility/OwnPtr.h>
#include "AP_HAL_Linux.h"
#include "I2CDevice.h"
class Linux::I2CDriver : public AP_HAL::I2CDriver {
public:
I2CDriver(uint8_t bus);
I2CDriver(std::vector<const char *> devpaths);
void begin() { }
void end() { }
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);
/* writeRegisters: write bytes to contigious registers */
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);
/* readRegister: read contigious device registers - writes the first
* register, then reads back multiple bytes */
uint8_t readRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data);
uint8_t readRegistersMultiple(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t count,
uint8_t* data);
uint8_t lockup_count();
AP_HAL::Semaphore *get_semaphore();
bool do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len,
uint8_t *recv, uint32_t recv_len)override;
private:
bool set_address(uint8_t addr);
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _fake_dev;
char *_device = NULL;
uint8_t _addr;
bool _print_ioctl_error = true;
};
#endif // __AP_HAL_LINUX_I2CDRIVER_H__