6VehicleWindFactGroup::VehicleWindFactGroup(QObject *parent)
7 :
FactGroup(1000, QStringLiteral(
":/json/Vehicle/WindFact.json"), parent)
9 _addFact(&_directionFact);
10 _addFact(&_speedFact);
11 _addFact(&_verticalSpeedFact);
13 _directionFact.setRawValue(qQNaN());
14 _speedFact.setRawValue(qQNaN());
15 _verticalSpeedFact.setRawValue(qQNaN());
22 switch (message.msgid) {
23 case MAVLINK_MSG_ID_WIND_COV:
24 _handleWindCov(message);
26 case MAVLINK_MSG_ID_HIGH_LATENCY:
27 _handleHighLatency(message);
29 case MAVLINK_MSG_ID_HIGH_LATENCY2:
30 _handleHighLatency2(message);
32#ifndef QGC_NO_ARDUPILOT_DIALECT
33 case MAVLINK_MSG_ID_WIND:
44 mavlink_high_latency_t highLatency{};
45 mavlink_msg_high_latency_decode(&message, &highLatency);
47 speed()->setRawValue(
static_cast<double>(highLatency.airspeed) / 5.0);
54 mavlink_high_latency2_t highLatency2{};
55 mavlink_msg_high_latency2_decode(&message, &highLatency2);
57 direction()->setRawValue(
static_cast<double>(highLatency2.wind_heading) * 2.0);
58 speed()->setRawValue(
static_cast<double>(highLatency2.windspeed) / 5.0);
65 mavlink_wind_cov_t wind{};
66 mavlink_msg_wind_cov_decode(&message, &wind);
68 float windDirection = qRadiansToDegrees(qAtan2(wind.wind_y, wind.wind_x));
69 if (windDirection < 0) {
72 direction()->setRawValue(windDirection);
74 const float windSpeed = qSqrt(qPow(wind.wind_x, 2) + qPow(wind.wind_y, 2));
75 speed()->setRawValue(windSpeed);
77 verticalSpeed()->setRawValue(wind.wind_z);
82#ifndef QGC_NO_ARDUPILOT_DIALECT
85 mavlink_wind_t wind{};
86 mavlink_msg_wind_decode(&message, &wind);
89 float windDirection = wind.direction;
90 if (windDirection < 0) {
93 direction()->setRawValue(windDirection);
94 speed()->setRawValue(wind.speed);
95 verticalSpeed()->setRawValue(wind.speed_z);
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
void _setTelemetryAvailable(bool telemetryAvailable)