32 #define MAX_I2C_DEVICES 10 45 typedef struct I2C_STATE {
70 static void lateInit();
75 inline void set_address(uint8_t address)
override { _address = address; }
78 inline void set_retries(uint8_t retries)
override { _retries = retries; }
84 bool transfer(
const uint8_t *send, uint32_t send_len,
85 uint8_t *recv, uint32_t recv_len)
override;
88 bool read_registers_multiple(uint8_t first_reg, uint8_t *recv,
89 uint32_t recv_len, uint8_t times);
100 uint32_t period_usec, Device::PeriodicCb proc)
override 114 void register_completion_callback(
Handler h);
118 register_completion_callback(r.
h);
122 register_completion_callback(r.
h);
139 uint32_t
i2c_read(uint8_t addr,
const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen);
140 uint32_t
i2c_write(uint8_t addr,
const uint8_t *tx_buff, uint8_t len);
142 uint32_t wait_stop_done(
bool v);
143 void finish_transfer();
178 void _do_bus_reset();
181 #define I2C_LOG_SIZE 99 182 static I2C_State log[I2C_LOG_SIZE];
183 static uint8_t log_ptr;
196 uint32_t bus_clock=400000,
197 bool use_smbus =
false,
198 uint32_t timeout_ms=4) {
203 for(uint8_t i=0; i<n; i++){
void register_completion_callback(AP_HAL::Proc proc)
uint8_t get_last_error_state()
#define MAX_I2C_DEVICES
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
AP_HAL::OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)
uint32_t i2c_write(const i2c_dev *dev, uint8_t addr, const uint8_t *tx_buff, uint8_t txlen)
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
void register_completion_callback(AP_HAL::MemberProc proc)
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void set_retries(uint8_t retries) override
F4Light::Semaphore * get_semaphore() override
static uint8_t get_dev_count()
static AP_HAL::Device::PeriodicHandle register_timer_task(uint32_t period_us, AP_HAL::Device::PeriodicCb proc, F4Light::Semaphore *sem)
bool unregister_callback(PeriodicHandle h) override
void set_address(uint8_t address) override
static bool adjust_timer_task(AP_HAL::Device::PeriodicHandle h, uint32_t period_us)
static bool unregister_timer_task(AP_HAL::Device::PeriodicHandle h)
static F4Light::I2CDevice * get_device(uint8_t i)
uint32_t get_error_count()
void init()
Generic board initialization function.
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb proc) override
uint32_t i2c_read(const i2c_dev *dev, uint8_t addr, const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen)
bool set_speed(enum AP_HAL::Device::Speed speed) override