12 qCDebug(MAVLinkSystemLog) <<
"New Vehicle:" << id;
15QGCMAVLinkSystem::~QGCMAVLinkSystem()
22 for (
int i = 0; i < _messages->
count(); i++) {
25 if((msg->id() ==
id) && (msg->compId() == compId)) {
36 for (
int i = 0; i < _messages->
count(); i++) {
38 if (msg && (msg == message)) {
46void QGCMAVLinkSystem::_resetSelection()
48 for (
int i = 0; i < _messages->
count(); i++) {
50 if (msg && msg->selected()) {
51 msg->setSelected(
false);
57void QGCMAVLinkSystem::setSelected(
int sel)
59 if (sel >= _messages->
count()) {
67 if(msg && !msg->selected()) {
68 msg->setSelected(
true);
76 if (_messages->
count()) {
77 selectedMsg = qobject_cast<QGCMAVLinkMessage*>(_messages->
get(_selected));
91 if (aa->name() == bb->name()) {
92 return (aa->name() < bb->name());
95 return (aa->name() < bb->name());
101 if (_messages->
count()) {
102 selectedMsg = qobject_cast<QGCMAVLinkMessage*>(_messages->
get(_selected));
104 message->setSelected(
true);
106 _messages->
append(message);
108 if (_messages->
count() > 0) {
112 _checkCompID(message);
116 const int idx = findMessage(selectedMsg);
126 if (_compIDsStr.isEmpty()) {
127 _compIDsStr << tr(
"Comp All");
130 if (!_compIDs.contains(
static_cast<int>(message->compId()))) {
131 const int compId =
static_cast<int>(message->compId());
132 _compIDs.append(compId);
133 _compIDsStr << tr(
"Comp %1").arg(compId);
static bool messages_sort(const QObject *a, const QObject *b)
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void endResetModel()
Depth-counted endResetModel — only the outermost call has effect.
void beginResetModel()
Depth-counted beginResetModel — only the outermost call has effect.
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
QList< QObject * > * objectList()