QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
EscStatusFactGroupListModel.h
Go to the documentation of this file.
1#pragma once
2
4
6{
8 QML_ELEMENT
10
11public:
12 explicit EscStatusFactGroupListModel(QObject* parent = nullptr);
13
14protected:
15 // Overrides from FactGroupListModel
16 bool _shouldHandleMessage(const mavlink_message_t &message, QList<uint32_t> &ids) const final;
18};
19
21{
22 Q_OBJECT
23
24 Q_PROPERTY(Fact *rpm READ rpm CONSTANT)
25 Q_PROPERTY(Fact *current READ current CONSTANT)
26 Q_PROPERTY(Fact *voltage READ voltage CONSTANT)
27 Q_PROPERTY(Fact *count READ count CONSTANT)
28 Q_PROPERTY(Fact *connectionType READ connectionType CONSTANT)
29 Q_PROPERTY(Fact *info READ info CONSTANT)
30 Q_PROPERTY(Fact *failureFlags READ failureFlags CONSTANT)
31 Q_PROPERTY(Fact *errorCount READ errorCount CONSTANT)
32 Q_PROPERTY(Fact *temperature READ temperature CONSTANT)
33
34public:
35 explicit EscStatusFactGroup(uint32_t escIndex, QObject *parent = nullptr);
36
37 Fact *rpm() { return &_rpmFact; }
38 Fact *current() { return &_currentFact; }
39 Fact *voltage() { return &_voltageFact; }
40 Fact *count() { return &_countFact; }
41 Fact *connectionType() { return &_connectionTypeFact; }
42 Fact *info() { return &_infoFact; }
43 Fact *failureFlags() { return &_failureFlagsFact; }
44 Fact *errorCount() { return &_errorCountFact; }
45 Fact *temperature() { return &_temperatureFact; }
46
47 // Overrides from FactGroup
48 void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final;
49
50private:
51 void _handleEscInfo(Vehicle *vehicle, const mavlink_message_t &message);
52 void _handleEscStatus(Vehicle *vehicle, const mavlink_message_t &message);
53
54 Fact _rpmFact = Fact(0, QStringLiteral("rpm"), FactMetaData::valueTypeInt32);
55 Fact _currentFact = Fact(0, QStringLiteral("current"), FactMetaData::valueTypeFloat);
56 Fact _voltageFact = Fact(0, QStringLiteral("voltage"), FactMetaData::valueTypeFloat);
57 Fact _countFact = Fact(0, QStringLiteral("count"), FactMetaData::valueTypeUint8);
58 Fact _connectionTypeFact = Fact(0, QStringLiteral("connectionType"), FactMetaData::valueTypeUint8);
59 Fact _infoFact = Fact(0, QStringLiteral("info"), FactMetaData::valueTypeUint8);
60 Fact _failureFlagsFact = Fact(0, QStringLiteral("failureFlags"), FactMetaData::valueTypeUint16);
61 Fact _errorCountFact = Fact(0, QStringLiteral("errorCount"), FactMetaData::valueTypeUint32);
62 Fact _temperatureFact = Fact(0, QStringLiteral("temperature"), FactMetaData::valueTypeFloat);
63};
struct __mavlink_message mavlink_message_t
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.
A Fact is used to hold a single value within the system.
Definition Fact.h:19
QModelIndex index(int row, int column=0, const QModelIndex &parent=QModelIndex()) const override
QModelIndex parent(const QModelIndex &child) const override