39 uint8_t *&buf_rx, uint16_t rx_len);
50 AP_HAL::Device::PeriodicCb
cb;
struct ChibiOS::DeviceBus::callback_info * callbacks
uint16_t bounce_buffer_tx_size
void bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len, uint8_t *&buf_rx, uint16_t rx_len)
DeviceBus(uint8_t _thread_priority=APM_I2C_PRIORITY)
uint8_t * bounce_buffer_rx
static void bus_thread(void *arg)
uint8_t * bounce_buffer_tx
void bouncebuffer_setup_tx(const uint8_t *&buf_tx, uint16_t tx_len)
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device)
uint16_t bounce_buffer_rx_size
bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
AP_HAL::Device::PeriodicCb cb
void bouncebuffer_setup_rx(uint8_t *&buf_rx, uint16_t rx_len)
struct callback_info * next
AP_HAL::Device * hal_device
void bouncebuffer_rx_copy(uint8_t *buf_rx, uint16_t rx_len)