QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleGeneratorFactGroup.h
Go to the documentation of this file.
1#pragma once
2
3#include "FactGroup.h"
4
6{
7 Q_OBJECT
8 Q_PROPERTY(Fact *status READ status CONSTANT)
9 Q_PROPERTY(Fact *genSpeed READ genSpeed CONSTANT)
10 Q_PROPERTY(Fact *batteryCurrent READ batteryCurrent CONSTANT)
11 Q_PROPERTY(Fact *loadCurrent READ loadCurrent CONSTANT)
12 Q_PROPERTY(Fact *powerGenerated READ powerGenerated CONSTANT)
13 Q_PROPERTY(Fact *busVoltage READ busVoltage CONSTANT)
14 Q_PROPERTY(Fact *rectifierTemp READ rectifierTemp CONSTANT)
15 Q_PROPERTY(Fact *batCurrentSetpoint READ batCurrentSetpoint CONSTANT)
16 Q_PROPERTY(Fact *genTemp READ genTemp CONSTANT)
17 Q_PROPERTY(Fact *runtime READ runtime CONSTANT)
18 Q_PROPERTY(Fact *timeMaintenance READ timeMaintenance CONSTANT)
19 Q_PROPERTY(QVariantList flagsListGenerator READ flagsListGenerator NOTIFY flagsListGeneratorChanged)
20
21public:
22 explicit VehicleGeneratorFactGroup(QObject *parent = nullptr);
23
24 Fact *status() { return &_statusFact; }
25 Fact *genSpeed() { return &_genSpeedFact; }
26 Fact *batteryCurrent() { return &_batteryCurrentFact; }
27 Fact *loadCurrent() { return &_loadCurrentFact; }
28 Fact *powerGenerated() { return &_powerGeneratedFact; }
29 Fact *busVoltage() { return &_busVoltageFact; }
30 Fact *rectifierTemp() { return &_rectifierTempFact; }
31 Fact *batCurrentSetpoint() { return &_batCurrentSetpointFact; }
32 Fact *genTemp() { return &_genTempFact; }
33 Fact *runtime() { return &_runtimeFact; }
34 Fact *timeMaintenance() { return &_timeMaintenanceFact; }
35 QVariantList &flagsListGenerator() {return _flagsListGenerator; }
36
37 // Overrides from FactGroup
38 void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final;
39
40signals:
42
43private slots:
44 void _updateGeneratorFlags(const QVariant &value);
45
46private:
47 void _handleGeneratorStatus(const mavlink_message_t &message);
48
49 Fact _statusFact = Fact(0, QStringLiteral("status"), FactMetaData::valueTypeUint64);
50 Fact _genSpeedFact = Fact(0, QStringLiteral("genSpeed"), FactMetaData::valueTypeUint16);
51 Fact _batteryCurrentFact = Fact(0, QStringLiteral("batteryCurrent"), FactMetaData::valueTypeFloat);
52 Fact _loadCurrentFact = Fact(0, QStringLiteral("loadCurrent"), FactMetaData::valueTypeFloat);
53 Fact _powerGeneratedFact = Fact(0, QStringLiteral("powerGenerated"), FactMetaData::valueTypeFloat);
54 Fact _busVoltageFact = Fact(0, QStringLiteral("busVoltage"), FactMetaData::valueTypeFloat);
55 Fact _rectifierTempFact = Fact(0, QStringLiteral("rectifierTemp"), FactMetaData::valueTypeInt16);
56 Fact _batCurrentSetpointFact = Fact(0, QStringLiteral("batCurrentSetpoint"), FactMetaData::valueTypeFloat);
57 Fact _genTempFact = Fact(0, QStringLiteral("genTemp"), FactMetaData::valueTypeInt16);
58 Fact _runtimeFact = Fact(0, QStringLiteral("runtime"), FactMetaData::valueTypeUint32);
59 Fact _timeMaintenanceFact = Fact(0, QStringLiteral("timeMaintenance"), FactMetaData::valueTypeInt32);
60
61 QVariantList _flagsListGenerator;
62 int _prevFlag = 0;
63};
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
A Fact is used to hold a single value within the system.
Definition Fact.h:19