4VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject *parent)
5 :
FactGroup(1000, QStringLiteral(
":/json/Vehicle/VibrationFact.json"), parent)
10 _addFact(&_clipCount1Fact);
11 _addFact(&_clipCount2Fact);
12 _addFact(&_clipCount3Fact);
14 _xAxisFact.setRawValue(qQNaN());
15 _yAxisFact.setRawValue(qQNaN());
16 _zAxisFact.setRawValue(qQNaN());
23 if (message.msgid != MAVLINK_MSG_ID_VIBRATION) {
27 mavlink_vibration_t vibration{};
28 mavlink_msg_vibration_decode(&message, &vibration);
30 xAxis()->setRawValue(vibration.vibration_x);
31 yAxis()->setRawValue(vibration.vibration_y);
32 zAxis()->setRawValue(vibration.vibration_z);
33 clipCount1()->setRawValue(vibration.clipping_0);
34 clipCount2()->setRawValue(vibration.clipping_1);
35 clipCount3()->setRawValue(vibration.clipping_2);
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
void _setTelemetryAvailable(bool telemetryAvailable)