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