QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
BatteryFactGroupListModel.cc
Go to the documentation of this file.
2
4 : FactGroupListModel("battery", parent)
5{
6
7}
8
9bool BatteryFactGroupListModel::_shouldHandleMessage(const mavlink_message_t &message, QList<uint32_t> &ids) const
10{
11 ids.clear();
12
13 switch (message.msgid) {
16 ids.append(0); // High latency messages do not have a battery id
17 return true;
19 {
22 ids.append(batteryStatus.id);
23 return true;
24 }
25 default:
26 return false; // Not a message we care about
27 }
28}
29
34
35BatteryFactGroup::BatteryFactGroup(uint32_t batteryId, QObject *parent)
36 : FactGroupWithId(1000, QStringLiteral(":/json/Vehicle/BatteryFact.json"), parent)
37{
38 _addFact(&_batteryFunctionFact);
39 _addFact(&_batteryTypeFact);
40 _addFact(&_voltageFact);
41 _addFact(&_currentFact);
42 _addFact(&_mahConsumedFact);
43 _addFact(&_temperatureFact);
44 _addFact(&_percentRemainingFact);
45 _addFact(&_timeRemainingFact);
46 _addFact(&_timeRemainingStrFact);
47 _addFact(&_chargeStateFact);
48 _addFact(&_instantPowerFact);
49
50 _idFact.setRawValue(batteryId);
51 _batteryFunctionFact.setRawValue(MAV_BATTERY_FUNCTION_UNKNOWN);
52 _batteryTypeFact.setRawValue(MAV_BATTERY_TYPE_UNKNOWN);
53 _voltageFact.setRawValue(qQNaN());
54 _currentFact.setRawValue(qQNaN());
55 _mahConsumedFact.setRawValue(qQNaN());
56 _temperatureFact.setRawValue(qQNaN());
57 _percentRemainingFact.setRawValue(qQNaN());
58 _timeRemainingFact.setRawValue(qQNaN());
59 _chargeStateFact.setRawValue(MAV_BATTERY_CHARGE_STATE_UNDEFINED);
60 _instantPowerFact.setRawValue(qQNaN());
61
62 (void) connect(&_timeRemainingFact, &Fact::rawValueChanged, this, &BatteryFactGroup::_timeRemainingChanged);
63}
64
65void BatteryFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message)
66{
67 switch (message.msgid) {
68 case MAVLINK_MSG_ID_HIGH_LATENCY:
69 _handleHighLatency(vehicle, message);
70 break;
71 case MAVLINK_MSG_ID_HIGH_LATENCY2:
72 _handleHighLatency2(vehicle, message);
73 break;
74 case MAVLINK_MSG_ID_BATTERY_STATUS:
75 _handleBatteryStatus(vehicle, message);
76 break;
77 default:
78 break;
79 }
80}
81
82void BatteryFactGroup::_handleHighLatency(Vehicle * /*vehicle*/, const mavlink_message_t &message)
83{
84 mavlink_high_latency_t highLatency{};
85 mavlink_msg_high_latency_decode(&message, &highLatency);
86
87 percentRemaining()->setRawValue((highLatency.battery_remaining == UINT8_MAX) ? qQNaN() : highLatency.battery_remaining);
88
90}
91
92void BatteryFactGroup::_handleHighLatency2(Vehicle * /*vehicle*/, const mavlink_message_t &message)
93{
94 mavlink_high_latency2_t highLatency2{};
95 mavlink_msg_high_latency2_decode(&message, &highLatency2);
96
97 percentRemaining()->setRawValue((highLatency2.battery == -1) ? qQNaN() : highLatency2.battery);
98
100}
101
102void BatteryFactGroup::_handleBatteryStatus(Vehicle * /*vehicle*/, const mavlink_message_t &message)
103{
104 mavlink_battery_status_t batteryStatus{};
105 mavlink_msg_battery_status_decode(&message, &batteryStatus);
106
107 if (batteryStatus.id != id()->rawValue().toUInt()) {
108 // Disregard battery status messages which are not targeted at this battery id
109 return;
110 }
111
112 double totalVoltage = qQNaN();
113 for (int i = 0; i < 10; i++) {
114 const double cellVoltage = ((batteryStatus.voltages[i] == UINT16_MAX)) ? qQNaN() : (static_cast<double>(batteryStatus.voltages[i]) / 1000.0);
115 if (qIsNaN(cellVoltage)) {
116 break;
117 }
118 if (i == 0) {
119 totalVoltage = cellVoltage;
120 } else {
121 totalVoltage += cellVoltage;
122 }
123 }
124
125 for (int i = 0; i < 4; i++) {
126 const double cellVoltage = ((batteryStatus.voltages_ext[i] == 0)) ? qQNaN() : (static_cast<double>(batteryStatus.voltages_ext[i]) / 1000.0);
127 if (qIsNaN(cellVoltage)) {
128 break;
129 }
130 totalVoltage += cellVoltage;
131 }
132
133 function()->setRawValue(batteryStatus.battery_function);
134 type()->setRawValue(batteryStatus.type);
135 temperature()->setRawValue((batteryStatus.temperature == INT16_MAX) ? qQNaN() : (static_cast<double>(batteryStatus.temperature) / 100.0));
136 voltage()->setRawValue(totalVoltage);
137 current()->setRawValue((batteryStatus.current_battery == -1) ? qQNaN() : (static_cast<double>(batteryStatus.current_battery) / 100.0));
138 mahConsumed()->setRawValue((batteryStatus.current_consumed == -1) ? qQNaN() : batteryStatus.current_consumed);
139 percentRemaining()->setRawValue((batteryStatus.battery_remaining == -1) ? qQNaN() : batteryStatus.battery_remaining);
140 timeRemaining()->setRawValue((batteryStatus.time_remaining == 0) ? qQNaN() : batteryStatus.time_remaining);
141 chargeState()->setRawValue(batteryStatus.charge_state);
142 instantPower()->setRawValue(totalVoltage * current()->rawValue().toDouble());
143
145}
146
147void BatteryFactGroup::_timeRemainingChanged(const QVariant &value)
148{
149 if (qIsNaN(value.toDouble())) {
150 _timeRemainingStrFact.setRawValue("––:––:––");
151 } else {
152 const int totalSeconds = value.toInt();
153 const int hours = totalSeconds / 3600;
154 const int minutes = (totalSeconds % 3600) / 60;
155 const int seconds = totalSeconds % 60;
156
157 _timeRemainingStrFact.setRawValue(QString::asprintf("%02dH:%02dM:%02dS", hours, minutes, seconds));
158 }
159}
struct __mavlink_message mavlink_message_t
BatteryFactGroupListModel(QObject *parent=nullptr)
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.
void _setTelemetryAvailable(bool telemetryAvailable)
Definition FactGroup.cc:172
void rawValueChanged(const QVariant &value)
QModelIndex index(int row, int column=0, const QModelIndex &parent=QModelIndex()) const override
void clear() override final