3 changed files with 60 additions and 0 deletions
@ -0,0 +1,59 @@
@@ -0,0 +1,59 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- |
||||
|
||||
// |
||||
// scan I2C and SPI buses for expected devices |
||||
// |
||||
|
||||
#include <AP_Common.h> |
||||
#include <AP_Progmem.h> |
||||
#include <AP_HAL.h> |
||||
#include <AP_HAL_Linux.h> |
||||
#include <AP_HAL_Empty.h> |
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; |
||||
|
||||
void setup(void) |
||||
{ |
||||
hal.console->println("BusTest startup..."); |
||||
} |
||||
|
||||
static struct { |
||||
const char *name; |
||||
enum AP_HAL::SPIDevice dev; |
||||
uint8_t whoami_reg; |
||||
} whoami_list[] = { |
||||
{ "MPU9250", AP_HAL::SPIDevice_MPU9250, 0x75 | 0x80 }, |
||||
{ "LSM9DSO", AP_HAL::SPIDevice_LSM9DS0, 0x0f | 0x80 }, |
||||
{ "MPU6000", AP_HAL::SPIDevice_MPU6000, 0x75 | 0x80 }, |
||||
}; |
||||
|
||||
void loop(void) |
||||
{ |
||||
AP_HAL::SPIDeviceDriver *spi; |
||||
AP_HAL::Semaphore *spi_sem; |
||||
|
||||
hal.console->printf("Scanning SPI bus devices\n"); |
||||
|
||||
for (uint8_t i=0; i<sizeof(whoami_list)/sizeof(whoami_list[0]); i++) { |
||||
spi = hal.spi->device(whoami_list[i].dev); |
||||
if (spi == NULL) { |
||||
hal.console->printf("Failed to get SPI device for %s\n", whoami_list[i].name); |
||||
continue; |
||||
} |
||||
spi_sem = spi->get_semaphore(); |
||||
if (!spi_sem->take(1000)) { |
||||
hal.console->printf("Failed to get SPI semaphore for %s\n", whoami_list[i].name); |
||||
continue; |
||||
} |
||||
uint8_t tx[2] = { whoami_list[i].whoami_reg, 0 }; |
||||
uint8_t rx[2]; |
||||
|
||||
spi->transaction(tx, rx, 2); |
||||
|
||||
hal.console->printf("WHO_AM_I for %s: 0x%02x\n", whoami_list[i].name, (unsigned)rx[1]); |
||||
spi_sem->give(); |
||||
} |
||||
hal.scheduler->delay(2000); |
||||
} |
||||
|
||||
AP_HAL_MAIN(); |
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
include ../../../../mk/apm.mk |
Loading…
Reference in new issue