Browse Source

AP_GPS: fixed example builds

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

14
libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde

@ -13,6 +13,19 @@ @@ -13,6 +13,19 @@
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_GPS.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
#include <AP_Notify.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
@ -25,7 +38,6 @@ void setup() @@ -25,7 +38,6 @@ void setup()
{
hal.console->println("GPS 406 library test");
hal.uartB->begin(57600, 128, 16);
gps.print_errors = true;
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL); // GPS Initialization
hal.scheduler->delay(1000);

13
libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde

@ -14,6 +14,19 @@ @@ -14,6 +14,19 @@
#include <AP_HAL_PX4.h>
#include <AP_HAL_Empty.h>
#include <AP_GPS.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
#include <AP_Math.h>
#include <AP_Notify.h>
#include <AP_BoardLED.h>

14
libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde

@ -15,6 +15,19 @@ @@ -15,6 +15,19 @@
#include <AP_HAL_PX4.h>
#include <AP_HAL_Empty.h>
#include <AP_GPS.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
#include <AP_Math.h>
#include <AP_Notify.h>
@ -27,7 +40,6 @@ AP_GPS_MTK19 gps; @@ -27,7 +40,6 @@ AP_GPS_MTK19 gps;
void setup()
{
hal.uartB->begin(38400);
gps.print_errors = true;
hal.console->println("GPS MTK library test");
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL); // GPS Initialization

13
libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde

@ -14,6 +14,19 @@ @@ -14,6 +14,19 @@
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_Empty.h>
#include <AP_Notify.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;

13
libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.pde

@ -15,6 +15,19 @@ @@ -15,6 +15,19 @@
#include <AP_HAL_Empty.h>
#include <AP_HAL_PX4.h>
#include <AP_GPS.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
#include <AP_Math.h>
#include <AP_Notify.h>

14
libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde

@ -15,6 +15,19 @@ @@ -15,6 +15,19 @@
#include <AP_HAL_Empty.h>
#include <AP_HAL_PX4.h>
#include <AP_GPS.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
#include <AP_Math.h>
#include <AP_Notify.h>
@ -27,7 +40,6 @@ AP_GPS_UBLOX gps; @@ -27,7 +40,6 @@ AP_GPS_UBLOX gps;
void setup()
{
hal.uartB->begin(38400);
gps.print_errors = true;
hal.console->println("GPS UBLOX library test");
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL); // GPS Initialization

Loading…
Cancel
Save