46 case MAVLINK_MSG_ID_GPS_INPUT: {
47 mavlink_gps_input_t packet;
48 mavlink_msg_gps_input_decode(msg, &packet);
50 bool have_alt = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_ALT) == 0);
51 bool have_hdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HDOP) == 0);
52 bool have_vdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VDOP) == 0);
53 bool have_vel_h = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VEL_HORIZ) == 0);
54 bool have_vel_v = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VEL_VERT) == 0);
55 bool have_sa = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY) == 0);
56 bool have_ha = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY) == 0);
57 bool have_va = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY) == 0);
67 loc.alt = packet.alt * 100;
81 Vector3f vel(packet.vn, packet.ve, 0);
113 case MAVLINK_MSG_ID_HIL_GPS: {
114 mavlink_hil_gps_t packet;
115 mavlink_msg_hil_gps_decode(msg, &packet);
122 loc.
lat = packet.lat;
123 loc.lng = packet.lon;
124 loc.alt = packet.alt * 0.1f;
129 if (packet.vel < 65535) {
132 Vector3f vel(packet.vn/100.0f, packet.ve/100.0f, packet.vd/100.0f);
134 if (packet.vd != 0) {
137 if (packet.cog < 36000) {
143 if (packet.satellites_visible < 255) {
float norm(const T first, const U second, const Params... parameters)
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
GPS_Status status
driver fix status
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Vector3f velocity
3D velocity in m/s, in NED format
void handle_msg(const mavlink_message_t *msg)
int32_t lat
param 3 - Latitude * 10**7
GPS_Status
GPS status codes.
AP_GPS_MAV(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
float wrap_360(const T angle, float unit_mod)
uint16_t time_week
GPS week number.
AP_GPS::GPS_State & state
public state for this instance
uint16_t vdop
vertical dilution of precision in cm
Location location
last fix location
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
float speed_accuracy
3D velocity RMS accuracy estimate in m/s
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
float horizontal_accuracy
horizontal RMS accuracy estimate in m
float ground_speed
ground speed in m/sec
float vertical_accuracy
vertical RMS accuracy estimate in m
uint16_t hdop
horizontal dilution of precision in cm
uint8_t num_sats
Number of visible satellites.
bool have_speed_accuracy
does GPS give speed accuracy? Set to true only once available.
float ground_course
ground course in degrees