Unverified Commit 9502c20a authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #6316 from mavlink/lowBatteryState

Support for low battery state (and remaining time)
parents 07820407 32f88ed2
......@@ -46,5 +46,19 @@
"type": "float",
"decimalPlaces": 2,
"units": "W"
},
{
"name": "timeRemaining",
"shortDescription": "Time Remaining",
"type": "int32",
"units": "s"
},
{
"name": "chargeState",
"shortDescription": "Charge State",
"type": "uint8",
"enumStrings": "Low Battery State Not Provided,Normal Operation,Low Battery State,Critical Battery State,Emergency Battery State,Battery Failed,Battery Unhealthy",
"enumValues": "0,1,2,3,4,5,6",
"decimalPlaces": 0
}
]
......@@ -1319,6 +1319,20 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
}
_batteryFactGroup.cellCount()->setRawValue(cellCount);
//-- Time remaining in seconds (0 means not supported)
_batteryFactGroup.timeRemaining()->setRawValue(bat_status.time_remaining);
//-- Battery charge state (0 means not supported)
if(bat_status.charge_state <= MAV_BATTERY_CHARGE_STATE_UNHEALTHY) {
_batteryFactGroup.chargeState()->setRawValue(bat_status.charge_state);
} else {
_batteryFactGroup.chargeState()->setRawValue(0);
}
//-- TODO: Somewhere, actions would be taken based on this chargeState:
// MAV_BATTERY_CHARGE_STATE_CRITICAL: Battery state is critical, return / abort immediately
// MAV_BATTERY_CHARGE_STATE_EMERGENCY: Battery state is too low for ordinary abortion, fastest possible emergency stop preventing damage
// MAV_BATTERY_CHARGE_STATE_FAILED: Battery failed, damage unavoidable
// MAV_BATTERY_CHARGE_STATE_UNHEALTHY: Battery is diagnosed to be broken or an error occurred, usage is discouraged / prohibited
}
void Vehicle::_setHomePosition(QGeoCoordinate& homeCoord)
......@@ -3269,6 +3283,8 @@ const char* VehicleBatteryFactGroup::_currentFactName = "cur
const char* VehicleBatteryFactGroup::_temperatureFactName = "temperature";
const char* VehicleBatteryFactGroup::_cellCountFactName = "cellCount";
const char* VehicleBatteryFactGroup::_instantPowerFactName = "instantPower";
const char* VehicleBatteryFactGroup::_timeRemainingFactName = "timeRemaining";
const char* VehicleBatteryFactGroup::_chargeStateFactName = "chargeState";
const char* VehicleBatteryFactGroup::_settingsGroup = "Vehicle.battery";
......@@ -3289,6 +3305,8 @@ VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
, _temperatureFact (0, _temperatureFactName, FactMetaData::valueTypeDouble)
, _cellCountFact (0, _cellCountFactName, FactMetaData::valueTypeInt32)
, _instantPowerFact (0, _instantPowerFactName, FactMetaData::valueTypeFloat)
, _timeRemainingFact (0, _timeRemainingFactName, FactMetaData::valueTypeInt32)
, _chargeStateFact (0, _chargeStateFactName, FactMetaData::valueTypeUint8)
{
_addFact(&_voltageFact, _voltageFactName);
_addFact(&_percentRemainingFact, _percentRemainingFactName);
......@@ -3297,6 +3315,8 @@ VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
_addFact(&_temperatureFact, _temperatureFactName);
_addFact(&_cellCountFact, _cellCountFactName);
_addFact(&_instantPowerFact, _instantPowerFactName);
_addFact(&_timeRemainingFact, _timeRemainingFactName);
_addFact(&_chargeStateFact, _chargeStateFactName);
// Start out as not available
_voltageFact.setRawValue (_voltageUnavailable);
......
......@@ -254,6 +254,8 @@ public:
Q_PROPERTY(Fact* temperature READ temperature CONSTANT)
Q_PROPERTY(Fact* cellCount READ cellCount CONSTANT)
Q_PROPERTY(Fact* instantPower READ instantPower CONSTANT)
Q_PROPERTY(Fact* timeRemaining READ timeRemaining CONSTANT)
Q_PROPERTY(Fact* chargeState READ chargeState CONSTANT)
Fact* voltage (void) { return &_voltageFact; }
Fact* percentRemaining (void) { return &_percentRemainingFact; }
......@@ -262,7 +264,8 @@ public:
Fact* temperature (void) { return &_temperatureFact; }
Fact* cellCount (void) { return &_cellCountFact; }
Fact* instantPower (void) { return &_instantPowerFact; }
Fact* timeRemaining (void) { return &_timeRemainingFact; }
Fact* chargeState (void) { return &_chargeStateFact; }
static const char* _voltageFactName;
static const char* _percentRemainingFactName;
......@@ -271,6 +274,8 @@ public:
static const char* _temperatureFactName;
static const char* _cellCountFactName;
static const char* _instantPowerFactName;
static const char* _timeRemainingFactName;
static const char* _chargeStateFactName;
static const char* _settingsGroup;
......@@ -290,6 +295,8 @@ private:
Fact _temperatureFact;
Fact _cellCountFact;
Fact _instantPowerFact;
Fact _timeRemainingFact;
Fact _chargeStateFact;
};
class VehicleTemperatureFactGroup : public FactGroup
......
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