AP_GPS: fixed build for new syntax

This commit is contained in:
Andrew Tridgell 2012-12-19 11:02:47 +11:00
parent 958b27f06d
commit 8beaec61a8
5 changed files with 19 additions and 35 deletions

View File

@ -14,13 +14,9 @@
#include <AP_HAL_AVR.h>
#include <AP_GPS.h>
#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()

View File

@ -10,17 +10,15 @@
#include <AP_Param.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_Empty.h>
#include <AP_GPS.h>
#include <AP_Math.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;
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()

View File

@ -15,13 +15,9 @@
#include <AP_GPS.h>
#include <AP_Math.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;
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()

View File

@ -11,14 +11,12 @@
#include <AP_HAL.h>
#include <AP_GPS.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_Empty.h>
#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()

View File

@ -15,13 +15,9 @@
#include <AP_GPS.h>
#include <AP_Math.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;
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()