Commit 101adaf3 authored by Lorenz Meier's avatar Lorenz Meier

UAS: Interpret UINT16_MAX as unknown for battery voltage.

parent 7797d824
...@@ -495,36 +495,39 @@ void UAS::receiveMessage(mavlink_message_t message) ...@@ -495,36 +495,39 @@ void UAS::receiveMessage(mavlink_message_t message)
emit loadChanged(this,state.load/10.0f); emit loadChanged(this,state.load/10.0f);
emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time); emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
// Battery charge/time remaining/voltage calculations if (state.voltage_battery != UINT16_MAX) {
currentVoltage = state.voltage_battery/1000.0f; // Battery charge/time remaining/voltage calculations
lpVoltage = filterVoltage(currentVoltage); currentVoltage = state.voltage_battery/1000.0f;
tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage; lpVoltage = filterVoltage(currentVoltage);
tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage;
// We don't want to tick above the threshold
if (tickLowpassVoltage > tickVoltage)
{
lastTickVoltageValue = tickLowpassVoltage;
}
// We don't want to tick above the threshold if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f)
if (tickLowpassVoltage > tickVoltage) /* warn if lower than treshold */
{ && (lpVoltage < tickVoltage)
lastTickVoltageValue = tickLowpassVoltage; /* warn only if we have at least the voltage of an empty LiPo cell, else we're sampling something wrong */
} && (currentVoltage > 3.3f)
/* warn only if current voltage is really still lower by a reasonable amount */
&& ((currentVoltage - 0.2f) < tickVoltage)
/* warn only every 12 seconds */
&& (QGC::groundTimeUsecs() - lastVoltageWarning) > 12000000)
{
_say(QString("Voltage warning for system %1: %2 volts").arg(getUASID()).arg(lpVoltage, 0, 'f', 1, QChar(' ')));
lastVoltageWarning = QGC::groundTimeUsecs();
lastTickVoltageValue = tickLowpassVoltage;
}
if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f) if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
/* warn if lower than treshold */ chargeLevel = state.battery_remaining;
&& (lpVoltage < tickVoltage)
/* warn only if we have at least the voltage of an empty LiPo cell, else we're sampling something wrong */
&& (currentVoltage > 3.3f)
/* warn only if current voltage is really still lower by a reasonable amount */
&& ((currentVoltage - 0.2f) < tickVoltage)
/* warn only every 12 seconds */
&& (QGC::groundTimeUsecs() - lastVoltageWarning) > 12000000)
{
_say(QString("Voltage warning for system %1: %2 volts").arg(getUASID()).arg(lpVoltage, 0, 'f', 1, QChar(' ')));
lastVoltageWarning = QGC::groundTimeUsecs();
lastTickVoltageValue = tickLowpassVoltage;
}
if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage; emit batteryChanged(this, lpVoltage, currentCurrent, getChargeLevel(), 0);
chargeLevel = state.battery_remaining; }
emit batteryChanged(this, lpVoltage, currentCurrent, getChargeLevel(), 0);
emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time); emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time);
emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time); emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment