QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleGeneratorFactGroup.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3
4VehicleGeneratorFactGroup::VehicleGeneratorFactGroup(QObject *parent)
5 : FactGroup(1000, QStringLiteral(":/json/Vehicle/GeneratorFact.json"), parent)
6{
7 _addFact(&_statusFact);
8 _addFact(&_genSpeedFact);
9 _addFact(&_batteryCurrentFact);
10 _addFact(&_loadCurrentFact);
11 _addFact(&_powerGeneratedFact);
12 _addFact(&_busVoltageFact);
13 _addFact(&_batCurrentSetpointFact);
14 _addFact(&_rectifierTempFact);
15 _addFact(&_genTempFact);
16 _addFact(&_runtimeFact);
17 _addFact(&_timeMaintenanceFact);
18
19 _statusFact.setRawValue(qQNaN());
20 _genSpeedFact.setRawValue(qQNaN());
21 _batteryCurrentFact.setRawValue(qQNaN());
22 _loadCurrentFact.setRawValue(qQNaN());
23 _powerGeneratedFact.setRawValue(qQNaN());
24 _busVoltageFact.setRawValue(qQNaN());
25 _batCurrentSetpointFact.setRawValue(qQNaN());
26 _rectifierTempFact.setRawValue(qQNaN());
27 _genTempFact.setRawValue(qQNaN());
28 _runtimeFact.setRawValue(qQNaN());
29 _timeMaintenanceFact.setRawValue(qQNaN());
30
31 (void) connect(status(), &Fact::rawValueChanged, this,& VehicleGeneratorFactGroup::_updateGeneratorFlags);
32}
33
34void VehicleGeneratorFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message)
35{
36 Q_UNUSED(vehicle);
37
38 switch (message.msgid) {
39 case MAVLINK_MSG_ID_GENERATOR_STATUS:
40 _handleGeneratorStatus(message);
41 break;
42 default:
43 break;
44 }
45}
46
47void VehicleGeneratorFactGroup::_handleGeneratorStatus(const mavlink_message_t &message)
48{
49 mavlink_generator_status_t generator{};
50 mavlink_msg_generator_status_decode(&message, &generator);
51
52 status()->setRawValue((generator.status == UINT16_MAX) ? qQNaN() : generator.status);
53 genSpeed()->setRawValue((generator.generator_speed == UINT16_MAX) ? qQNaN() : generator.generator_speed);
54 batteryCurrent()->setRawValue(generator.battery_current);
55 loadCurrent()->setRawValue(generator.load_current);
56 powerGenerated()->setRawValue(generator.power_generated);
57 busVoltage()->setRawValue(generator.bus_voltage);
58 rectifierTemp()->setRawValue((generator.rectifier_temperature == INT16_MAX) ? qQNaN() : generator.rectifier_temperature);
59 batCurrentSetpoint()->setRawValue(generator.bat_current_setpoint);
60 genTemp()->setRawValue((generator.generator_temperature == INT16_MAX) ? qQNaN() : generator.generator_temperature);
61 runtime()->setRawValue((generator.runtime == UINT32_MAX) ? qQNaN() : generator.runtime);
62 timeMaintenance()->setRawValue((generator.time_until_maintenance == INT32_MAX) ? qQNaN() : generator.time_until_maintenance);
63
65}
66
67void VehicleGeneratorFactGroup::_updateGeneratorFlags(const QVariant &value)
68{
69 const int statusFlag = value.toInt();
70 if (statusFlag == _prevFlag) {
71 return;
72 }
73
74 _prevFlag = statusFlag;
75 _flagsListGenerator.clear();
76
77 const QBitArray bitsetFlags(23);
78 for (qsizetype i = 0; i < bitsetFlags.size(); i++) {
79 if (bitsetFlags[i]) {
80 _flagsListGenerator.append(1);
81 } else {
82 _flagsListGenerator.append(0);
83 }
84 }
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
void rawValueChanged(const QVariant &value)