ardupilot/libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/SPIDriver.cpp
Caio Marcelo de Oliveira Filho 2e464a53c2 AP_HAL: make code not depend on concrete HAL implementations
The switching between different AP_HAL was happening by giving different
definitions of AP_HAL_BOARD_DRIVER, and the programs would use it to
instantiate.

A program or library code would have to explicitly include (and depend)
on the concrete implementation of the HAL, even when using it only via
interface.

The proposed change move this dependency to be link time. There is a
AP_HAL::get_HAL() function that is used by the client code. Each
implementation of HAL provides its own definition of this function,
returning the appropriate concrete instance.

Since this replaces the job of AP_HAL_BOARD_DRIVER, the definition was
removed.

The static variables for PX4 and VRBRAIN were named differently to avoid
shadowing the extern symbol 'hal'.
2015-10-21 09:16:07 +11:00

39 lines
1.2 KiB
C++

#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
// Loopback test for SPI driver
// Connect MISO and MOSI pins together (12 and 13 on Flymaple)
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_HAL::SPIDeviceDriver* spidev;
void setup (void) {
hal.scheduler->delay(5000);
hal.console->printf_P(PSTR("Starting AP_HAL_FLYMAPLE::SPIDriver test\r\n"));
spidev = hal.spi->device(AP_HAL::SPIDevice_MPU6000); // Not really MPU6000, just a generic SPU driver
if (!spidev)
hal.scheduler->panic(PSTR("Starting AP_HAL_FLYMAPLE::SPIDriver failed to get spidev\r\n"));
}
void loop (void) {
uint8_t tx_data[] = { 'h', 'e', 'l', 'l', 'o', 0 };
uint8_t rx_data[] = { 0, 0, 0, 0, 0, 0 };
spidev->transaction(tx_data, rx_data, sizeof(tx_data));
if (memcmp(tx_data, rx_data, sizeof(tx_data)))
hal.console->println("Incorrect data read from SPI loopback. Do you have the loopback wire installed between pins 11 and 12?");
else
hal.console->println("Correct data read from SPI loopback");
hal.scheduler->delay(500);
}
AP_HAL_MAIN();