4#include "development/mavlink_msg_gnss_integrity.h"
6#include <QtPositioning/QGeoCoordinate>
12 switch (message.msgid) {
13 case MAVLINK_MSG_ID_GPS2_RAW:
14 _handleGps2Raw(message);
16 case MAVLINK_MSG_ID_GNSS_INTEGRITY:
26 mavlink_gps2_raw_t gps2Raw{};
27 mavlink_msg_gps2_raw_decode(&message, &gps2Raw);
29 lat()->setRawValue(gps2Raw.lat * 1e-7);
30 lon()->setRawValue(gps2Raw.lon * 1e-7);
32 count()->setRawValue((gps2Raw.satellites_visible == 255) ? 0 : gps2Raw.satellites_visible);
33 hdop()->setRawValue((gps2Raw.eph == UINT16_MAX) ? qQNaN() : (gps2Raw.eph / 100.0));
34 vdop()->setRawValue((gps2Raw.epv == UINT16_MAX) ? qQNaN() : (gps2Raw.epv / 100.0));
35 courseOverGround()->setRawValue((gps2Raw.cog == UINT16_MAX) ? qQNaN() : (gps2Raw.cog / 100.0));
36 yaw()->setRawValue((gps2Raw.yaw == UINT16_MAX) ? qQNaN() : (gps2Raw.yaw / 100.0));
37 lock()->setRawValue(gps2Raw.fix_type);
struct __mavlink_message mavlink_message_t
Geographic coordinate conversion utilities using GeographicLib.
void _setTelemetryAvailable(bool telemetryAvailable)
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final
Allows a FactGroup to parse incoming messages and fill in values.
void _handleGnssIntegrity(const mavlink_message_t &message)
QString convertGeoToMGRS(const QGeoCoordinate &coord)