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