60 serial_manager.
init();
61 gps.
init(serial_manager);
66 static uint32_t last_msg_ms;
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),
AP_HAL::UARTDriver * console
uint16_t time_week(uint8_t instance) const
uint32_t last_message_time_ms(uint8_t instance) const
const Location & location(uint8_t instance) const
int32_t lat
param 3 - Latitude * 10**7
int32_t ground_course_cd(uint8_t instance) const
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.
virtual void printf(const char *,...) FMT_PRINTF(2
float ground_speed(uint8_t instance) const
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
uint32_t time_week_ms(uint8_t instance) const
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
GPS_Status status(uint8_t instance) const
Query GPS status.
Common definitions and utility routines for the ArduPilot libraries.
static AP_BoardConfig board_config
int32_t lng
param 4 - Longitude * 10**7
uint8_t num_sats(uint8_t instance) const
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)
AP_HAL::Scheduler * scheduler
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-