18 switch (message.msgid) {
55 :
FactGroupWithId(1000, QStringLiteral(
":/json/Vehicle/EscStatusFactGroup.json"), parent)
81 switch (message.msgid) {
82 case MAVLINK_MSG_ID_ESC_INFO:
83 _handleEscInfo(vehicle, message);
85 case MAVLINK_MSG_ID_ESC_STATUS:
86 _handleEscStatus(vehicle, message);
95 mavlink_esc_info_t escInfo{};
96 mavlink_msg_esc_info_decode(&message, &escInfo);
100 if (index < escInfo.index || index >= escInfo.index + 4) {
107 _connectionTypeFact.
setRawValue(escInfo.connection_type);
109 _failureFlagsFact.
setRawValue(escInfo.failure_flags[index]);
110 _errorCountFact.
setRawValue(escInfo.error_count[index]);
111 _temperatureFact.
setRawValue(escInfo.temperature[index]);
118 mavlink_esc_status_t escStatus{};
119 mavlink_msg_esc_status_decode(&message, &escStatus);
123 if (index < escStatus.index || index >= escStatus.index + 4) {
130 _currentFact.
setRawValue(escStatus.current[index]);
131 _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
EscStatusFactGroup(uint32_t escIndex, QObject *parent=nullptr)
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final
Allows a FactGroup to parse incoming messages and fill in values.
Dynamically manages FactGroupWithIds based on incoming messages.
FactGroupWithId is a FactGroup which has an id Fact which can be used to identify the group.
void _setTelemetryAvailable(bool telemetryAvailable)
void _addFact(Fact *fact, const QString &name)
void setRawValue(const QVariant &value)
QVariant rawValue() const
Value after translation.
QModelIndex index(int row, int column=0, const QModelIndex &parent=QModelIndex()) const override
void clear() override final