QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MAVLinkSystem.cc
Go to the documentation of this file.
1#include "MAVLinkSystem.h"
2
3#include "MAVLinkMessage.h"
6
7#include <algorithm>
8
9QGC_LOGGING_CATEGORY(MAVLinkSystemLog, "AnalyzeView.MAVLinkSystem")
10
11QGCMAVLinkSystem::QGCMAVLinkSystem(quint8 id, QObject *parent)
12 : QObject(parent)
13 , _systemID(id)
14 , _messages(new QmlObjectListModel(this))
15{
16 qCDebug(MAVLinkSystemLog) << "New Vehicle:" << id;
17}
18
23
24QGCMAVLinkMessage *QGCMAVLinkSystem::findMessage(uint32_t id, uint8_t compId, const QString &instanceValue)
25{
26 for (int i = 0; i < _messages->count(); i++) {
27 QGCMAVLinkMessage *const msg = qobject_cast<QGCMAVLinkMessage*>(_messages->get(i));
28 if(msg) {
29 if((msg->id() == id) && (msg->compId() == compId) && (msg->instanceValue() == instanceValue)) {
30 return msg;
31 }
32 }
33 }
34
35 return nullptr;
36}
37
39{
40 for (int i = 0; i < _messages->count(); i++) {
41 const QGCMAVLinkMessage *const msg = qobject_cast<const QGCMAVLinkMessage*>(_messages->get(i));
42 if (msg && (msg == message)) {
43 return i;
44 }
45 }
46
47 return -1;
48}
49
50void QGCMAVLinkSystem::_resetSelection()
51{
52 for (int i = 0; i < _messages->count(); i++) {
53 QGCMAVLinkMessage *const msg = qobject_cast<QGCMAVLinkMessage*>(_messages->get(i));
54 if (msg && msg->selected()) {
55 msg->setSelected(false);
56 }
57 }
58}
59
61{
62 if (sel < 0 || sel >= _messages->count()) {
63 return;
64 }
65
66 _selected = sel;
67 emit selectedChanged();
68 _resetSelection();
69 QGCMAVLinkMessage *const msg = qobject_cast<QGCMAVLinkMessage*>(_messages->get(sel));
70 if (msg && !msg->selected()) {
71 msg->setSelected(true);
72 }
73}
74
76{
78 if (_messages->count()) {
79 selectedMsg = qobject_cast<QGCMAVLinkMessage*>(_messages->get(_selected));
80 }
81
82 return selectedMsg;
83}
84
86{
88 if (_messages->count()) {
89 selectedMsg = qobject_cast<QGCMAVLinkMessage*>(_messages->get(_selected));
90 } else {
91 message->setSelected(true);
92 }
93 const auto cmp = [](const QObject *a, const QObject *b) {
94 const auto *ma = qobject_cast<const QGCMAVLinkMessage*>(a);
95 const auto *mb = qobject_cast<const QGCMAVLinkMessage*>(b);
96 if (!ma || !mb) return false;
97 return ma->name() < mb->name();
98 };
99 QList<QObject*> *const list = _messages->objectList();
100 const int insertPos = static_cast<int>(std::lower_bound(list->cbegin(), list->cend(), static_cast<const QObject*>(message), cmp) - list->cbegin());
101 _messages->insert(insertPos, message);
102 _checkCompID(message);
103
104 if (selectedMsg) {
105 const int idx = findMessage(selectedMsg);
106 if (idx >= 0) {
107 _selected = idx;
108 emit selectedChanged();
109 }
110 }
111}
112
113void QGCMAVLinkSystem::_checkCompID(const QGCMAVLinkMessage *message)
114{
115 if (_compIDsStr.isEmpty()) {
116 _compIDsStr << tr("Comp All");
117 }
118
119 if (!_compIDs.contains(static_cast<int>(message->compId()))) {
120 const int compId = static_cast<int>(message->compId());
121 _compIDs.append(compId);
122 _compIDsStr << tr("Comp %1").arg(compId);
123 emit compIDsChanged();
124 }
125}
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void setSelected(bool sel)
quint8 compId() const
QString instanceValue() const
bool selected() const
quint32 id() const
void setSelected(int sel)
QGCMAVLinkMessage * selectedMsg()
QGCMAVLinkMessage * findMessage(uint32_t id, uint8_t compId, const QString &instanceValue=QString())
void selectedChanged()
void append(QGCMAVLinkMessage *message)
Q_INVOKABLE QObject * get(int index)
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
QList< QObject * > * objectList()
void insert(int index, QObject *object)