QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleLocalPositionSetpointFactGroup.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3
4VehicleLocalPositionSetpointFactGroup::VehicleLocalPositionSetpointFactGroup(QObject *parent)
5 : FactGroup(1000, QStringLiteral(":/json/Vehicle/LocalPositionSetpointFact.json"), parent)
6{
7 _addFact(&_xFact);
8 _addFact(&_yFact);
9 _addFact(&_zFact);
10 _addFact(&_vxFact);
11 _addFact(&_vyFact);
12 _addFact(&_vzFact);
13
14 _xFact.setRawValue(qQNaN());
15 _yFact.setRawValue(qQNaN());
16 _zFact.setRawValue(qQNaN());
17 _vxFact.setRawValue(qQNaN());
18 _vyFact.setRawValue(qQNaN());
19 _vzFact.setRawValue(qQNaN());
20}
21
22void VehicleLocalPositionSetpointFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message)
23{
24 Q_UNUSED(vehicle);
25
26 if (message.msgid != MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED) {
27 return;
28 }
29
30 mavlink_position_target_local_ned_t localPosition{};
31 mavlink_msg_position_target_local_ned_decode(&message, &localPosition);
32
33 x()->setRawValue(localPosition.x);
34 y()->setRawValue(localPosition.y);
35 z()->setRawValue(localPosition.z);
36
37 vx()->setRawValue(localPosition.vx);
38 vy()->setRawValue(localPosition.vy);
39 vz()->setRawValue(localPosition.vz);
40
42}
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
void _setTelemetryAvailable(bool telemetryAvailable)
Definition FactGroup.cc:172