31 mavlink_device_op_read_t packet;
32 mavlink_msg_device_op_read_decode(msg, &packet);
35 uint8_t data[
sizeof(mavlink_device_op_read_reply_t::data)] {};
37 if (packet.bustype == DEVICE_OP_BUSTYPE_I2C) {
39 }
else if (packet.bustype == DEVICE_OP_BUSTYPE_SPI) {
59 mavlink_msg_device_op_read_reply_send(
69 mavlink_msg_device_op_read_reply_send(
83 mavlink_device_op_write_t packet;
84 mavlink_msg_device_op_write_decode(msg, &packet);
88 if (packet.bustype == DEVICE_OP_BUSTYPE_I2C) {
90 }
else if (packet.bustype == DEVICE_OP_BUSTYPE_SPI) {
104 for (uint8_t i=0; i<packet.count; i++) {
113 mavlink_msg_device_op_write_reply_send(
void handle_device_op_read(mavlink_message_t *msg)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Interface definition for the various Ground Control System.
void handle_device_op_write(mavlink_message_t *msg)
virtual AP_HAL::Semaphore * get_semaphore()=0
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
void fail(const char *why)
virtual OwnPtr< SPIDevice > get_device(const char *name)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
AP_HAL::SPIDeviceManager * spi
AP_HAL::I2CDeviceManager * i2c_mgr
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
virtual 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)=0
bool write_register(uint8_t reg, uint8_t val, bool checked=false)