QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
EscStatusFactGroupListModel.cc
Go to the documentation of this file.
2#include "MAVLinkLib.h"
3#include "QGCMAVLink.h"
4
6 : FactGroupListModel("escStatus", parent)
7{
8
9}
10
11bool EscStatusFactGroupListModel::_shouldHandleMessage(const mavlink_message_t &message, QList<uint32_t> &ids) const
12{
13 bool shouldHandle = false;
15
16 ids.clear();
17
18 switch (message.msgid) {
20 {
23 firstIndex = escStatus.index;
24 shouldHandle = true;
25 }
26 break;
28 {
31 firstIndex = escStatus.index;
32 shouldHandle = true;
33 }
34 break;
35 default:
36 shouldHandle = false; // Not a message we care about
37 break;
38 }
39
40 if (shouldHandle) {
41 for (uint32_t index = firstIndex; index <= firstIndex + 3; index++) {
42 ids.append(index);
43 }
44 }
45
46 return shouldHandle;
47}
48
53
54EscStatusFactGroup::EscStatusFactGroup(uint32_t escIndex, QObject *parent)
55 : FactGroupWithId(1000, QStringLiteral(":/json/Vehicle/EscStatusFactGroup.json"), parent)
56{
57 _addFact(&_rpmFact);
58 _addFact(&_currentFact);
59 _addFact(&_voltageFact);
60 _addFact(&_countFact);
61 _addFact(&_connectionTypeFact);
62 _addFact(&_infoFact);
63 _addFact(&_failureFlagsFact);
64 _addFact(&_errorCountFact);
65 _addFact(&_temperatureFact);
66
67 _idFact.setRawValue(escIndex);
68 _rpmFact.setRawValue(0);
69 _currentFact.setRawValue(0);
70 _voltageFact.setRawValue(0);
71 _countFact.setRawValue(0);
72 _connectionTypeFact.setRawValue(0);
73 _infoFact.setRawValue(0);
74 _failureFlagsFact.setRawValue(0);
75 _errorCountFact.setRawValue(0);
76 _temperatureFact.setRawValue(0);
77}
78
80{
81 switch (message.msgid) {
82 case MAVLINK_MSG_ID_ESC_INFO:
83 _handleEscInfo(vehicle, message);
84 break;
85 case MAVLINK_MSG_ID_ESC_STATUS:
86 _handleEscStatus(vehicle, message);
87 break;
88 default:
89 break;
90 }
91}
92
93void EscStatusFactGroup::_handleEscInfo(Vehicle * /*vehicle*/, const mavlink_message_t &message)
94{
95 mavlink_esc_info_t escInfo{};
96 mavlink_msg_esc_info_decode(&message, &escInfo);
97
98 uint8_t index = _idFact.rawValue().toUInt();
99
100 if (index < escInfo.index || index >= escInfo.index + 4) {
101 // Disregard ESC info messages which are not targeted at this ESC index
102 return;
103 }
104
105 index %= 4; // Convert to 0-based index for the arrays in escInfo
106 _countFact.setRawValue(escInfo.count);
107 _connectionTypeFact.setRawValue(escInfo.connection_type);
108 _infoFact.setRawValue(escInfo.info);
109 _failureFlagsFact.setRawValue(escInfo.failure_flags[index]);
110 _errorCountFact.setRawValue(escInfo.error_count[index]);
111 _temperatureFact.setRawValue(escInfo.temperature[index]);
112
114}
115
116void EscStatusFactGroup::_handleEscStatus(Vehicle * /*vehicle*/, const mavlink_message_t &message)
117{
118 mavlink_esc_status_t escStatus{};
119 mavlink_msg_esc_status_decode(&message, &escStatus);
120
121 uint8_t index = _idFact.rawValue().toUInt();
122
123 if (index < escStatus.index || index >= escStatus.index + 4) {
124 // Disregard ESC info messages which are not targeted at this ESC index
125 return;
126 }
127
128 index %= 4; // Convert to 0-based index for the arrays in escInfo
129 _rpmFact.setRawValue(escStatus.rpm[index]);
130 _currentFact.setRawValue(escStatus.current[index]);
131 _voltageFact.setRawValue(escStatus.voltage[index]);
132
134}
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)
Definition FactGroup.cc:175
void _addFact(Fact *fact, const QString &name)
Definition FactGroup.cc:116
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
QModelIndex index(int row, int column=0, const QModelIndex &parent=QModelIndex()) const override
void clear() override final