diff --git a/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde b/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde index 9438cdbc49..248b4a0a24 100644 --- a/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde +++ b/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde @@ -14,13 +14,9 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; -AP_GPS_406 gps(hal.uartB); +AP_GPS_406 gps; #define T6 1000000 #define T7 10000000 @@ -30,7 +26,7 @@ void setup() hal.uartB->begin(57600, 128, 16); gps.print_errors = true; - gps.init(); // GPS Initialization + gps.init(hal.uartB); // GPS Initialization hal.scheduler->delay(1000); } void loop() diff --git a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde index df76235528..429fe8d93d 100644 --- a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde +++ b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde @@ -10,17 +10,15 @@ #include #include #include +#include +#include #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; GPS *gps; -AP_GPS_Auto GPS(hal.uartB, &gps); +AP_GPS_Auto GPS(&gps); #define T6 1000000 #define T7 10000000 @@ -51,7 +49,7 @@ void setup() hal.console->println("GPS AUTO library test"); gps = &GPS; - gps->init(GPS::GPS_ENGINE_AIRBORNE_2G); + gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_2G); } void loop() diff --git a/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde b/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde index 82b02725b5..a5bb1c3491 100644 --- a/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde +++ b/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde @@ -15,13 +15,9 @@ #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_GPS_MTK16 gps(hal.uartB); +AP_GPS_MTK16 gps; #define T6 1000000 #define T7 10000000 @@ -31,7 +27,7 @@ void setup() gps.print_errors = true; hal.console->println("GPS MTK library test"); - gps.init(); // GPS Initialization + gps.init(hal.uartB); // GPS Initialization } void loop() diff --git a/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde b/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde index 660d39d053..ff1387312c 100644 --- a/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde +++ b/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde @@ -11,14 +11,12 @@ #include #include #include +#include +#include -#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM1; -#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 -const AP_HAL::HAL& hal = AP_HAL_AVR_APM2; -#endif +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; -AP_GPS_NMEA NMEA_gps(hal.uartB); +AP_GPS_NMEA NMEA_gps; GPS *gps = &NMEA_gps; #define T6 1000000 @@ -52,7 +50,7 @@ void setup() for (uint8_t i = 0; i < sizeof(sirf_to_nmea); i++) hal.uartB->write(sirf_to_nmea[i]); - gps->init(); + gps->init(hal.uartB); } void loop() diff --git a/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde b/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde index 611c98434a..4bb16e418a 100644 --- a/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde +++ b/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde @@ -15,13 +15,9 @@ #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_GPS_UBLOX gps(hal.uartB); +AP_GPS_UBLOX gps; #define T6 1000000 #define T7 10000000 @@ -31,7 +27,7 @@ void setup() gps.print_errors = true; hal.console->println("GPS UBLOX library test"); - gps.init(GPS::GPS_ENGINE_AIRBORNE_2G); // GPS Initialization + gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_2G); // GPS Initialization } void loop()