QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleEFIFactGroup.h
Go to the documentation of this file.
1
#pragma once
2
3
#include "
FactGroup.h
"
4
5
class
VehicleEFIFactGroup
:
public
FactGroup
6
{
7
Q_OBJECT
8
Q_PROPERTY(
Fact
*
health
READ
health
CONSTANT)
9
Q_PROPERTY(
Fact
*
ecuIndex
READ
ecuIndex
CONSTANT)
10
Q_PROPERTY(
Fact
*
rpm
READ
rpm
CONSTANT)
11
Q_PROPERTY(
Fact
*
fuelConsumed
READ
fuelConsumed
CONSTANT)
12
Q_PROPERTY(
Fact
*
fuelFlow
READ
fuelFlow
CONSTANT)
13
Q_PROPERTY(
Fact
*
engineLoad
READ
engineLoad
CONSTANT)
14
Q_PROPERTY(
Fact
*
throttlePos
READ
throttlePos
CONSTANT)
15
Q_PROPERTY(
Fact
*
sparkTime
READ
sparkTime
CONSTANT)
16
Q_PROPERTY(
Fact
*
baroPress
READ
baroPress
CONSTANT)
17
Q_PROPERTY(
Fact
*
intakePress
READ
intakePress
CONSTANT)
18
Q_PROPERTY(
Fact
*
intakeTemp
READ
intakeTemp
CONSTANT)
19
Q_PROPERTY(
Fact
*
cylinderTemp
READ
cylinderTemp
CONSTANT)
20
Q_PROPERTY(
Fact
*
ignTime
READ
ignTime
CONSTANT)
21
Q_PROPERTY(
Fact
*
injTime
READ
injTime
CONSTANT)
22
Q_PROPERTY(
Fact
*
exGasTemp
READ
exGasTemp
CONSTANT)
23
Q_PROPERTY(
Fact
*
throttleOut
READ
throttleOut
CONSTANT)
24
Q_PROPERTY(
Fact
*
ptComp
READ
ptComp
CONSTANT)
25
Q_PROPERTY(
Fact
*
ignVoltage
READ
ignVoltage
CONSTANT)
26
Q_PROPERTY(
Fact
*
fuelPressure
READ
fuelPressure
CONSTANT)
27
28
public
:
29
explicit
VehicleEFIFactGroup
(QObject *parent =
nullptr
);
30
31
Fact
*
health
() {
return
&_healthFact; }
32
Fact
*
ecuIndex
() {
return
&_ecuIndexFact; }
33
Fact
*
rpm
() {
return
&_rpmFact; }
34
Fact
*
fuelConsumed
() {
return
&_fuelConsumedFact; }
35
Fact
*
fuelFlow
() {
return
&_fuelFlowFact; }
36
Fact
*
engineLoad
() {
return
&_engineLoadFact; }
37
Fact
*
throttlePos
() {
return
&_throttlePosFact; }
38
Fact
*
sparkTime
() {
return
&_sparkTimeFact; }
39
Fact
*
baroPress
() {
return
&_baroPressFact; }
40
Fact
*
intakePress
() {
return
&_intakePressFact; }
41
Fact
*
intakeTemp
() {
return
&_intakeTempFact; }
42
Fact
*
cylinderTemp
() {
return
&_cylinderTempFact; }
43
Fact
*
ignTime
() {
return
&_ignTimeFact; }
44
Fact
*
injTime
() {
return
&_injTimeFact; }
45
Fact
*
exGasTemp
() {
return
&_exGasTempFact; }
46
Fact
*
throttleOut
() {
return
&_throttleOutFact; }
47
Fact
*
ptComp
() {
return
&_ptCompFact; }
48
Fact
*
ignVoltage
() {
return
&_ignVoltageFact; }
49
Fact
*
fuelPressure
() {
return
&_fuelPressureFact; }
50
51
// Overrides from FactGroup
52
void
handleMessage
(
Vehicle
*vehicle,
const
mavlink_message_t
&message)
final
;
53
54
private
:
55
void
_handleEFIStatus(
const
mavlink_message_t
&message);
56
57
Fact
_healthFact =
Fact
(0, QStringLiteral(
"health"
),
FactMetaData::valueTypeInt8
);
58
Fact
_ecuIndexFact =
Fact
(0, QStringLiteral(
"ecuIndex"
),
FactMetaData::valueTypeFloat
);
59
Fact
_rpmFact =
Fact
(0, QStringLiteral(
"rpm"
),
FactMetaData::valueTypeFloat
);
60
Fact
_fuelConsumedFact =
Fact
(0, QStringLiteral(
"fuelConsumed"
),
FactMetaData::valueTypeFloat
);
61
Fact
_fuelFlowFact =
Fact
(0, QStringLiteral(
"fuelFlow"
),
FactMetaData::valueTypeFloat
);
62
Fact
_engineLoadFact =
Fact
(0, QStringLiteral(
"engineLoad"
),
FactMetaData::valueTypeFloat
);
63
Fact
_throttlePosFact =
Fact
(0, QStringLiteral(
"throttlePos"
),
FactMetaData::valueTypeFloat
);
64
Fact
_sparkTimeFact =
Fact
(0, QStringLiteral(
"sparkTime"
),
FactMetaData::valueTypeFloat
);
65
Fact
_baroPressFact =
Fact
(0, QStringLiteral(
"baroPress"
),
FactMetaData::valueTypeFloat
);
66
Fact
_intakePressFact =
Fact
(0, QStringLiteral(
"intakePress"
),
FactMetaData::valueTypeFloat
);
67
Fact
_intakeTempFact =
Fact
(0, QStringLiteral(
"intakeTemp"
),
FactMetaData::valueTypeFloat
);
68
Fact
_cylinderTempFact =
Fact
(0, QStringLiteral(
"cylinderTemp"
),
FactMetaData::valueTypeFloat
);
69
Fact
_ignTimeFact =
Fact
(0, QStringLiteral(
"ignTime"
),
FactMetaData::valueTypeFloat
);
70
Fact
_injTimeFact =
Fact
(0, QStringLiteral(
"injTime"
),
FactMetaData::valueTypeFloat
);
71
Fact
_exGasTempFact =
Fact
(0, QStringLiteral(
"exGasTemp"
),
FactMetaData::valueTypeFloat
);
72
Fact
_throttleOutFact =
Fact
(0, QStringLiteral(
"throttleOut"
),
FactMetaData::valueTypeFloat
);
73
Fact
_ptCompFact =
Fact
(0, QStringLiteral(
"ptComp"
),
FactMetaData::valueTypeFloat
);
74
Fact
_ignVoltageFact =
Fact
(0, QStringLiteral(
"ignVoltage"
),
FactMetaData::valueTypeFloat
);
75
Fact
_fuelPressureFact =
Fact
(0, QStringLiteral(
"fuelPressure"
),
FactMetaData::valueTypeFloat
);
76
};
FactGroup.h
mavlink_message_t
struct __mavlink_message mavlink_message_t
Definition
QGCCorePlugin.h:24
FactGroup
Used to group Facts together into an object hierarachy.
Definition
FactGroup.h:16
FactMetaData::valueTypeInt8
@ valueTypeInt8
Definition
FactMetaData.h:26
FactMetaData::valueTypeFloat
@ valueTypeFloat
Definition
FactMetaData.h:33
Fact
A Fact is used to hold a single value within the system.
Definition
Fact.h:17
VehicleEFIFactGroup
Definition
VehicleEFIFactGroup.h:6
VehicleEFIFactGroup::injTime
Fact * injTime()
Definition
VehicleEFIFactGroup.h:44
VehicleEFIFactGroup::intakeTemp
Fact * intakeTemp()
Definition
VehicleEFIFactGroup.h:41
VehicleEFIFactGroup::ecuIndex
Fact * ecuIndex()
Definition
VehicleEFIFactGroup.h:32
VehicleEFIFactGroup::baroPress
Fact * baroPress()
Definition
VehicleEFIFactGroup.h:39
VehicleEFIFactGroup::fuelPressure
Fact * fuelPressure()
Definition
VehicleEFIFactGroup.h:49
VehicleEFIFactGroup::ptComp
Fact * ptComp()
Definition
VehicleEFIFactGroup.h:47
VehicleEFIFactGroup::engineLoad
Fact * engineLoad()
Definition
VehicleEFIFactGroup.h:36
VehicleEFIFactGroup::cylinderTemp
Fact * cylinderTemp()
Definition
VehicleEFIFactGroup.h:42
VehicleEFIFactGroup::throttleOut
Fact * throttleOut()
Definition
VehicleEFIFactGroup.h:46
VehicleEFIFactGroup::intakePress
Fact * intakePress()
Definition
VehicleEFIFactGroup.h:40
VehicleEFIFactGroup::health
Fact * health()
Definition
VehicleEFIFactGroup.h:31
VehicleEFIFactGroup::fuelConsumed
Fact * fuelConsumed()
Definition
VehicleEFIFactGroup.h:34
VehicleEFIFactGroup::sparkTime
Fact * sparkTime()
Definition
VehicleEFIFactGroup.h:38
VehicleEFIFactGroup::throttlePos
Fact * throttlePos()
Definition
VehicleEFIFactGroup.h:37
VehicleEFIFactGroup::exGasTemp
Fact * exGasTemp()
Definition
VehicleEFIFactGroup.h:45
VehicleEFIFactGroup::fuelFlow
Fact * fuelFlow()
Definition
VehicleEFIFactGroup.h:35
VehicleEFIFactGroup::ignTime
Fact * ignTime()
Definition
VehicleEFIFactGroup.h:43
VehicleEFIFactGroup::handleMessage
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final
Allows a FactGroup to parse incoming messages and fill in values.
Definition
VehicleEFIFactGroup.cc:48
VehicleEFIFactGroup::ignVoltage
Fact * ignVoltage()
Definition
VehicleEFIFactGroup.h:48
VehicleEFIFactGroup::rpm
Fact * rpm()
Definition
VehicleEFIFactGroup.h:33
Vehicle
Definition
Vehicle.h:86
src
Vehicle
FactGroups
VehicleEFIFactGroup.h
Generated by
1.9.8