5#include <QtGui/QQuaternion>
6#include <QtGui/QVector3D>
8VehicleFactGroup::VehicleFactGroup(QObject *parent)
9 :
FactGroup(100, QStringLiteral(
":/json/Vehicle/VehicleFact.json"), parent)
12 _addFact(&_pitchFact);
13 _addFact(&_headingFact);
14 _addFact(&_rollRateFact);
15 _addFact(&_pitchRateFact);
16 _addFact(&_yawRateFact);
17 _addFact(&_groundSpeedFact);
18 _addFact(&_airSpeedFact);
19 _addFact(&_airSpeedSetpointFact);
20 _addFact(&_climbRateFact);
21 _addFact(&_altitudeRelativeFact);
22 _addFact(&_altitudeAMSLFact);
23 _addFact(&_altitudeAboveTerrFact);
24 _addFact(&_altitudeTuningFact);
25 _addFact(&_altitudeTuningSetpointFact);
26 _addFact(&_xTrackErrorFact);
27 _addFact(&_rangeFinderDistFact);
28 _addFact(&_flightDistanceFact);
29 _addFact(&_flightTimeFact);
30 _addFact(&_distanceToHomeFact);
31 _addFact(&_timeToHomeFact);
32 _addFact(&_missionItemIndexFact);
33 _addFact(&_headingToNextWPFact);
34 _addFact(&_distanceToNextWPFact);
35 _addFact(&_headingToHomeFact);
36 _addFact(&_headingFromHomeFact);
37 _addFact(&_headingFromGCSFact);
38 _addFact(&_distanceToGCSFact);
39 _addFact(&_hobbsFact);
40 _addFact(&_throttlePctFact);
41 _addFact(&_imuTempFact);
43 _hobbsFact.setRawValue(QStringLiteral(
"––––:––:––"));
48 switch (message.msgid) {
49 case MAVLINK_MSG_ID_ATTITUDE:
52 case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
55 case MAVLINK_MSG_ID_ALTITUDE:
58 case MAVLINK_MSG_ID_VFR_HUD:
61 case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
64 case MAVLINK_MSG_ID_RAW_IMU:
67#ifndef QGC_NO_ARDUPILOT_DIALECT
68 case MAVLINK_MSG_ID_RANGEFINDER:
77void VehicleFactGroup::_handleAttitudeWorker(
double rollRadians,
double pitchRadians,
double yawRadians)
83 rollDegrees = qRadiansToDegrees(rollDegrees);
84 pitchDegrees = qRadiansToDegrees(pitchDegrees);
85 yawDegrees = qRadiansToDegrees(yawDegrees);
87 if (yawDegrees < 0.0) {
91 yawDegrees = trunc(yawDegrees);
93 roll()->setRawValue(rollDegrees);
94 pitch()->setRawValue(pitchDegrees);
95 heading()->setRawValue(yawDegrees);
100 if ((message.sysid != vehicle->
id()) || (message.compid != vehicle->
compId())) {
104 if (_receivingAttitudeQuaternion) {
108 mavlink_attitude_t attitude{};
109 mavlink_msg_attitude_decode(&message, &attitude);
111 _handleAttitudeWorker(attitude.roll, attitude.pitch, attitude.yaw);
118 mavlink_altitude_t altitude{};
119 mavlink_msg_altitude_decode(&message, &altitude);
123 altitudeRelative()->setRawValue(altitude.altitude_relative);
124 altitudeAMSL()->setRawValue(altitude.altitude_amsl);
132 if ((message.sysid != vehicle->
id()) || (message.compid != vehicle->
compId())) {
136 _receivingAttitudeQuaternion =
true;
138 mavlink_attitude_quaternion_t attitudeQuaternion{};
139 mavlink_msg_attitude_quaternion_decode(&message, &attitudeQuaternion);
141 QQuaternion quat(attitudeQuaternion.q1, attitudeQuaternion.q2, attitudeQuaternion.q3, attitudeQuaternion.q4);
142 QVector3D rates(attitudeQuaternion.rollspeed, attitudeQuaternion.pitchspeed, attitudeQuaternion.yawspeed);
143 QQuaternion repr_offset(attitudeQuaternion.repr_offset_q[0], attitudeQuaternion.repr_offset_q[1], attitudeQuaternion.repr_offset_q[2], attitudeQuaternion.repr_offset_q[3]);
146 if (repr_offset.length() >= 0.5f) {
148 rates = repr_offset * rates;
151 float attRoll, attPitch, attYaw;
152 float q[] = { quat.scalar(), quat.x(), quat.y(), quat.z() };
153 mavlink_quaternion_to_euler(q, &attRoll, &attPitch, &attYaw);
155 _handleAttitudeWorker(attRoll, attPitch, attYaw);
157 rollRate()->setRawValue(qRadiansToDegrees(rates[0]));
158 pitchRate()->setRawValue(qRadiansToDegrees(rates[1]));
159 yawRate()->setRawValue(qRadiansToDegrees(rates[2]));
166 mavlink_nav_controller_output_t navControllerOutput{};
167 mavlink_msg_nav_controller_output_decode(&message, &navControllerOutput);
169 altitudeTuningSetpoint()->setRawValue(
_altitudeTuningFact.rawValue().toDouble() - navControllerOutput.alt_error);
170 xTrackError()->setRawValue(navControllerOutput.xtrack_error);
171 airSpeedSetpoint()->setRawValue(
_airSpeedFact.rawValue().toDouble() - navControllerOutput.aspd_error);
172 distanceToNextWP()->setRawValue(navControllerOutput.wp_dist);
179 mavlink_vfr_hud_t vfrHud{};
180 mavlink_msg_vfr_hud_decode(&message, &vfrHud);
182 airSpeed()->setRawValue(qIsNaN(vfrHud.airspeed) ? 0 : vfrHud.airspeed);
183 groundSpeed()->setRawValue(qIsNaN(vfrHud.groundspeed) ? 0 : vfrHud.groundspeed);
184 climbRate()->setRawValue(qIsNaN(vfrHud.climb) ? 0 : vfrHud.climb);
185 throttlePct()->setRawValue(
static_cast<int16_t
>(vfrHud.throttle));
190 if (!qIsNaN(vfrHud.groundspeed) && !qIsNaN(
_distanceToHomeFact.cookedValue().toDouble())) {
191 timeToHome()->setRawValue(
_distanceToHomeFact.cookedValue().toDouble() / vfrHud.groundspeed);
199 mavlink_raw_imu_t imuRaw{};
200 mavlink_msg_raw_imu_decode(&message, &imuRaw);
202 imuTemp()->setRawValue((imuRaw.temperature == 0) ? 0 : (imuRaw.temperature * 0.01));
207#ifndef QGC_NO_ARDUPILOT_DIALECT
210 mavlink_rangefinder_t rangefinder{};
211 mavlink_msg_rangefinder_decode(&message, &rangefinder);
213 rangeFinderDist()->setRawValue(qIsNaN(rangefinder.distance) ? 0 : rangefinder.distance);
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
void _setTelemetryAvailable(bool telemetryAvailable)
void _handleAltitude(const mavlink_message_t &message)
void _handleNavControllerOutput(const mavlink_message_t &message)
void _handleAttitude(Vehicle *vehicle, const mavlink_message_t &message)
float _altitudeTuningOffset
void _handleRawImuTemp(const mavlink_message_t &message)
void _handleVfrHud(const mavlink_message_t &message)
void _handleAttitudeQuaternion(Vehicle *vehicle, const mavlink_message_t &message)
bool _altitudeMessageAvailable
void _handleRangefinder(const mavlink_message_t &message)
float limitAngleToPMPIf(double angle)