Browse Source

GPS: update notify

mission-4.1.18
Randy Mackay 12 years ago committed by Andrew Tridgell
parent
commit
496962f037
  1. 3
      libraries/AP_GPS/GPS.cpp
  2. 1
      libraries/AP_GPS/GPS.h
  3. 8
      libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde

3
libraries/AP_GPS/GPS.cpp

@ -97,6 +97,9 @@ GPS::update(void)
} }
} }
} }
// update notify with gps status
notify.flags.gps_status = _status;
} }
void void

1
libraries/AP_GPS/GPS.h

@ -11,6 +11,7 @@
#include <inttypes.h> #include <inttypes.h>
#include <AP_Progmem.h> #include <AP_Progmem.h>
#include <AP_Math.h> #include <AP_Math.h>
#include <AP_Notify.h>
/// @class GPS /// @class GPS
/// @brief Abstract base class for GPS receiver drivers. /// @brief Abstract base class for GPS receiver drivers.

8
libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde

@ -15,9 +15,14 @@
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty.h>
#include <AP_GPS.h> #include <AP_GPS.h>
#include <AP_Math.h> #include <AP_Math.h>
#include <AP_Notify.h>
#include <AP_BoardLED.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
// create board led object
AP_BoardLED board_led;
GPS *gps; GPS *gps;
AP_GPS_Auto GPS(&gps); AP_GPS_Auto GPS(&gps);
@ -31,6 +36,9 @@ void setup()
hal.console->println("GPS AUTO library test"); hal.console->println("GPS AUTO library test");
gps = &GPS; gps = &GPS;
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_2G); gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_2G);
// initialise the leds
board_led.init();
} }
void loop() void loop()

Loading…
Cancel
Save