14 switch (message.msgid) {
37 :
FactGroupWithId(1000, QStringLiteral(
":/json/Vehicle/BatteryFact.json"), parent)
52 _batteryFunctionFact.
setRawValue(MAV_BATTERY_FUNCTION_UNKNOWN);
53 _batteryTypeFact.
setRawValue(MAV_BATTERY_TYPE_UNKNOWN);
60 _chargeStateFact.
setRawValue(MAV_BATTERY_CHARGE_STATE_UNDEFINED);
63 (void) connect(&_timeRemainingFact, &
Fact::rawValueChanged,
this, &BatteryFactGroup::_timeRemainingChanged);
68 switch (message.msgid) {
69 case MAVLINK_MSG_ID_HIGH_LATENCY:
70 _handleHighLatency(vehicle, message);
72 case MAVLINK_MSG_ID_HIGH_LATENCY2:
73 _handleHighLatency2(vehicle, message);
75 case MAVLINK_MSG_ID_BATTERY_STATUS:
76 _handleBatteryStatus(vehicle, message);
85 mavlink_high_latency_t highLatency{};
86 mavlink_msg_high_latency_decode(&message, &highLatency);
96 mavlink_msg_high_latency2_decode(&message, &highLatency2);
105 mavlink_battery_status_t batteryStatus{};
106 mavlink_msg_battery_status_decode(&message, &batteryStatus);
108 if (batteryStatus.id !=
id()->rawValue().toUInt()) {
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)) {
120 totalVoltage = cellVoltage;
122 totalVoltage += cellVoltage;
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)) {
131 totalVoltage += cellVoltage;
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);
148void BatteryFactGroup::_timeRemainingChanged(
const QVariant &value)
150 if (qIsNaN(value.toDouble())) {
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;
158 _timeRemainingStrFact.
setRawValue(QString::asprintf(
"%02dH:%02dM:%02dS", hours, minutes, seconds));
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.
Fact * percentRemaining()
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)
void _addFact(Fact *fact, const QString &name)
void rawValueChanged(const QVariant &value)
void setRawValue(const QVariant &value)
QModelIndex index(int row, int column=0, const QModelIndex &parent=QModelIndex()) const override
void clear() override final