QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MAVLinkMessage.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QObject>
4#include <QtCore/QString>
5#include <QtCore/QLoggingCategory>
6#include <QtQmlIntegration/QtQmlIntegration>
7
8#include "MAVLinkLib.h"
9
11
13
15{
17 // QML_ELEMENT
18 Q_MOC_INCLUDE("QmlObjectListModel.h")
19 Q_PROPERTY(quint32 id READ id CONSTANT)
20 Q_PROPERTY(quint32 sysId READ sysId CONSTANT)
21 Q_PROPERTY(quint32 compId READ compId CONSTANT)
22 Q_PROPERTY(QString name READ name CONSTANT)
23 Q_PROPERTY(qreal actualRateHz READ actualRateHz NOTIFY actualRateHzChanged)
24 Q_PROPERTY(int32_t targetRateHz READ targetRateHz NOTIFY targetRateHzChanged)
26 Q_PROPERTY(QmlObjectListModel *fields READ fields CONSTANT)
27 Q_PROPERTY(bool fieldSelected READ fieldSelected NOTIFY fieldSelectedChanged)
28 Q_PROPERTY(bool selected READ selected NOTIFY selectedChanged)
29
30public:
31 explicit QGCMAVLinkMessage(const mavlink_message_t &message, QObject *parent = nullptr);
33
34 quint32 id() const { return _message.msgid; }
35 quint8 sysId() const { return _message.sysid; }
36 quint8 compId() const { return _message.compid; }
37 QString name() const { return _name; }
38 qreal actualRateHz() const { return _actualRateHz; }
39 int32_t targetRateHz() const { return _targetRateHz; }
40 quint64 count() const { return _count; }
41 quint64 lastCount() const { return _lastCount; }
42 QmlObjectListModel *fields() const { return _fields; }
43 bool fieldSelected() const { return _fieldSelected; }
44 bool selected() const { return _selected; }
45
46 void updateFieldSelection();
47 void update(const mavlink_message_t &message);
48 void updateFreq();
49 void setSelected(bool sel);
50 void setTargetRateHz(int32_t rate);
51
58
59private:
60 void _updateFields();
61
62 mavlink_message_t _message{};
63 QmlObjectListModel *_fields = nullptr;
64 QString _name;
65 qreal _actualRateHz = 0.0;
66 int32_t _targetRateHz = 0;
67 uint64_t _count = 1;
68 uint64_t _lastCount = 0;
69 bool _fieldSelected = false;
70 bool _selected = false;
71};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
int count READ count NOTIFY countChanged(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) bool dirty() const
QModelIndex index(int row, int column=0, const QModelIndex &parent=QModelIndex()) const override
QModelIndex parent(const QModelIndex &child) const override
void targetRateHzChanged()
void actualRateHzChanged()
void fieldSelectedChanged()
int count() const override final