QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleSetpointFactGroup.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3
4#include <QtMath>
5
6VehicleSetpointFactGroup::VehicleSetpointFactGroup(QObject *parent)
7 : FactGroup(1000, QStringLiteral(":/json/Vehicle/SetpointFact.json"), parent)
8{
9 _addFact(&_rollFact);
10 _addFact(&_pitchFact);
11 _addFact(&_yawFact);
12 _addFact(&_rollRateFact);
13 _addFact(&_pitchRateFact);
14 _addFact(&_yawRateFact);
15
16 _rollFact.setRawValue(qQNaN());
17 _pitchFact.setRawValue(qQNaN());
18 _yawFact.setRawValue(qQNaN());
19 _rollRateFact.setRawValue(qQNaN());
20 _pitchRateFact.setRawValue(qQNaN());
21 _yawRateFact.setRawValue(qQNaN());
22}
23
24void VehicleSetpointFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message)
25{
26 Q_UNUSED(vehicle);
27
28 if (message.msgid != MAVLINK_MSG_ID_ATTITUDE_TARGET) {
29 return;
30 }
31
32 mavlink_attitude_target_t attitudeTarget{};
33 mavlink_msg_attitude_target_decode(&message, &attitudeTarget);
34
35 float targetRoll, targetPitch, targetYaw;
36 mavlink_quaternion_to_euler(attitudeTarget.q, &targetRoll, &targetPitch, &targetYaw);
37
38 roll()->setRawValue(qRadiansToDegrees(targetRoll));
39 pitch()->setRawValue(qRadiansToDegrees(targetPitch));
40 if (targetYaw < 0.f) {
41 targetYaw += 2.f * static_cast<float>(M_PI); // bring to range [0, 2pi] to match the heading angle
42 }
43 yaw()->setRawValue(qRadiansToDegrees(targetYaw));
44
45 rollRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_roll_rate));
46 pitchRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_pitch_rate));
47 yawRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_yaw_rate));
48
50}
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