diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index 2d58c00569..f0537384cb 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -33,7 +33,7 @@ #include "Rover.h" -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); Rover rover; diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index 0bc1c30dbe..b69eca0be7 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -117,7 +117,7 @@ void Tracker::one_second_loop() AP_ADC_ADS7844 apm1_adc; #endif -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); Tracker::Tracker(void) { diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 0ef6474da0..448c008c2a 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -19,7 +19,7 @@ constructor for main Copter class */ -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); Copter::Copter(void) : ins_sample_rate(AP_InertialSensor::RATE_400HZ), diff --git a/ArduPlane/Plane.cpp b/ArduPlane/Plane.cpp index 16da4bc3ae..2529166341 100644 --- a/ArduPlane/Plane.cpp +++ b/ArduPlane/Plane.cpp @@ -20,7 +20,7 @@ constructor for main Plane class */ -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); Plane::Plane(void) { diff --git a/Tools/CPUInfo/CPUInfo.cpp b/Tools/CPUInfo/CPUInfo.cpp index 0f19e8e9df..114363704d 100644 --- a/Tools/CPUInfo/CPUInfo.cpp +++ b/Tools/CPUInfo/CPUInfo.cpp @@ -39,7 +39,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup() { } diff --git a/Tools/Hello/Hello.cpp b/Tools/Hello/Hello.cpp index f1038cac6f..36d18e48a9 100644 --- a/Tools/Hello/Hello.cpp +++ b/Tools/Hello/Hello.cpp @@ -30,7 +30,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup() { hal.console->println_P(PSTR("hello world")); diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 18a0b8e180..a8970fe2ed 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -72,7 +72,7 @@ #define streq(x, y) (!strcmp(x, y)) -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); class ReplayVehicle { public: diff --git a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp index b17e68d1c1..7bed91970c 100644 --- a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp +++ b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp @@ -38,7 +38,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); // default PID values #define TEST_P 1.0f diff --git a/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp b/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp index f3aa6446eb..23c0e2cea2 100644 --- a/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp +++ b/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp @@ -22,7 +22,7 @@ uint32_t timer; #if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX /* Only build this sketch for APM1 and Linux */ -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_ADC_ADS7844 adc; diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index 228cb473d4..76d4f10a8f 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -43,7 +43,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); // INS and Baro declaration AP_InertialSensor ins; diff --git a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp index 2368affe61..543935c799 100644 --- a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp +++ b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp @@ -55,7 +55,7 @@ AP_ADC_ADS7844 apm1_adc; #endif -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static AP_Vehicle::FixedWing aparm; diff --git a/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp b/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp index f9f714d06c..3dd44c8ea4 100644 --- a/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp +++ b/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp @@ -36,7 +36,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static AP_Baro barometer; diff --git a/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp b/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp index 1fdfb32d2f..772d69910e 100644 --- a/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp +++ b/libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp @@ -33,7 +33,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_BattMonitor battery_mon; uint32_t timer; diff --git a/libraries/AP_Common/examples/AP_Common/AP_Common.cpp b/libraries/AP_Common/examples/AP_Common/AP_Common.cpp index 8440766556..3c76e8615c 100644 --- a/libraries/AP_Common/examples/AP_Common/AP_Common.cpp +++ b/libraries/AP_Common/examples/AP_Common/AP_Common.cpp @@ -15,7 +15,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void test_high_low_byte(void) { diff --git a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp index c28bc89809..dbf2c4294f 100644 --- a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp +++ b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp @@ -38,7 +38,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static Compass compass; diff --git a/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp b/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp index 16cd246c87..c89f80afc8 100644 --- a/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp +++ b/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp @@ -12,7 +12,7 @@ #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static const int16_t dec_tbl[37][73] = \ { \ diff --git a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp index 4361a8e491..778b9f46a0 100644 --- a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp +++ b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp @@ -40,7 +40,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); // create board led object AP_BoardLED board_led; diff --git a/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp b/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp index 49748c9b07..258130ed90 100644 --- a/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp +++ b/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp @@ -39,7 +39,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup() { diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 6d85476432..0b4856d0f6 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -117,14 +117,7 @@ */ -/* - define AP_HAL_BOARD_DRIVER to the right hal type for this - board. This prevents us having a mess of ifdefs in every example - sketch - */ - #if CONFIG_HAL_BOARD == HAL_BOARD_APM1 -#define AP_HAL_BOARD_DRIVER AP_HAL_AVR_APM1 #define HAL_BOARD_NAME "APM 1" #define HAL_CPU_CLASS HAL_CPU_CLASS_16 #define HAL_STORAGE_SIZE 4096 @@ -137,7 +130,6 @@ #endif #elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 -#define AP_HAL_BOARD_DRIVER AP_HAL_AVR_APM2 #define HAL_BOARD_NAME "APM 2" #define HAL_CPU_CLASS HAL_CPU_CLASS_16 #define HAL_STORAGE_SIZE 4096 @@ -154,7 +146,6 @@ #endif #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL -#define AP_HAL_BOARD_DRIVER AP_HAL_SITL #define HAL_BOARD_NAME "SITL" #define HAL_CPU_CLASS HAL_CPU_CLASS_1000 #define HAL_OS_POSIX_IO 1 @@ -169,7 +160,6 @@ #define HAL_COMPASS_DEFAULT HAL_COMPASS_HIL #elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE -#define AP_HAL_BOARD_DRIVER AP_HAL_FLYMAPLE #define HAL_BOARD_NAME "FLYMAPLE" #define HAL_CPU_CLASS HAL_CPU_CLASS_75 #define HAL_STORAGE_SIZE 4096 @@ -181,7 +171,6 @@ #define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE #elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 -#define AP_HAL_BOARD_DRIVER AP_HAL_PX4 #define HAL_BOARD_NAME "PX4" #define HAL_CPU_CLASS HAL_CPU_CLASS_150 #define HAL_OS_POSIX_IO 1 @@ -201,7 +190,6 @@ #endif #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX -#define AP_HAL_BOARD_DRIVER AP_HAL_Linux #define HAL_BOARD_NAME "Linux" #define HAL_CPU_CLASS HAL_CPU_CLASS_1000 #define HAL_OS_POSIX_IO 1 @@ -270,7 +258,6 @@ #endif #elif CONFIG_HAL_BOARD == HAL_BOARD_EMPTY -#define AP_HAL_BOARD_DRIVER AP_HAL_Empty #define HAL_BOARD_NAME "EMPTY" #define HAL_CPU_CLASS HAL_CPU_CLASS_16 #define HAL_STORAGE_SIZE 4096 @@ -281,7 +268,6 @@ #define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE #elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN -#define AP_HAL_BOARD_DRIVER AP_HAL_VRBRAIN #define HAL_BOARD_NAME "VRBRAIN" #define HAL_CPU_CLASS HAL_CPU_CLASS_150 #define HAL_OS_POSIX_IO 1 diff --git a/libraries/AP_HAL/AP_HAL_Namespace.h b/libraries/AP_HAL/AP_HAL_Namespace.h index cefcede824..bd4da93bd4 100644 --- a/libraries/AP_HAL/AP_HAL_Namespace.h +++ b/libraries/AP_HAL/AP_HAL_Namespace.h @@ -62,6 +62,8 @@ namespace AP_HAL { SPIDevice_RASPIO = 12 }; + // Must be implemented by the concrete HALs. + const HAL& get_HAL(); } #endif // __AP_HAL_NAMESPACE_H__ diff --git a/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp b/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp index b421413b55..99cf093eb0 100644 --- a/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp +++ b/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp @@ -11,7 +11,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_HAL::AnalogSource* ch; diff --git a/libraries/AP_HAL/examples/Printf/Printf.cpp b/libraries/AP_HAL/examples/Printf/Printf.cpp index b642d0f301..5c347bcd24 100644 --- a/libraries/AP_HAL/examples/Printf/Printf.cpp +++ b/libraries/AP_HAL/examples/Printf/Printf.cpp @@ -31,7 +31,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup(void) { hal.console->println_P(PSTR("Starting Printf test")); diff --git a/libraries/AP_HAL/examples/RCInput/RCInput.cpp b/libraries/AP_HAL/examples/RCInput/RCInput.cpp index 847e428070..b673c7bf70 100644 --- a/libraries/AP_HAL/examples/RCInput/RCInput.cpp +++ b/libraries/AP_HAL/examples/RCInput/RCInput.cpp @@ -36,7 +36,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define MAX_CHANNELS 16 diff --git a/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp b/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp index d8c01f27a6..27e20b7a3c 100644 --- a/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp +++ b/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp @@ -39,7 +39,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define MAX_CHANNELS 14 diff --git a/libraries/AP_HAL/examples/RCOutput/RCOutput.cpp b/libraries/AP_HAL/examples/RCOutput/RCOutput.cpp index f82741f3a4..edc38d4138 100644 --- a/libraries/AP_HAL/examples/RCOutput/RCOutput.cpp +++ b/libraries/AP_HAL/examples/RCOutput/RCOutput.cpp @@ -36,7 +36,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup (void) { diff --git a/libraries/AP_HAL/examples/Storage/Storage.cpp b/libraries/AP_HAL/examples/Storage/Storage.cpp index 38721ac98f..61ed2c1e16 100644 --- a/libraries/AP_HAL/examples/Storage/Storage.cpp +++ b/libraries/AP_HAL/examples/Storage/Storage.cpp @@ -41,7 +41,7 @@ #include #endif -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_HAL::Storage *st; diff --git a/libraries/AP_HAL/examples/UART_test/UART_test.cpp b/libraries/AP_HAL/examples/UART_test/UART_test.cpp index cee4be3a2a..3e1dc52f30 100644 --- a/libraries/AP_HAL/examples/UART_test/UART_test.cpp +++ b/libraries/AP_HAL/examples/UART_test/UART_test.cpp @@ -40,7 +40,7 @@ #include #endif -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static AP_HAL::UARTDriver* uarts[] = { hal.uartA, // console diff --git a/libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp b/libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp index 973ea85265..b27b73b698 100644 --- a/libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp +++ b/libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp @@ -86,6 +86,9 @@ void HAL_AVR_APM1::init(int argc, char * const argv[]) const { PORTJ |= _BV(0); }; -const HAL_AVR_APM1 AP_HAL_AVR_APM1; +const AP_HAL::HAL& AP_HAL::get_HAL() { + static const HAL_AVR_APM1 hal; + return hal; +} #endif // CONFIG_HAL_BOARD == HAL_BOARD_APM1 diff --git a/libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp b/libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp index 6a83ed917f..638c06c8f8 100644 --- a/libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp +++ b/libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp @@ -85,6 +85,9 @@ void HAL_AVR_APM2::init(int argc, char * const argv[]) const { PORTH |= _BV(0); }; -const HAL_AVR_APM2 AP_HAL_AVR_APM2; +const AP_HAL::HAL& AP_HAL::get_HAL() { + static const HAL_AVR_APM2 hal; + return hal; +} #endif // CONFIG_HAL_BOARD == HAL_BOARD_APM2 diff --git a/libraries/AP_HAL_AVR/examples/Semaphore/Semaphore.cpp b/libraries/AP_HAL_AVR/examples/Semaphore/Semaphore.cpp index e9fef7c6f1..03387fe725 100644 --- a/libraries/AP_HAL_AVR/examples/Semaphore/Semaphore.cpp +++ b/libraries/AP_HAL_AVR/examples/Semaphore/Semaphore.cpp @@ -6,7 +6,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); /** * You'll want to use a logic analyzer to watch the effects of this test. diff --git a/libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.cpp b/libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.cpp index b1fb79047e..596cef86ba 100644 --- a/libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.cpp +++ b/libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.cpp @@ -11,7 +11,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void test_snprintf_P() { char test[40]; diff --git a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp index a5fccd7227..c55a2d4599 100644 --- a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp +++ b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp @@ -52,6 +52,9 @@ void HAL_Empty::init(int argc,char* const argv[]) const { _member->init(); } -const HAL_Empty AP_HAL_Empty; +const AP_HAL::HAL& AP_HAL::get_HAL() { + static const HAL_Empty hal; + return hal; +} #endif diff --git a/libraries/AP_HAL_Empty/examples/empty_example/empty_example.cpp b/libraries/AP_HAL_Empty/examples/empty_example/empty_example.cpp index dc4ecf27da..86a6744f77 100644 --- a/libraries/AP_HAL_Empty/examples/empty_example/empty_example.cpp +++ b/libraries/AP_HAL_Empty/examples/empty_example/empty_example.cpp @@ -10,7 +10,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup() { hal.console->println_P(PSTR("Empty setup")); diff --git a/libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp b/libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp index f8da648d4c..327e9ea927 100644 --- a/libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp +++ b/libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp @@ -85,6 +85,9 @@ void HAL_FLYMAPLE::init(int argc,char* const argv[]) const { storage->init(NULL); // Uses EEPROM.*, flash_stm* copied from AeroQuad_v3.2 } -const HAL_FLYMAPLE AP_HAL_FLYMAPLE; +const AP_HAL::HAL& AP_HAL::get_HAL() { + static const HAL_FLYMAPLE hal; + return hal; +} #endif diff --git a/libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.cpp b/libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.cpp index 743348e257..1cf9ef3f96 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.cpp @@ -24,7 +24,7 @@ #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_Baro_BMP085 bmp085; diff --git a/libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/AnalogIn.cpp b/libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/AnalogIn.cpp index d0ee74e8e2..2f32ebcee7 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/AnalogIn.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/AnalogIn.cpp @@ -14,7 +14,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); // Expects pin 15 to be connected to board VCC 3.3V static AP_HAL::AnalogSource *vcc_pin; // GPIO pin 15 diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Blink/Blink.cpp b/libraries/AP_HAL_FLYMAPLE/examples/Blink/Blink.cpp index 0bd46d4096..5b7584d52d 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Blink/Blink.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/Blink/Blink.cpp @@ -7,7 +7,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_HAL::DigitalSource *a_led; AP_HAL::DigitalSource *b_led; diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Console/Console.cpp b/libraries/AP_HAL_FLYMAPLE/examples/Console/Console.cpp index 1923010839..847599550d 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Console/Console.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/Console/Console.cpp @@ -15,7 +15,7 @@ #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup(void) { diff --git a/libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.cpp b/libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.cpp index ac576b4b20..3d37ebfe55 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.cpp @@ -12,7 +12,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define HMC5883L 0x1E diff --git a/libraries/AP_HAL_FLYMAPLE/examples/RCInput/RCInput.cpp b/libraries/AP_HAL_FLYMAPLE/examples/RCInput/RCInput.cpp index 5e65ee9be7..174dd6584a 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/RCInput/RCInput.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/RCInput/RCInput.cpp @@ -7,7 +7,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void multiread(AP_HAL::RCInput* in, uint16_t* channels) { /* Multi-channel read method: */ diff --git a/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.cpp b/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.cpp index ac88a6773c..563852507b 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.cpp @@ -7,7 +7,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void multiread(AP_HAL::RCInput* in, uint16_t* channels) { /* Multi-channel read method: */ diff --git a/libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/SPIDriver.cpp b/libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/SPIDriver.cpp index f3f9b98368..1ccd3efe2f 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/SPIDriver.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/SPIDriver.cpp @@ -10,7 +10,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_HAL::SPIDeviceDriver* spidev; diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Scheduler/Scheduler.cpp b/libraries/AP_HAL_FLYMAPLE/examples/Scheduler/Scheduler.cpp index 51e5449f90..ef10509f70 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Scheduler/Scheduler.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/Scheduler/Scheduler.cpp @@ -7,7 +7,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); /** * You'll want to use a logic analyzer to watch the effects of this test. diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Semaphore/Semaphore.cpp b/libraries/AP_HAL_FLYMAPLE/examples/Semaphore/Semaphore.cpp index bd8fa7e3ab..cd7c34b893 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Semaphore/Semaphore.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/Semaphore/Semaphore.cpp @@ -6,7 +6,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); /** * You'll want to use a logic analyzer to watch the effects of this test. diff --git a/libraries/AP_HAL_FLYMAPLE/examples/Storage/Storage.cpp b/libraries/AP_HAL_FLYMAPLE/examples/Storage/Storage.cpp index 28607c203f..f912bace44 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/Storage/Storage.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/Storage/Storage.cpp @@ -7,7 +7,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); uint8_t fibs[] = { 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 0 }; diff --git a/libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/UARTDriver.cpp b/libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/UARTDriver.cpp index 222b63d5ed..b84a7f1eec 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/UARTDriver.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/UARTDriver.cpp @@ -14,7 +14,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup(void) { diff --git a/libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/UtilityStringTest.cpp b/libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/UtilityStringTest.cpp index 0a50624f41..dd0019e35a 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/UtilityStringTest.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/UtilityStringTest.cpp @@ -10,7 +10,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void test_snprintf_P() { char test[40]; diff --git a/libraries/AP_HAL_FLYMAPLE/examples/empty_example/empty_example.cpp b/libraries/AP_HAL_FLYMAPLE/examples/empty_example/empty_example.cpp index 1fce6400b6..3f3555b92b 100644 --- a/libraries/AP_HAL_FLYMAPLE/examples/empty_example/empty_example.cpp +++ b/libraries/AP_HAL_FLYMAPLE/examples/empty_example/empty_example.cpp @@ -6,7 +6,7 @@ #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup() { hal.scheduler->delay(5000); diff --git a/libraries/AP_HAL_Linux/GPIO.cpp b/libraries/AP_HAL_Linux/GPIO.cpp index 664d22df5d..9a308226b9 100644 --- a/libraries/AP_HAL_Linux/GPIO.cpp +++ b/libraries/AP_HAL_Linux/GPIO.cpp @@ -5,7 +5,7 @@ using namespace Linux; -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); LinuxDigitalSource::LinuxDigitalSource(uint8_t v) : _v(v) @@ -33,4 +33,4 @@ void LinuxDigitalSource::toggle() write(!read()); } -#endif \ No newline at end of file +#endif diff --git a/libraries/AP_HAL_Linux/GPIO_BBB.cpp b/libraries/AP_HAL_Linux/GPIO_BBB.cpp index 011645ed79..ec01377f19 100644 --- a/libraries/AP_HAL_Linux/GPIO_BBB.cpp +++ b/libraries/AP_HAL_Linux/GPIO_BBB.cpp @@ -17,7 +17,7 @@ using namespace Linux; -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); LinuxGPIO_BBB::LinuxGPIO_BBB() {} diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.cpp b/libraries/AP_HAL_Linux/GPIO_RPI.cpp index f9164a266e..89d3cd9bb5 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.cpp +++ b/libraries/AP_HAL_Linux/GPIO_RPI.cpp @@ -18,7 +18,7 @@ using namespace Linux; -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); LinuxGPIO_RPI::LinuxGPIO_RPI() {} @@ -198,4 +198,4 @@ bool LinuxGPIO_RPI::usb_connected(void) return false; } -#endif // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT \ No newline at end of file +#endif // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index 25ca0a5e2b..1e1565ef46 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -236,6 +236,9 @@ void HAL_Linux::init(int argc,char* const argv[]) const utilInstance.init(argc+gopt.optind-1, &argv[gopt.optind-1]); } -const HAL_Linux AP_HAL_Linux; +const AP_HAL::HAL& AP_HAL::get_HAL() { + static const HAL_Linux hal; + return hal; +} #endif diff --git a/libraries/AP_HAL_Linux/RCInput_Raspilot.cpp b/libraries/AP_HAL_Linux/RCInput_Raspilot.cpp index 304a109d5a..53f7881fce 100644 --- a/libraries/AP_HAL_Linux/RCInput_Raspilot.cpp +++ b/libraries/AP_HAL_Linux/RCInput_Raspilot.cpp @@ -15,7 +15,7 @@ #include "px4io_protocol.h" -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); using namespace Linux; diff --git a/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp b/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp index 9ae9ad4354..7195a380af 100644 --- a/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp @@ -27,7 +27,7 @@ using namespace Linux; -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static void catch_sigbus(int sig) { diff --git a/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp b/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp index 00cf1a622e..11bb17ddc5 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp @@ -89,7 +89,7 @@ enum { using namespace Linux; -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); LinuxRCOutput_Bebop::LinuxRCOutput_Bebop(): _i2c_sem(NULL), diff --git a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp index 35e6897b17..97aa3f9275 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp @@ -54,7 +54,7 @@ using namespace Linux; #define PWM_CHAN_COUNT 16 -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); LinuxRCOutput_PCA9685::LinuxRCOutput_PCA9685(uint8_t addr, bool external_clock, diff --git a/libraries/AP_HAL_Linux/RCOutput_PRU.cpp b/libraries/AP_HAL_Linux/RCOutput_PRU.cpp index 3d6f5801ff..206136d4ca 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PRU.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_PRU.cpp @@ -24,7 +24,7 @@ using namespace Linux; static const uint8_t chan_pru_map[]= {10,8,11,9,7,6,5,4,3,2,1,0}; //chan_pru_map[CHANNEL_NUM] = PRU_REG_R30/31_NUM; static const uint8_t pru_chan_map[]= {11,10,9,8,7,6,5,4,1,3,0,2}; //pru_chan_map[PRU_REG_R30/31_NUM] = CHANNEL_NUM; -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static void catch_sigbus(int sig) { hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n"); diff --git a/libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp b/libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp index 1608a4b8d7..c2664b8cf4 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp @@ -20,7 +20,7 @@ using namespace Linux; #define PWM_CHAN_COUNT 8 -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void LinuxRCOutput_Raspilot::init(void* machtnicht) { diff --git a/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp b/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp index 8b8d90ff2e..909124ecb2 100644 --- a/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp @@ -20,7 +20,7 @@ using namespace Linux; #define PWM_CHAN_COUNT 8 // FIXME -static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static void catch_sigbus(int sig) { hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n"); diff --git a/libraries/AP_HAL_Linux/examples/BusTest/BusTest.cpp b/libraries/AP_HAL_Linux/examples/BusTest/BusTest.cpp index c8ec818b72..d70b8f80fa 100644 --- a/libraries/AP_HAL_Linux/examples/BusTest/BusTest.cpp +++ b/libraries/AP_HAL_Linux/examples/BusTest/BusTest.cpp @@ -13,7 +13,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup(void) { diff --git a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp index 47b8e83063..2da60e08bf 100644 --- a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp +++ b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp @@ -307,7 +307,10 @@ void HAL_PX4::init(int argc, char * const argv[]) const exit(1); } -const HAL_PX4 AP_HAL_PX4; +const AP_HAL::HAL& AP_HAL::get_HAL() { + static const HAL_PX4 hal_px4; + return hal_px4; +} #endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/AP_HAL_PX4/examples/simple/simple.cpp b/libraries/AP_HAL_PX4/examples/simple/simple.cpp index d03674fc12..f642f242df 100644 --- a/libraries/AP_HAL_PX4/examples/simple/simple.cpp +++ b/libraries/AP_HAL_PX4/examples/simple/simple.cpp @@ -39,7 +39,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup() { hal.console->println_P(PSTR("hello world")); diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index c76c36911f..efd9e8043e 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -79,6 +79,9 @@ void HAL_SITL::init(int argc, char * const argv[]) const analogin->init(NULL); } -const HAL_SITL AP_HAL_SITL; +const AP_HAL::HAL& AP_HAL::get_HAL() { + static const HAL_SITL hal; + return hal; +} #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp b/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp index 779cde622e..c62fca3277 100644 --- a/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp +++ b/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp @@ -339,7 +339,10 @@ void HAL_VRBRAIN::init(int argc, char * const argv[]) const exit(1); } -const HAL_VRBRAIN AP_HAL_VRBRAIN; +const AP_HAL::HAL& AP_HAL::get_HAL() { + static const HAL_VRBRAIN hal_vrbrain; + return hal_vrbrain; +} #endif // CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN diff --git a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp index dd72d978c0..9638069e3e 100644 --- a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp +++ b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp @@ -41,7 +41,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_InertialSensor ins; diff --git a/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp b/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp index e43f548353..04b7a88160 100644 --- a/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp +++ b/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp @@ -50,7 +50,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static int accel_fd[INS_MAX_INSTANCES]; static int gyro_fd[INS_MAX_INSTANCES]; @@ -210,7 +210,7 @@ void loop(void) } #else -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup() {} void loop() {} #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_Math/examples/eulers/eulers.cpp b/libraries/AP_Math/examples/eulers/eulers.cpp index e5a9896684..921932e85c 100644 --- a/libraries/AP_Math/examples/eulers/eulers.cpp +++ b/libraries/AP_Math/examples/eulers/eulers.cpp @@ -37,7 +37,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define SHOW_POLES_BREAKDOWN 0 diff --git a/libraries/AP_Math/examples/location/location.cpp b/libraries/AP_Math/examples/location/location.cpp index 288f4cb851..26cc8f1394 100644 --- a/libraries/AP_Math/examples/location/location.cpp +++ b/libraries/AP_Math/examples/location/location.cpp @@ -37,7 +37,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static const struct { Vector2f wp1, wp2, location; diff --git a/libraries/AP_Math/examples/polygon/polygon.cpp b/libraries/AP_Math/examples/polygon/polygon.cpp index 08b5fb7220..ec6aa3946d 100644 --- a/libraries/AP_Math/examples/polygon/polygon.cpp +++ b/libraries/AP_Math/examples/polygon/polygon.cpp @@ -12,7 +12,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); /* * this is the boundary of the 2010 outback challenge diff --git a/libraries/AP_Math/examples/rotations/rotations.cpp b/libraries/AP_Math/examples/rotations/rotations.cpp index 911098a98d..97495b8441 100644 --- a/libraries/AP_Math/examples/rotations/rotations.cpp +++ b/libraries/AP_Math/examples/rotations/rotations.cpp @@ -37,7 +37,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static void print_vector(Vector3f &v) { diff --git a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp index 523bb19f60..1348d8e9ee 100644 --- a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp +++ b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp @@ -38,7 +38,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); class MissionTest { public: diff --git a/libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.cpp b/libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.cpp index 8b690d7d4b..59ab05a8dc 100644 --- a/libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.cpp @@ -37,7 +37,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); RC_Channel rc1(0), rc2(1), rc3(2), rc4(3); diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index 89d6a1fe0f..0a84242bb8 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -37,7 +37,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); RC_Channel rc1(0), rc2(1), rc3(2), rc4(3); diff --git a/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp b/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp index 1c6eb3eefb..0183e7401f 100644 --- a/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp +++ b/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp @@ -30,7 +30,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup () { hal.console->println_P(PSTR("Unit test for AP_Mount. This sketch" diff --git a/libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp b/libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp index c8d64636d6..29fc705bc4 100644 --- a/libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp +++ b/libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp @@ -18,7 +18,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); // create board led object AP_BoardLED board_led; diff --git a/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp b/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp index e62e4fe9ae..8a12c0cc17 100644 --- a/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp +++ b/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp @@ -34,7 +34,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 static ToshibaLED_PX4 toshiba_led; diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp index 8842526bd0..c64c9aea67 100644 --- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp +++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp @@ -30,7 +30,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static OpticalFlow optflow; diff --git a/libraries/AP_Parachute/examples/AP_Parachute_test/AP_Parachute_test.cpp b/libraries/AP_Parachute/examples/AP_Parachute_test/AP_Parachute_test.cpp index 6ea39dd550..1a9b4b7ae1 100644 --- a/libraries/AP_Parachute/examples/AP_Parachute_test/AP_Parachute_test.cpp +++ b/libraries/AP_Parachute/examples/AP_Parachute_test/AP_Parachute_test.cpp @@ -15,7 +15,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); // Relay AP_Relay relay; diff --git a/libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp b/libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp index f6e40485d7..8109cad5ae 100644 --- a/libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp +++ b/libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp @@ -12,7 +12,7 @@ #include #include // PerfMonitor library -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); AP_PERFMON_REGISTER_FN(setup) AP_PERFMON_REGISTER_FN(loop) diff --git a/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp b/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp index dd2f85bd1c..8e85f92644 100644 --- a/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp +++ b/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp @@ -36,7 +36,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static AP_SerialManager serial_manager; static RangeFinder sonar {serial_manager}; diff --git a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp index 5e15cdda15..1afda837e8 100644 --- a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp +++ b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp @@ -40,7 +40,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); class SchedTest { public: diff --git a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp index c2b481198d..7171046c6a 100644 --- a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp +++ b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp @@ -39,7 +39,7 @@ #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define LOG_TEST_MSG 1 diff --git a/libraries/Filter/examples/Derivative/Derivative.cpp b/libraries/Filter/examples/Derivative/Derivative.cpp index 6721eaf151..c04040f6c5 100644 --- a/libraries/Filter/examples/Derivative/Derivative.cpp +++ b/libraries/Filter/examples/Derivative/Derivative.cpp @@ -13,7 +13,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); DerivativeFilter derivative; diff --git a/libraries/Filter/examples/Filter/Filter.cpp b/libraries/Filter/examples/Filter/Filter.cpp index 8899650b76..0c8e95a006 100644 --- a/libraries/Filter/examples/Filter/Filter.cpp +++ b/libraries/Filter/examples/Filter/Filter.cpp @@ -16,7 +16,7 @@ #include // ModeFilter class (inherits from Filter class) #include // AverageFilter class (inherits from Filter class) -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); int16_t rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000}; diff --git a/libraries/Filter/examples/LowPassFilter/LowPassFilter.cpp b/libraries/Filter/examples/LowPassFilter/LowPassFilter.cpp index cd92b2b109..33f4a7ed2a 100644 --- a/libraries/Filter/examples/LowPassFilter/LowPassFilter.cpp +++ b/libraries/Filter/examples/LowPassFilter/LowPassFilter.cpp @@ -13,7 +13,7 @@ #include // Filter library #include // LowPassFilter class (inherits from Filter class) -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); // create a global instance of the class LowPassFilterFloat low_pass_filter; diff --git a/libraries/Filter/examples/LowPassFilter2p/LowPassFilter2p.cpp b/libraries/Filter/examples/LowPassFilter2p/LowPassFilter2p.cpp index d713d05465..1081bd9e76 100644 --- a/libraries/Filter/examples/LowPassFilter2p/LowPassFilter2p.cpp +++ b/libraries/Filter/examples/LowPassFilter2p/LowPassFilter2p.cpp @@ -15,7 +15,7 @@ #include // Filter library #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); // craete an instance with 800Hz sample rate and 30Hz cutoff static LowPassFilter2pFloat low_pass_filter(800, 30); diff --git a/libraries/GCS_Console/examples/Console/Console.cpp b/libraries/GCS_Console/examples/Console/Console.cpp index e6dafc244c..9c891e82fe 100644 --- a/libraries/GCS_Console/examples/Console/Console.cpp +++ b/libraries/GCS_Console/examples/Console/Console.cpp @@ -21,7 +21,7 @@ #include "simplegcs.h" -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void flush_console_to_statustext() { uint8_t data[50]; diff --git a/libraries/GCS_MAVLink/examples/routing/routing.cpp b/libraries/GCS_MAVLink/examples/routing/routing.cpp index 7e74c53333..58024875c9 100644 --- a/libraries/GCS_MAVLink/examples/routing/routing.cpp +++ b/libraries/GCS_MAVLink/examples/routing/routing.cpp @@ -43,7 +43,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS; static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS]; diff --git a/libraries/PID/examples/pid/pid.cpp b/libraries/PID/examples/pid/pid.cpp index e25cb06b8f..c8a72514e9 100644 --- a/libraries/PID/examples/pid/pid.cpp +++ b/libraries/PID/examples/pid/pid.cpp @@ -15,7 +15,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); long radio_in; long radio_trim; diff --git a/libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp index 51e69db266..03b81d429f 100644 --- a/libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp @@ -46,7 +46,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define NUM_CHANNELS 8 diff --git a/libraries/StorageManager/examples/StorageTest/StorageTest.cpp b/libraries/StorageManager/examples/StorageTest/StorageTest.cpp index 59c5e21cc4..5be898cff1 100644 --- a/libraries/StorageManager/examples/StorageTest/StorageTest.cpp +++ b/libraries/StorageManager/examples/StorageTest/StorageTest.cpp @@ -40,7 +40,7 @@ #include #include -const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define DO_INITIALISATION 1