QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleFactGroup.cc
Go to the documentation of this file.
1#include "VehicleFactGroup.h"
2#include "Vehicle.h"
3#include "QGCMath.h"
4
5#include <cmath>
6
7#include <QtGui/QQuaternion>
8#include <QtGui/QVector3D>
9
51
53{
54 // 0 <= rssi <= 100 is the valid range; 255 (or anything > 100) means "unknown".
55 if (rssi > 100) {
56 if (_rcRSSIFact.rawValue().toUInt() != 255) {
58 }
59 return;
60 }
61
62 // Initialize the filter lazily so the first sample is taken verbatim.
63 if (_rcRSSIStore == 255.0) {
64 _rcRSSIStore = static_cast<double>(rssi);
65 }
66
67 // Low-pass filter to damp RSSI jitter.
68 _rcRSSIStore = (_rcRSSIStore * 0.9) + (static_cast<double>(rssi) * 0.1);
69 uint8_t filteredRSSI = static_cast<uint8_t>(std::ceil(_rcRSSIStore));
70 if (_rcRSSIStore < 0.1) {
71 filteredRSSI = 0;
72 }
73
74 if (_rcRSSIFact.rawValue().toUInt() != filteredRSSI) {
75 _rcRSSIFact.setRawValue(filteredRSSI);
76 }
77}
78
80{
81 switch (message.msgid) {
82 case MAVLINK_MSG_ID_ATTITUDE:
83 _handleAttitude(vehicle, message);
84 break;
85 case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
86 _handleAttitudeQuaternion(vehicle, message);
87 break;
88 case MAVLINK_MSG_ID_ALTITUDE:
89 _handleAltitude(message);
90 break;
91 case MAVLINK_MSG_ID_VFR_HUD:
92 _handleVfrHud(message);
93 break;
94 case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
96 break;
97 case MAVLINK_MSG_ID_RAW_IMU:
98 _handleRawImuTemp(message);
99 break;
100#ifndef QGC_NO_ARDUPILOT_DIALECT
101 case MAVLINK_MSG_ID_RANGEFINDER:
102 _handleRangefinder(message);
103 break;
104#endif
105 default:
106 break;
107 }
108}
109
110void VehicleFactGroup::_handleAttitudeWorker(double rollRadians, double pitchRadians, double yawRadians)
111{
112 double rollDegrees = QGC::limitAngleToPMPIf(rollRadians);
113 double pitchDegrees = QGC::limitAngleToPMPIf(pitchRadians);
114 double yawDegrees = QGC::limitAngleToPMPIf(yawRadians);
115
116 rollDegrees = qRadiansToDegrees(rollDegrees);
117 pitchDegrees = qRadiansToDegrees(pitchDegrees);
118 yawDegrees = qRadiansToDegrees(yawDegrees);
119
120 if (yawDegrees < 0.0) {
121 yawDegrees += 360.0;
122 }
123 // truncate to integer so widget never displays 360
124 yawDegrees = trunc(yawDegrees);
125
126 roll()->setRawValue(rollDegrees);
127 pitch()->setRawValue(pitchDegrees);
128 heading()->setRawValue(yawDegrees);
129}
130
132{
133 if ((message.sysid != vehicle->id()) || (message.compid != vehicle->compId())) {
134 return;
135 }
136
137 if (_receivingAttitudeQuaternion) {
138 return;
139 }
140
141 mavlink_attitude_t attitude{};
142 mavlink_msg_attitude_decode(&message, &attitude);
143
144 _handleAttitudeWorker(attitude.roll, attitude.pitch, attitude.yaw);
145
147}
148
150{
151 mavlink_altitude_t altitude{};
152 mavlink_msg_altitude_decode(&message, &altitude);
153
154 // Data from ALTITUDE message takes precedence over gps messages
156 altitudeRelative()->setRawValue(altitude.altitude_relative);
157 altitudeAMSL()->setRawValue(altitude.altitude_amsl);
158
160}
161
163{
164 // only accept the attitude message from the vehicle's flight controller
165 if ((message.sysid != vehicle->id()) || (message.compid != vehicle->compId())) {
166 return;
167 }
168
169 _receivingAttitudeQuaternion = true;
170
171 mavlink_attitude_quaternion_t attitudeQuaternion{};
172 mavlink_msg_attitude_quaternion_decode(&message, &attitudeQuaternion);
173
174 QQuaternion quat(attitudeQuaternion.q1, attitudeQuaternion.q2, attitudeQuaternion.q3, attitudeQuaternion.q4);
175 QVector3D rates(attitudeQuaternion.rollspeed, attitudeQuaternion.pitchspeed, attitudeQuaternion.yawspeed);
176 QQuaternion repr_offset(attitudeQuaternion.repr_offset_q[0], attitudeQuaternion.repr_offset_q[1], attitudeQuaternion.repr_offset_q[2], attitudeQuaternion.repr_offset_q[3]);
177
178 // if repr_offset is valid, rotate attitude and rates
179 if (repr_offset.length() >= 0.5f) {
180 quat *= repr_offset;
181 rates = repr_offset * rates;
182 }
183
184 float attRoll, attPitch, attYaw;
185 float q[] = { quat.scalar(), quat.x(), quat.y(), quat.z() };
186 mavlink_quaternion_to_euler(q, &attRoll, &attPitch, &attYaw);
187
188 _handleAttitudeWorker(attRoll, attPitch, attYaw);
189
190 rollRate()->setRawValue(qRadiansToDegrees(rates[0]));
191 pitchRate()->setRawValue(qRadiansToDegrees(rates[1]));
192 yawRate()->setRawValue(qRadiansToDegrees(rates[2]));
193
195}
196
198{
199 mavlink_nav_controller_output_t navControllerOutput{};
200 mavlink_msg_nav_controller_output_decode(&message, &navControllerOutput);
201
202 altitudeTuningSetpoint()->setRawValue(_altitudeTuningFact.rawValue().toDouble() - navControllerOutput.alt_error);
203 xTrackError()->setRawValue(navControllerOutput.xtrack_error);
204 airSpeedSetpoint()->setRawValue(_airSpeedFact.rawValue().toDouble() - navControllerOutput.aspd_error);
205 distanceToNextWP()->setRawValue(navControllerOutput.wp_dist);
206
208}
209
211{
212 mavlink_vfr_hud_t vfrHud{};
213 mavlink_msg_vfr_hud_decode(&message, &vfrHud);
214
215 airSpeed()->setRawValue(qIsNaN(vfrHud.airspeed) ? 0 : vfrHud.airspeed);
216 groundSpeed()->setRawValue(qIsNaN(vfrHud.groundspeed) ? 0 : vfrHud.groundspeed);
217 climbRate()->setRawValue(qIsNaN(vfrHud.climb) ? 0 : vfrHud.climb);
218 throttlePct()->setRawValue(static_cast<int16_t>(vfrHud.throttle));
219 if (qIsNaN(_altitudeTuningOffset)) {
220 _altitudeTuningOffset = vfrHud.alt;
221 }
223 if (!qIsNaN(vfrHud.groundspeed) && !qIsNaN(_distanceToHomeFact.cookedValue().toDouble())) {
224 timeToHome()->setRawValue(_distanceToHomeFact.cookedValue().toDouble() / vfrHud.groundspeed);
225 }
226
228}
229
231{
232 mavlink_raw_imu_t imuRaw{};
233 mavlink_msg_raw_imu_decode(&message, &imuRaw);
234
235 imuTemp()->setRawValue((imuRaw.temperature == 0) ? 0 : (imuRaw.temperature * 0.01));
236
238}
239
240#ifndef QGC_NO_ARDUPILOT_DIALECT
242{
243 mavlink_rangefinder_t rangefinder{};
244 mavlink_msg_rangefinder_decode(&message, &rangefinder);
245
246 rangeFinderDist()->setRawValue(qIsNaN(rangefinder.distance) ? 0 : rangefinder.distance);
247
249}
250#endif
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
void _setTelemetryAvailable(bool telemetryAvailable)
Definition FactGroup.cc:175
void _addFact(Fact *fact, const QString &name)
Definition FactGroup.cc:116
QVariant cookedValue() const
Definition Fact.cc:220
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
void _handleAltitude(const mavlink_message_t &message)
VehicleFactGroup(QObject *parent=nullptr)
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override
Allows a FactGroup to parse incoming messages and fill in values.
void _handleNavControllerOutput(const mavlink_message_t &message)
void _handleAttitude(Vehicle *vehicle, const mavlink_message_t &message)
void _handleRawImuTemp(const mavlink_message_t &message)
void updateRCRSSI(uint8_t rssi)
void _handleVfrHud(const mavlink_message_t &message)
void _handleAttitudeQuaternion(Vehicle *vehicle, const mavlink_message_t &message)
Fact * altitudeTuningSetpoint()
void _handleRangefinder(const mavlink_message_t &message)
int id() const
Definition Vehicle.h:425
int compId() const
Definition Vehicle.h:426
float limitAngleToPMPIf(double angle)
Definition QGCMath.cc:13