QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleWindFactGroup.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3
4#include <QtMath>
5
6VehicleWindFactGroup::VehicleWindFactGroup(QObject *parent)
7 : FactGroup(1000, QStringLiteral(":/json/Vehicle/WindFact.json"), parent)
8{
9 _addFact(&_directionFact);
10 _addFact(&_speedFact);
11 _addFact(&_verticalSpeedFact);
12
13 _directionFact.setRawValue(qQNaN());
14 _speedFact.setRawValue(qQNaN());
15 _verticalSpeedFact.setRawValue(qQNaN());
16}
17
18void VehicleWindFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message)
19{
20 Q_UNUSED(vehicle);
21
22 switch (message.msgid) {
23 case MAVLINK_MSG_ID_WIND_COV:
24 _handleWindCov(message);
25 break;
26 case MAVLINK_MSG_ID_HIGH_LATENCY:
27 _handleHighLatency(message);
28 break;
29 case MAVLINK_MSG_ID_HIGH_LATENCY2:
30 _handleHighLatency2(message);
31 break;
32#ifndef QGC_NO_ARDUPILOT_DIALECT
33 case MAVLINK_MSG_ID_WIND:
34 _handleWind(message);
35 break;
36#endif
37 default:
38 break;
39 }
40}
41
42void VehicleWindFactGroup::_handleHighLatency(const mavlink_message_t &message)
43{
44 mavlink_high_latency_t highLatency{};
45 mavlink_msg_high_latency_decode(&message, &highLatency);
46
47 speed()->setRawValue(static_cast<double>(highLatency.airspeed) / 5.0);
48
50}
51
52void VehicleWindFactGroup::_handleHighLatency2(const mavlink_message_t &message)
53{
54 mavlink_high_latency2_t highLatency2{};
55 mavlink_msg_high_latency2_decode(&message, &highLatency2);
56
57 direction()->setRawValue(static_cast<double>(highLatency2.wind_heading) * 2.0);
58 speed()->setRawValue(static_cast<double>(highLatency2.windspeed) / 5.0);
59
61}
62
63void VehicleWindFactGroup::_handleWindCov(const mavlink_message_t &message)
64{
65 mavlink_wind_cov_t wind{};
66 mavlink_msg_wind_cov_decode(&message, &wind);
67
68 float windDirection = qRadiansToDegrees(qAtan2(wind.wind_y, wind.wind_x));
69 if (windDirection < 0) {
70 windDirection += 360;
71 }
72 direction()->setRawValue(windDirection);
73
74 const float windSpeed = qSqrt(qPow(wind.wind_x, 2) + qPow(wind.wind_y, 2));
75 speed()->setRawValue(windSpeed);
76
77 verticalSpeed()->setRawValue(wind.wind_z);
78
80}
81
82#ifndef QGC_NO_ARDUPILOT_DIALECT
83void VehicleWindFactGroup::_handleWind(const mavlink_message_t &message)
84{
85 mavlink_wind_t wind{};
86 mavlink_msg_wind_decode(&message, &wind);
87
88 // We don't want negative wind angles
89 float windDirection = wind.direction;
90 if (windDirection < 0) {
91 windDirection += 360;
92 }
93 direction()->setRawValue(windDirection);
94 speed()->setRawValue(wind.speed);
95 verticalSpeed()->setRawValue(wind.speed_z);
96
98}
99#endif
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