APM:Libraries
BusTest.cpp
Go to the documentation of this file.
1 //
2 // scan I2C and SPI buses for expected devices
3 //
4 
5 #include <AP_Common/AP_Common.h>
6 #include <AP_HAL/AP_HAL.h>
7 
9 
10 static struct {
11  const char *name;
12  uint8_t whoami_reg;
13 } whoami_list[] = {
14  { "ms5611", 0x00 | 0x80 },
15  { "mpu9250", 0x75 | 0x80 },
16  { "mpu6000", 0x75 | 0x80 },
17  { "lsm9ds0_am", 0x0F | 0x80 },
18  { "lsm9ds0_g", 0x0F | 0x80 },
19 };
20 
22 get_device(const char *name)
23 {
25 
26  const char *spi_name = hal.spi->get_device_name(0);
27  /* Dummy is the default device at index 0
28  if there isn't registered device for the target board.
29  */
30  const char *dummy = "**dummy**";
31  if (!strcmp(dummy, spi_name)) {
32  hal.console->printf("No devices, nothing to do.\n");
33  while (1) {
34  hal.scheduler->delay(500);
35  }
36  }
37 
38  /* We get possible registered device count on the target board */
39  uint8_t spicount = hal.spi->get_count();
40  for (uint8_t ref = 0; ref < spicount; ref++) {
41  /*
42  * We get the name from the index and we compare
43  * with our possible devices list.
44  */
45  spi_name = hal.spi->get_device_name(ref);
46  if (!strcmp(name, spi_name)) {
47  dev = hal.spi->get_device(spi_name);
48  break;
49  }
50  }
51 
52  return dev;
53 }
54 
55 void setup(void)
56 {
57  hal.console->println("BusTest startup...\n");
58 }
59 
60 void loop(void)
61 {
63  AP_HAL::Semaphore *spi_sem;
64  const char *bus_type = new char;
65 
66  hal.console->printf("Scanning SPI and I2C bus devices\n");
67 
68  for (uint8_t i = 0; i < ARRAY_SIZE(whoami_list); i++) {
69  dev = get_device(whoami_list[i].name);
70  if (!dev) {
71  continue;
72  }
73 
74  if (dev->bus_type() == AP_HAL::Device::BusType::BUS_TYPE_SPI) {
75  bus_type = "SPI";
76  } else {
77  bus_type = "I2C";
78  }
79 
80  hal.console->printf("Device %s registered on %s bus\n", whoami_list[i].name, bus_type);
81  hal.console->printf("Trying to send data...\n");
82 
83  spi_sem = dev->get_semaphore();
84  if (!spi_sem->take(1000)) {
85  hal.console->printf("Failed to get SPI semaphore for %s\n", whoami_list[i].name);
86  break;
87  }
88  uint8_t tx[2] = { whoami_list[i].whoami_reg, 0 };
89  uint8_t rx[2] = { 0, 0 };
90  dev->transfer(tx, sizeof(tx), rx, sizeof(rx));
91  if (rx[1] != 0) {
92  hal.console->printf("WHO_AM_I for %s: 0x%02x\n\n", whoami_list[i].name, (unsigned)rx[1]);
93  } else {
94  hal.console->printf("No response %s!\n\n", whoami_list[i].name);
95  break;
96  }
97  spi_sem->give();
98  }
99 
100  hal.scheduler->delay(1000);
101 }
102 
103 AP_HAL_MAIN();
AP_HAL_MAIN()
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static struct @91 whoami_list[]
virtual AP_HAL::Semaphore * get_semaphore()=0
AP_HAL::OwnPtr< AP_HAL::Device > get_device(const char *name)
Definition: BusTest.cpp:22
virtual uint8_t get_count()
Definition: SPIDevice.h:74
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
const char * name
Definition: BusTest.cpp:11
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
enum BusType bus_type(void) const
Definition: Device.h:50
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: BusTest.cpp:8
void println(const char *str)
Definition: BetterStream.h:34
uint8_t whoami_reg
Definition: BusTest.cpp:12
virtual bool give()=0
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
void loop(void)
Definition: BusTest.cpp:60
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)=0
const HAL & get_HAL()
Common definitions and utility routines for the ArduPilot libraries.
virtual const char * get_device_name(uint8_t idx)
Definition: SPIDevice.h:77
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
void setup(void)
Definition: BusTest.cpp:55