QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MAVLinkInspectorController.cc
Go to the documentation of this file.
3#include "MAVLinkMessage.h"
4#include "MAVLinkProtocol.h"
5#include "MAVLinkSystem.h"
9#include "Vehicle.h"
10
11#include <QtQml/QQmlEngine>
12
13QGC_LOGGING_CATEGORY(MAVLinkInspectorControllerLog, "AnalyzeView.MAVLinkInspectorController")
14
15MAVLinkInspectorController::TimeScale_st::TimeScale_st(const QString &label_, uint32_t timeScale_)
16 : label(label_)
17 , timeScale(timeScale_)
18{
19
20}
21
22/*===========================================================================*/
23
24MAVLinkInspectorController::Range_st::Range_st(const QString &label_, qreal range_)
25 : label(label_)
26 , range(range_)
27{
28
29}
30
31/*===========================================================================*/
32
34 : QObject(parent)
35 , _updateFrequencyTimer(new QTimer(this))
36 , _systems(new QmlObjectListModel(this))
37{
38 // qCDebug(MAVLinkInspectorControllerLog) << Q_FUNC_INFO << this;
39
40 MultiVehicleManager *const multiVehicleManager = MultiVehicleManager::instance();
41 (void) connect(multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &MAVLinkInspectorController::_vehicleAdded);
42 (void) connect(multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved);
43 (void) connect(multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
44
45 MAVLinkProtocol *const mavlinkProtocol = MAVLinkProtocol::instance();
46 (void) connect(mavlinkProtocol, &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage);
47 (void) connect(_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
48
49 _updateFrequencyTimer->setInterval(1000);
50 _updateFrequencyTimer->setSingleShot(false);
51 _updateFrequencyTimer->start();
52
53 _timeScaleSt.append(new TimeScale_st(tr("5 Sec"), 5 * 1000));
54 _timeScaleSt.append(new TimeScale_st(tr("10 Sec"), 10 * 1000));
55 _timeScaleSt.append(new TimeScale_st(tr("30 Sec"), 30 * 1000));
56 _timeScaleSt.append(new TimeScale_st(tr("60 Sec"), 60 * 1000));
57 _timeScaleSt.append(new TimeScale_st(tr("2 Min"), 120 * 1000));
58 _timeScaleSt.append(new TimeScale_st(tr("5 Min"), 300 * 1000));
59
60 _rangeSt.append(new Range_st(tr("Auto"), 0));
61 _rangeSt.append(new Range_st(tr("10,000"), 10000));
62 _rangeSt.append(new Range_st(tr("1,000"), 1000));
63 _rangeSt.append(new Range_st(tr("100"), 100));
64 _rangeSt.append(new Range_st(tr("10"), 10));
65 _rangeSt.append(new Range_st(tr("1"), 1));
66 _rangeSt.append(new Range_st(tr("0.1"), 0.1));
67 _rangeSt.append(new Range_st(tr("0.01"), 0.01));
68 _rangeSt.append(new Range_st(tr("0.001"), 0.001));
69 _rangeSt.append(new Range_st(tr("0.0001"), 0.0001));
70}
71
73{
74 qDeleteAll(_timeScaleSt);
75 qDeleteAll(_rangeSt);
76 _systems->clearAndDeleteContents();
77
78 // qCDebug(MAVLinkInspectorControllerLog) << Q_FUNC_INFO << this;
79}
80
82{
83 QStringList names;
84 for (int i = 0; i < _systems->count(); i++) {
85 const QGCMAVLinkSystem *const system = qobject_cast<const QGCMAVLinkSystem*>(_systems->get(i));
86 if (system) {
87 names << tr("System %1").arg(system->id());
88 }
89 }
90 return names;
91}
92
94{
95 if (_timeScales.isEmpty()) {
96 for (const TimeScale_st *timeScale : _timeScaleSt) {
97 _timeScales << timeScale->label;
98 }
99 }
100
101 return _timeScales;
102}
103
105{
106 if (_rangeList.isEmpty()) {
107 for (const Range_st *range : _rangeSt) {
108 _rangeList << range->label;
109 }
110 }
111
112 return _rangeList;
113}
114
115void MAVLinkInspectorController::_setActiveVehicle(Vehicle *vehicle)
116{
117 if (vehicle) {
118 QGCMAVLinkSystem *const system = _findVehicle(static_cast<uint8_t>(vehicle->id()));
119 if (system) {
120 _activeSystem = system;
121 } else {
122 _activeSystem = nullptr;
123 }
124 } else {
125 _activeSystem = nullptr;
126 }
127
128 emit activeSystemChanged();
129}
130
131QGCMAVLinkSystem *MAVLinkInspectorController::_findVehicle(uint8_t id)
132{
133 for (int i = 0; i < _systems->count(); i++) {
134 QGCMAVLinkSystem *const system = qobject_cast<QGCMAVLinkSystem*>(_systems->get(i));
135 if (system && (system->id() == id)) {
136 return system;
137 }
138 }
139
140 return nullptr;
141}
142
143void MAVLinkInspectorController::_refreshFrequency()
144{
145 for (int i = 0; i < _systems->count(); i++) {
146 QGCMAVLinkSystem *const system = qobject_cast<QGCMAVLinkSystem*>(_systems->get(i));
147 if (!system) {
148 continue;
149 }
150
151 for (int messageIndex = 0; messageIndex < system->messages()->count(); messageIndex++) {
152 QGCMAVLinkMessage *const msg = qobject_cast<QGCMAVLinkMessage*>(system->messages()->get(messageIndex));
153 if (msg) {
154 msg->updateFreq();
155 }
156 }
157 }
158}
159
160void MAVLinkInspectorController::_vehicleAdded(Vehicle *vehicle)
161{
162 QGCMAVLinkSystem *sys = _findVehicle(static_cast<uint8_t>(vehicle->id()));
163
164 if (sys) {
166 } else {
167 sys = new QGCMAVLinkSystem(static_cast<uint8_t>(vehicle->id()), this);
168 _systems->append(sys);
169 }
170
171 (void) connect(vehicle, &Vehicle::mavlinkMsgIntervalsChanged, sys, [sys](uint8_t compid, uint16_t msgId, int32_t rate) {
172 for (int i = 0; i < sys->messages()->count(); i++) {
173 QGCMAVLinkMessage *const msg = qobject_cast<QGCMAVLinkMessage*>(sys->messages()->get(i));
174 if ((msg->compId() == compid) && (msg->id() == msgId)) {
175 msg->setTargetRateHz(rate);
176 break;
177 }
178 }
179 });
180
181 emit systemsChanged();
182}
183
184void MAVLinkInspectorController::_vehicleRemoved(const Vehicle *vehicle)
185{
186 QGCMAVLinkSystem *const system = _findVehicle(static_cast<uint8_t>(vehicle->id()));
187 if (!system) {
188 return;
189 }
190
191 system->deleteLater();
192 (void) _systems->removeOne(system);
193
194 emit systemsChanged();
195}
196
197void MAVLinkInspectorController::_receiveMessage(LinkInterface *link, const mavlink_message_t &message)
198{
199 Q_UNUSED(link);
200
201 QGCMAVLinkMessage *msg = nullptr;
202 QGCMAVLinkSystem *system = _findVehicle(message.sysid);
203 const QString instanceValue = QGCMAVLinkMessage::extractInstanceValue(message);
204
205 if (!system) {
206 system = new QGCMAVLinkSystem(message.sysid, this);
207 _systems->append(system);
208 emit systemsChanged();
209
210 if (!_activeSystem) {
211 _activeSystem = system;
212 emit activeSystemChanged();
213 }
214 } else {
215 msg = system->findMessage(message.msgid, message.compid, instanceValue);
216 }
217
218 if (!msg) {
219 msg = new QGCMAVLinkMessage(message, instanceValue, this);
220 system->append(msg);
221 } else {
222 msg->update(message);
223 }
224}
225
227{
228 QGCMAVLinkSystem *const system = _findVehicle(systemId);
229 if (system != _activeSystem) {
230 _activeSystem = system;
231 emit activeSystemChanged();
232 }
233}
234
236{
237 if (!_activeSystem) {
238 return;
239 }
240
241 MultiVehicleManager *const multiVehicleManager = MultiVehicleManager::instance();
242 if (!multiVehicleManager) {
243 return;
244 }
245
246 const uint8_t sysId = _selectedSystemID();
247 if (sysId == 0) {
248 return;
249 }
250
251 Vehicle *const vehicle = multiVehicleManager->getVehicleById(sysId);
252 if (!vehicle) {
253 return;
254 }
255
256 const QGCMAVLinkMessage *const msg = _activeSystem->selectedMsg();
257 if (!msg) {
258 return;
259 }
260
261 const uint8_t compId = _selectedComponentID();
262 if (compId == 0) {
263 return;
264 }
265
266 // TODO: Make QGCMAVLinkMessage a part of comm and use signals/slots for msg rate changes
267 vehicle->setMessageRate(compId, msg->id(), rate);
268}
269
270uint8_t MAVLinkInspectorController::_selectedSystemID() const
271{
272 return (_activeSystem ? _activeSystem->id() : 0);
273}
274
275uint8_t MAVLinkInspectorController::_selectedComponentID() const
276{
277 const QGCMAVLinkMessage *const msg = _activeSystem ? _activeSystem->selectedMsg() : nullptr;
278 return (msg ? msg->compId() : 0);
279}
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
The link interface defines the interface for all links used to communicate with the ground station ap...
MAVLink message inspector controller (provides the logic for UI display)
Q_INVOKABLE void setActiveSystem(int systemId)
Q_INVOKABLE void setMessageInterval(int32_t rate) const
MAVLinkInspectorController(QObject *parent=nullptr)
MAVLink micro air vehicle protocol reference implementation.
void messageReceived(LinkInterface *link, const mavlink_message_t &message)
static MAVLinkProtocol * instance()
static MultiVehicleManager * instance()
void vehicleAdded(Vehicle *vehicle)
void vehicleRemoved(Vehicle *vehicle)
void activeVehicleChanged(Vehicle *activeVehicle)
Q_INVOKABLE Vehicle * getVehicleById(int vehicleId) const
void setTargetRateHz(int32_t rate)
quint8 compId() const
void update(const mavlink_message_t &message)
static QString extractInstanceValue(const mavlink_message_t &message)
Extract the instance field value from a raw mavlink message, or empty string if none.
quint32 id() const
QmlObjectListModel * messages() const
QGCMAVLinkMessage * selectedMsg()
QGCMAVLinkMessage * findMessage(uint32_t id, uint8_t compId, const QString &instanceValue=QString())
quint8 id() const
void append(QGCMAVLinkMessage *message)
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
Q_INVOKABLE QObject * get(int index)
QObject * removeOne(const QObject *object) override final
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
int id() const
Definition Vehicle.h:425
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
Definition Vehicle.cc:3335
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)