diff --git a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.pde b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.pde index d3fc4abe2b..c819d9bc4b 100644 --- a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.pde +++ b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.pde @@ -11,11 +11,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; // default PID values #define TEST_P 1.0 diff --git a/libraries/APM_OBC/examples/trivial_APM_OBC/trivial_APM_OBC.pde b/libraries/APM_OBC/examples/trivial_APM_OBC/trivial_APM_OBC.pde index dc65cf1f8a..b4e4e035a6 100644 --- a/libraries/APM_OBC/examples/trivial_APM_OBC/trivial_APM_OBC.pde +++ b/libraries/APM_OBC/examples/trivial_APM_OBC/trivial_APM_OBC.pde @@ -8,11 +8,7 @@ #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; void setup () { hal.console->println_P(PSTR("Unit test for APM_OBC. This sketch" diff --git a/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.pde b/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.pde index 3318a284f6..18fd3af6da 100644 --- a/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.pde +++ b/libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.pde @@ -20,7 +20,7 @@ uint32_t timer; #if CONFIG_HAL_BOARD == HAL_BOARD_APM1 /* Only build this sketch for APM1 */ -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; AP_ADC_ADS7844 adc; diff --git a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.pde b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.pde index 9c5b532169..6942da5d46 100644 --- a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.pde +++ b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.pde @@ -19,11 +19,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; AP_Airspeed airspeed; diff --git a/libraries/AP_Baro/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.pde b/libraries/AP_Baro/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.pde index 21556dd6c1..f34d9fec95 100644 --- a/libraries/AP_Baro/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.pde +++ b/libraries/AP_Baro/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.pde @@ -20,7 +20,7 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_APM1 /* Build this example sketch only for the APM1. */ -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; AP_Baro_BMP085 bmp085; diff --git a/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde b/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde index 13a0d64f2d..c806d5ff01 100644 --- a/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde +++ b/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde @@ -9,9 +9,9 @@ #include #include +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; #if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; AP_Baro_MS5611 baro; static uint32_t timer; @@ -58,7 +58,6 @@ void loop() #else // Non-APM2 #warning AP_Baro_MS5611_test built as stub for APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; void setup () {} void loop () {} #endif diff --git a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde index ffad44ad4e..dc13869498 100644 --- a/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde +++ b/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde @@ -13,11 +13,7 @@ #include #include // Compass Library -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; AP_Compass_HMC5843 compass; uint32_t timer; diff --git a/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.pde b/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.pde index 7769a5c710..097c8cb965 100644 --- a/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.pde +++ b/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.pde @@ -11,11 +11,7 @@ #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; static const int16_t dec_tbl[37][73] = \ { \ diff --git a/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde b/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde index 6fd0731da3..1730e1992a 100644 --- a/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde +++ b/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde @@ -21,19 +21,19 @@ #include // ArduPilot general purpose FIFO buffer #include +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; #if CONFIG_HAL_BOARD == HAL_BOARD_APM2 #define A_LED_PIN 27 #define C_LED_PIN 25 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; AP_InertialSensor_MPU6000 ins; AP_Baro_MS5611 baro; + #else #define A_LED_PIN 37 #define C_LED_PIN 35 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; AP_ADC_ADS7844 adc; AP_InertialSensor_Oilpan ins(&adc); AP_Baro_BMP085 baro; diff --git a/libraries/AP_LeadFilter/examples/AP_LeadFilter/AP_LeadFilter.pde b/libraries/AP_LeadFilter/examples/AP_LeadFilter/AP_LeadFilter.pde index eaf949ca1c..bbb7b83e3a 100644 --- a/libraries/AP_LeadFilter/examples/AP_LeadFilter/AP_LeadFilter.pde +++ b/libraries/AP_LeadFilter/examples/AP_LeadFilter/AP_LeadFilter.pde @@ -14,11 +14,7 @@ #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; AP_LeadFilter xLeadFilter; // GPS lag filter diff --git a/libraries/AP_Math/examples/eulers/eulers.pde b/libraries/AP_Math/examples/eulers/eulers.pde index 5dcf2c6844..31b0657f4a 100644 --- a/libraries/AP_Math/examples/eulers/eulers.pde +++ b/libraries/AP_Math/examples/eulers/eulers.pde @@ -11,11 +11,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; static float rad_diff(float rad1, float rad2) { diff --git a/libraries/AP_Math/examples/location/location.pde b/libraries/AP_Math/examples/location/location.pde index 9681965ef6..bdb647adc4 100644 --- a/libraries/AP_Math/examples/location/location.pde +++ b/libraries/AP_Math/examples/location/location.pde @@ -10,11 +10,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; static const struct { Vector2f wp1, wp2, location; diff --git a/libraries/AP_Math/examples/polygon/polygon.pde b/libraries/AP_Math/examples/polygon/polygon.pde index 2d00be3974..b5cc65e2a9 100644 --- a/libraries/AP_Math/examples/polygon/polygon.pde +++ b/libraries/AP_Math/examples/polygon/polygon.pde @@ -10,11 +10,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; /* * this is the boundary of the 2010 outback challenge diff --git a/libraries/AP_Math/examples/rotations/rotations.pde b/libraries/AP_Math/examples/rotations/rotations.pde index b7d2a3dcd3..ba854f6039 100644 --- a/libraries/AP_Math/examples/rotations/rotations.pde +++ b/libraries/AP_Math/examples/rotations/rotations.pde @@ -11,11 +11,7 @@ #include // ArduPilot Mega Declination Helper Library #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; // standard rotation matrices (these are the originals from the old code) #define MATRIX_ROTATION_NONE Matrix3f(1, 0, 0, 0, 1, 0, 0,0, 1) diff --git a/libraries/AP_Menu/examples/menu/menu.pde b/libraries/AP_Menu/examples/menu/menu.pde index c8bf0a416e..2b03140a8f 100644 --- a/libraries/AP_Menu/examples/menu/menu.pde +++ b/libraries/AP_Menu/examples/menu/menu.pde @@ -8,11 +8,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; int8_t menu_test(uint8_t argc, const Menu::arg *argv) diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde index 9c9a242357..b0d41bc6e4 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.pde @@ -14,11 +14,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; RC_Channel rc1(0), rc2(1), rc3(2), rc4(3); diff --git a/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.pde b/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.pde index 04fa427c09..0d1ed5c308 100644 --- a/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.pde +++ b/libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.pde @@ -21,11 +21,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; void setup () { hal.console->println_P(PSTR("Unit test for AP_Mount. This sketch" diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde index 6e3a8e36a2..8e24f2f9a4 100644 --- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde +++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde @@ -12,11 +12,7 @@ #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; AP_OpticalFlow_ADNS3080 flowSensor; diff --git a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde index 37ea79d351..5c8a66d786 100644 --- a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde +++ b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde @@ -17,11 +17,11 @@ #define HEAD_BYTE1 0xA3 #define HEAD_BYTE2 0x95 +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; + #if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; DataFlash_APM2 DataFlash; #elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; DataFlash_APM1 DataFlash; #endif diff --git a/libraries/Filter/examples/Derivative/Derivative.pde b/libraries/Filter/examples/Derivative/Derivative.pde index 1c4915d1ad..f6628b7097 100644 --- a/libraries/Filter/examples/Derivative/Derivative.pde +++ b/libraries/Filter/examples/Derivative/Derivative.pde @@ -13,11 +13,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; #ifdef DESKTOP_BUILD #error Desktop build not supported with AP_HAL diff --git a/libraries/Filter/examples/Filter/Filter.pde b/libraries/Filter/examples/Filter/Filter.pde index fa720d592d..fcd6db9f91 100644 --- a/libraries/Filter/examples/Filter/Filter.pde +++ b/libraries/Filter/examples/Filter/Filter.pde @@ -15,11 +15,7 @@ #include // AverageFilter class (inherits from Filter class) #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; int16_t rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000}; diff --git a/libraries/Filter/examples/LowPassFilter/LowPassFilter.pde b/libraries/Filter/examples/LowPassFilter/LowPassFilter.pde index b63405be08..ab694f52f7 100644 --- a/libraries/Filter/examples/LowPassFilter/LowPassFilter.pde +++ b/libraries/Filter/examples/LowPassFilter/LowPassFilter.pde @@ -13,11 +13,7 @@ #include // LowPassFilter class (inherits from Filter class) #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; // create a global instance of the class LowPassFilterFloat low_pass_filter; diff --git a/libraries/GCS_Console/examples/Console/Console.pde b/libraries/GCS_Console/examples/Console/Console.pde index 5cbb81fa8f..cf18816e61 100644 --- a/libraries/GCS_Console/examples/Console/Console.pde +++ b/libraries/GCS_Console/examples/Console/Console.pde @@ -18,11 +18,7 @@ #include "simplegcs.h" -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; void flush_console_to_statustext() { uint8_t data[50];