17 switch (message.msgid) {
53EscStatusFactGroup::EscStatusFactGroup(uint32_t escIndex, QObject *parent)
54 :
FactGroupWithId(1000, QStringLiteral(
":/json/Vehicle/EscStatusFactGroup.json"), parent)
57 _addFact(&_currentFact);
58 _addFact(&_voltageFact);
59 _addFact(&_countFact);
60 _addFact(&_connectionTypeFact);
62 _addFact(&_failureFlagsFact);
63 _addFact(&_errorCountFact);
64 _addFact(&_temperatureFact);
67 _rpmFact.setRawValue(0);
68 _currentFact.setRawValue(0);
69 _voltageFact.setRawValue(0);
70 _countFact.setRawValue(0);
71 _connectionTypeFact.setRawValue(0);
72 _infoFact.setRawValue(0);
73 _failureFlagsFact.setRawValue(0);
74 _errorCountFact.setRawValue(0);
75 _temperatureFact.setRawValue(0);
80 switch (message.msgid) {
81 case MAVLINK_MSG_ID_ESC_INFO:
82 _handleEscInfo(vehicle, message);
84 case MAVLINK_MSG_ID_ESC_STATUS:
85 _handleEscStatus(vehicle, message);
94 mavlink_esc_info_t escInfo{};
95 mavlink_msg_esc_info_decode(&message, &escInfo);
97 uint8_t index =
_idFact.rawValue().toUInt();
99 if (index < escInfo.index || index >= escInfo.index + 4) {
105 _countFact.setRawValue(escInfo.count);
106 _connectionTypeFact.setRawValue(escInfo.connection_type);
107 _infoFact.setRawValue(escInfo.info);
108 _failureFlagsFact.setRawValue(escInfo.failure_flags[index]);
109 _errorCountFact.setRawValue(escInfo.error_count[index]);
110 _temperatureFact.setRawValue(escInfo.temperature[index]);
117 mavlink_esc_status_t escStatus{};
118 mavlink_msg_esc_status_decode(&message, &escStatus);
120 uint8_t index =
_idFact.rawValue().toUInt();
122 if (index < escStatus.index || index >= escStatus.index + 4) {
128 _rpmFact.setRawValue(escStatus.rpm[index]);
129 _currentFact.setRawValue(escStatus.current[index]);
130 _voltageFact.setRawValue(escStatus.voltage[index]);
struct __mavlink_message mavlink_message_t
EscStatusFactGroupListModel(QObject *parent=nullptr)
bool _shouldHandleMessage(const mavlink_message_t &message, QList< uint32_t > &ids) const final
FactGroupWithId * _createFactGroupWithId(uint32_t id) final
Dynamically manages FactGroupWithIds based on incoming messages.
void _setTelemetryAvailable(bool telemetryAvailable)
QModelIndex index(int row, int column=0, const QModelIndex &parent=QModelIndex()) const override
void clear() override final