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 < ARRAY_SIZE(whoami_list); 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(200); }
void setup (void) { hal.console->printf_P(PSTR("Starting Semaphore test\r\n")); setup_pin(PIN_A0); setup_pin(PIN_A1); setup_pin(PIN_A2); setup_pin(PIN_A3); hal.console->printf_P(PSTR("Using Dataflash's Semaphore\r\n")); AP_HAL::SPIDeviceDriver *dataflash = hal.spi->device( AP_HAL::SPIDevice_Dataflash); if (dataflash == NULL) { hal.scheduler->panic(PSTR("Error: No SPIDevice_Dataflash driver!")); } sem = dataflash->get_semaphore(); if (sem == NULL) { hal.scheduler->panic(PSTR("Error: No SPIDeviceDriver semaphore!")); } hal.scheduler->register_timer_process(async_blinker, NULL); }