QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleEFIFactGroup.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3
4VehicleEFIFactGroup::VehicleEFIFactGroup(QObject *parent)
5 : FactGroup(1000, QStringLiteral(":/json/Vehicle/EFIFact.json"), parent)
6{
7 _addFact(&_healthFact);
8 _addFact(&_ecuIndexFact);
9 _addFact(&_rpmFact);
10 _addFact(&_fuelConsumedFact);
11 _addFact(&_fuelFlowFact);
12 _addFact(&_engineLoadFact);
13 _addFact(&_sparkTimeFact);
14 _addFact(&_throttlePosFact);
15 _addFact(&_baroPressFact);
16 _addFact(&_intakePressFact);
17 _addFact(&_intakeTempFact);
18 _addFact(&_cylinderTempFact);
19 _addFact(&_ignTimeFact);
20 _addFact(&_exGasTempFact);
21 _addFact(&_injTimeFact);
22 _addFact(&_throttleOutFact);
23 _addFact(&_ptCompFact);
24 _addFact(&_ignVoltageFact);
25 _addFact(&_fuelPressureFact);
26
27 _healthFact.setRawValue(qQNaN());
28 _ecuIndexFact.setRawValue(qQNaN());
29 _rpmFact.setRawValue(qQNaN());
30 _fuelConsumedFact.setRawValue(qQNaN());
31 _fuelFlowFact.setRawValue(qQNaN());
32 _engineLoadFact.setRawValue(qQNaN());
33 _sparkTimeFact.setRawValue(qQNaN());
34 _throttlePosFact.setRawValue(qQNaN());
35 _baroPressFact.setRawValue(qQNaN());
36 _intakePressFact.setRawValue(qQNaN());
37 _intakeTempFact.setRawValue(qQNaN());
38 _cylinderTempFact.setRawValue(qQNaN());
39 _ignTimeFact.setRawValue(qQNaN());
40 _exGasTempFact.setRawValue(qQNaN());
41 _injTimeFact.setRawValue(qQNaN());
42 _throttleOutFact.setRawValue(qQNaN());
43 _ptCompFact.setRawValue(qQNaN());
44 _ignVoltageFact.setRawValue(qQNaN());
45 _fuelPressureFact.setRawValue(qQNaN());
46}
47
48void VehicleEFIFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message)
49{
50 Q_UNUSED(vehicle);
51
52 switch (message.msgid) {
53 case MAVLINK_MSG_ID_EFI_STATUS:
54 _handleEFIStatus(message);
55 break;
56 default:
57 break;
58 }
59}
60
61void VehicleEFIFactGroup::_handleEFIStatus(const mavlink_message_t &message)
62{
63 mavlink_efi_status_t efi{};
64 mavlink_msg_efi_status_decode(&message, &efi);
65
66 health()->setRawValue((efi.health == INT8_MAX) ? qQNaN() : efi.health);
67 ecuIndex()->setRawValue(efi.ecu_index);
68 rpm()->setRawValue(efi.rpm);
69 fuelConsumed()->setRawValue(efi.fuel_consumed);
70 fuelFlow()->setRawValue(efi.fuel_flow);
71 engineLoad()->setRawValue(efi.engine_load);
72 throttlePos()->setRawValue(efi.throttle_position);
73 sparkTime()->setRawValue(efi.spark_dwell_time);
74 baroPress()->setRawValue(efi.barometric_pressure);
75 intakePress()->setRawValue(efi.intake_manifold_pressure);
76 intakeTemp()->setRawValue(efi.intake_manifold_temperature);
77 cylinderTemp()->setRawValue(efi.cylinder_head_temperature);
78 ignTime()->setRawValue(efi.ignition_timing);
79 injTime()->setRawValue(efi.injection_time);
80 exGasTemp()->setRawValue(efi.exhaust_gas_temperature);
81 throttleOut()->setRawValue(efi.throttle_out);
82 ptComp()->setRawValue(efi.pt_compensation);
83 ignVoltage()->setRawValue(efi.ignition_voltage);
84 fuelPressure()->setRawValue(efi.fuel_pressure);
85
87}
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
void _setTelemetryAvailable(bool telemetryAvailable)
Definition FactGroup.cc:172