QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
BatteryFactGroupListModel.h
Go to the documentation of this file.
1#pragma once
2
4
6{
8 QML_ELEMENT
10
11public:
12 explicit BatteryFactGroupListModel(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 Q_PROPERTY(Fact *function READ function CONSTANT)
24 Q_PROPERTY(Fact *type READ type CONSTANT)
25 Q_PROPERTY(Fact *temperature READ temperature CONSTANT)
26 Q_PROPERTY(Fact *voltage READ voltage CONSTANT)
27 Q_PROPERTY(Fact *current READ current CONSTANT)
28 Q_PROPERTY(Fact *mahConsumed READ mahConsumed CONSTANT)
29 Q_PROPERTY(Fact *percentRemaining READ percentRemaining CONSTANT)
30 Q_PROPERTY(Fact *timeRemaining READ timeRemaining CONSTANT)
31 Q_PROPERTY(Fact *timeRemainingStr READ timeRemainingStr CONSTANT)
32 Q_PROPERTY(Fact *chargeState READ chargeState CONSTANT)
33 Q_PROPERTY(Fact *instantPower READ instantPower CONSTANT)
34
35public:
36 explicit BatteryFactGroup(uint32_t batteryId, QObject *parent = nullptr);
37
38 Fact *function() { return &_batteryFunctionFact; }
39 Fact *type() { return &_batteryTypeFact; }
40 Fact *voltage() { return &_voltageFact; }
41 Fact *percentRemaining() { return &_percentRemainingFact; }
42 Fact *mahConsumed() { return &_mahConsumedFact; }
43 Fact *current() { return &_currentFact; }
44 Fact *temperature() { return &_temperatureFact; }
45 Fact *instantPower() { return &_instantPowerFact; }
46 Fact *timeRemaining() { return &_timeRemainingFact; }
47 Fact *timeRemainingStr() { return &_timeRemainingStrFact; }
48 Fact *chargeState() { return &_chargeStateFact; }
49
50 // Overrides from FactGroup
51 void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final;
52
53private slots:
54 void _timeRemainingChanged(const QVariant &value);
55
56private:
57 void _handleHighLatency(Vehicle *vehicle, const mavlink_message_t &message);
58 void _handleHighLatency2(Vehicle *vehicle, const mavlink_message_t &message);
59 void _handleBatteryStatus(Vehicle *vehicle, const mavlink_message_t &message);
60
61 Fact _batteryFunctionFact = Fact(0, QStringLiteral("batteryFunction"), FactMetaData::valueTypeUint8);
62 Fact _batteryTypeFact = Fact(0, QStringLiteral("batteryType"), FactMetaData::valueTypeUint8);
63 Fact _voltageFact = Fact(0, QStringLiteral("voltage"), FactMetaData::valueTypeDouble);
64 Fact _currentFact = Fact(0, QStringLiteral("current"), FactMetaData::valueTypeDouble);
65 Fact _mahConsumedFact = Fact(0, QStringLiteral("mahConsumed"), FactMetaData::valueTypeDouble);
66 Fact _temperatureFact = Fact(0, QStringLiteral("temperature"), FactMetaData::valueTypeDouble);
67 Fact _percentRemainingFact = Fact(0, QStringLiteral("percentRemaining"), FactMetaData::valueTypeDouble);
68 Fact _timeRemainingFact = Fact(0, QStringLiteral("timeRemaining"), FactMetaData::valueTypeDouble);
69 Fact _timeRemainingStrFact = Fact(0, QStringLiteral("timeRemainingStr"), FactMetaData::valueTypeString);
70 Fact _chargeStateFact = Fact(0, QStringLiteral("chargeState"), FactMetaData::valueTypeUint8);
71 Fact _instantPowerFact = Fact(0, QStringLiteral("instantPower"), FactMetaData::valueTypeDouble);
72};
struct __mavlink_message mavlink_message_t
FactGroupWithId * _createFactGroupWithId(uint32_t id) final
bool _shouldHandleMessage(const mavlink_message_t &message, QList< uint32_t > &ids) const 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