Browse Source

AP_GPS: fixed example builds with change to init()

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
6b5d27efbb
  1. 2
      libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde
  2. 2
      libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde
  3. 2
      libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde
  4. 2
      libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde
  5. 2
      libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde

2
libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde

@ -27,7 +27,7 @@ void setup() @@ -27,7 +27,7 @@ void setup()
hal.uartB->begin(57600, 128, 16);
gps.print_errors = true;
gps.init(hal.uartB); // GPS Initialization
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G); // GPS Initialization
hal.scheduler->delay(1000);
}
void loop()

2
libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde

@ -35,7 +35,7 @@ void setup() @@ -35,7 +35,7 @@ void setup()
hal.console->println("GPS AUTO library test");
gps = &GPS;
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_2G);
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G);
// initialise the leds
board_led.init();

2
libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde

@ -30,7 +30,7 @@ void setup() @@ -30,7 +30,7 @@ void setup()
gps.print_errors = true;
hal.console->println("GPS MTK library test");
gps.init(hal.uartB); // GPS Initialization
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G); // GPS Initialization
}
void loop()

2
libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde

@ -51,7 +51,7 @@ void setup() @@ -51,7 +51,7 @@ void setup()
for (uint8_t i = 0; i < sizeof(sirf_to_nmea); i++)
hal.uartB->write(sirf_to_nmea[i]);
gps->init(hal.uartB);
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G);
}
void loop()

2
libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde

@ -30,7 +30,7 @@ void setup() @@ -30,7 +30,7 @@ void setup()
gps.print_errors = true;
hal.console->println("GPS UBLOX library test");
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_2G); // GPS Initialization
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G); // GPS Initialization
}
void loop()

Loading…
Cancel
Save