APM:Libraries
GPS_AUTO_test.cpp
Go to the documentation of this file.
1 //
2 // Test for AP_GPS_AUTO
3 //
4 
5 #include <stdlib.h>
6 
7 #include <AP_Common/AP_Common.h>
8 #include <AP_Param/AP_Param.h>
9 #include <AP_HAL/AP_HAL.h>
10 #include <AP_GPS/AP_GPS.h>
11 #include <DataFlash/DataFlash.h>
13 #include <AP_ADC/AP_ADC.h>
15 #include <AP_Baro/AP_Baro.h>
16 #include <Filter/Filter.h>
17 #include <AP_AHRS/AP_AHRS.h>
18 #include <AP_Compass/AP_Compass.h>
21 #include <AP_Vehicle/AP_Vehicle.h>
22 #include <AP_Mission/AP_Mission.h>
24 #include <AP_Terrain/AP_Terrain.h>
25 #include <AP_Math/AP_Math.h>
26 #include <AP_Notify/AP_Notify.h>
27 #include <AP_Notify/AP_BoardLED.h>
33 
34 void setup();
35 void loop();
36 
38 
40 
41 // create board led object
43 
44 // This example uses GPS system. Create it.
45 static AP_GPS gps;
46 // Serial manager is needed for UART comunications
48 
49 
50 void setup()
51 {
52  hal.console->printf("GPS AUTO library test\n");
53 
54  board_config.init();
55 
56  // Initialise the leds
57  board_led.init();
58 
59  // Initialize the UART for GPS system
60  serial_manager.init();
61  gps.init(serial_manager);
62 }
63 
64 void loop()
65 {
66  static uint32_t last_msg_ms;
67 
68  // Update GPS state based on possible bytes received from the module.
69  gps.update();
70 
71  // If new GPS data is received, output it's contents to the console
72  // Here we rely on the time of the message in GPS class and the time of last message
73  // saved in static variable last_msg_ms. When new message is received, the time
74  // in GPS class will be updated.
75  if (last_msg_ms != gps.last_message_time_ms()) {
76  // Reset the time of message
77  last_msg_ms = gps.last_message_time_ms();
78 
79  // Acquire location
80  const Location &loc = gps.location();
81 
82  // Print the contents of message
83  hal.console->printf("Lat: ");
84  print_latlon(hal.console, loc.lat);
85  hal.console->printf(" Lon: ");
86  print_latlon(hal.console, loc.lng);
87  hal.console->printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %u/%lu STATUS: %u\n",
88  (double)(loc.alt * 0.01f),
89  (double)gps.ground_speed(),
90  (int)gps.ground_course_cd() / 100,
91  gps.num_sats(),
92  gps.time_week(),
93  (long unsigned int)gps.time_week_ms(),
94  gps.status());
95  }
96 
97  // Delay for 10 mS will give us 100 Hz invocation rate
98  hal.scheduler->delay(10);
99 }
100 
101 // Register above functions in HAL board level
102 AP_HAL_MAIN();
Definition: AP_GPS.h:48
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint16_t time_week(uint8_t instance) const
Definition: AP_GPS.h:276
uint32_t last_message_time_ms(uint8_t instance) const
Definition: AP_GPS.h:310
AP_HAL_MAIN()
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
int32_t ground_course_cd(uint8_t instance) const
Definition: AP_GPS.h:252
A system for managing and storing variables that are of general interest to the system.
virtual void delay(uint16_t ms)=0
void init(const AP_SerialManager &serial_manager)
Startup initialisation.
Definition: AP_GPS.cpp:279
static AP_GPS gps
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
float ground_speed(uint8_t instance) const
Definition: AP_GPS.h:232
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
uint32_t time_week_ms(uint8_t instance) const
Definition: AP_GPS.h:268
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
AP_BoardLED board_led
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
const HAL & get_HAL()
Common definitions and utility routines for the ArduPilot libraries.
static AP_BoardConfig board_config
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
uint8_t num_sats(uint8_t instance) const
Definition: AP_GPS.h:260
void loop()
void setup()
void update(void)
Definition: AP_GPS.cpp:678
Catch-all header that defines all supported RangeFinder classes.
static AP_SerialManager serial_manager
void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon)
Definition: location.cpp:196
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
bool init(void)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-