4VehicleLocalPositionFactGroup::VehicleLocalPositionFactGroup(QObject *parent)
5 :
FactGroup(1000, QStringLiteral(
":/json/Vehicle/LocalPositionFact.json"), parent)
14 _xFact.setRawValue(qQNaN());
15 _yFact.setRawValue(qQNaN());
16 _zFact.setRawValue(qQNaN());
17 _vxFact.setRawValue(qQNaN());
18 _vyFact.setRawValue(qQNaN());
19 _vzFact.setRawValue(qQNaN());
26 if (message.msgid != MAVLINK_MSG_ID_LOCAL_POSITION_NED) {
30 mavlink_local_position_ned_t localPosition{};
31 mavlink_msg_local_position_ned_decode(&message, &localPosition);
33 x()->setRawValue(localPosition.x);
34 y()->setRawValue(localPosition.y);
35 z()->setRawValue(localPosition.z);
37 vx()->setRawValue(localPosition.vx);
38 vy()->setRawValue(localPosition.vy);
39 vz()->setRawValue(localPosition.vz);
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
void _setTelemetryAvailable(bool telemetryAvailable)