14 {
"ms5611", 0x00 | 0x80 },
15 {
"mpu9250", 0x75 | 0x80 },
16 {
"mpu6000", 0x75 | 0x80 },
17 {
"lsm9ds0_am", 0x0F | 0x80 },
18 {
"lsm9ds0_g", 0x0F | 0x80 },
30 const char *dummy =
"**dummy**";
31 if (!strcmp(dummy, spi_name)) {
40 for (uint8_t ref = 0; ref < spicount; ref++) {
46 if (!strcmp(name, spi_name)) {
64 const char *bus_type =
new char;
74 if (dev->
bus_type() == AP_HAL::Device::BusType::BUS_TYPE_SPI) {
84 if (!spi_sem->
take(1000)) {
89 uint8_t rx[2] = { 0, 0 };
90 dev->
transfer(tx,
sizeof(tx), rx,
sizeof(rx));
AP_HAL::UARTDriver * console
static struct @91 whoami_list[]
virtual AP_HAL::Semaphore * get_semaphore()=0
AP_HAL::OwnPtr< AP_HAL::Device > get_device(const char *name)
virtual uint8_t get_count()
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
virtual OwnPtr< SPIDevice > get_device(const char *name)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
enum BusType bus_type(void) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void println(const char *str)
AP_HAL::SPIDeviceManager * spi
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)=0
Common definitions and utility routines for the ArduPilot libraries.
virtual const char * get_device_name(uint8_t idx)
AP_HAL::Scheduler * scheduler