forked from Archive/PX4-Autopilot
battery_status: clearly define and handle zero remaining flight time
This commit is contained in:
parent
73287e8e8c
commit
91c48606ee
|
@ -8,7 +8,7 @@ float32 current_average_a # Battery current average in amperes, -1 if unknown
|
|||
float32 discharged_mah # Discharged amount in mAh, -1 if unknown
|
||||
float32 remaining # From 1 to 0, -1 if unknown
|
||||
float32 scale # Power scaling factor, >= 1, or -1 if unknown
|
||||
float32 time_remaining_s # predicted time in seconds remaining until battery is empty under previous averaged load, -1 if unknown
|
||||
float32 time_remaining_s # predicted time in seconds remaining until battery is empty under previous averaged load, NAN if unknown
|
||||
float32 temperature # temperature of the battery. NaN if unknown
|
||||
int32 cell_count # Number of cells
|
||||
|
||||
|
|
|
@ -249,7 +249,7 @@ void Battery::computeScale()
|
|||
|
||||
float Battery::computeRemainingTime(float current_a)
|
||||
{
|
||||
float time_remaining_s = -1.f;
|
||||
float time_remaining_s{NAN};
|
||||
|
||||
// Only estimate remaining time with useful in flight current measurements
|
||||
if (_current_filter_a.getState() > 1.f) {
|
||||
|
|
|
@ -76,8 +76,8 @@ private:
|
|||
bat_msg.energy_consumed = -1;
|
||||
bat_msg.current_battery = (battery_status.connected) ? battery_status.current_filtered_a * 100 : -1;
|
||||
bat_msg.battery_remaining = (battery_status.connected) ? ceilf(battery_status.remaining * 100.f) : -1;
|
||||
// MAVLink extension: 0 is unsupported, in uORB it's -1
|
||||
bat_msg.time_remaining = (battery_status.connected && (battery_status.time_remaining_s >= 0.f)) ?
|
||||
// MAVLink extension: 0 is unsupported, in uORB it's NAN
|
||||
bat_msg.time_remaining = (battery_status.connected && (PX4_ISFINITE(battery_status.time_remaining_s))) ?
|
||||
math::max((int)battery_status.time_remaining_s, 1) : 0;
|
||||
|
||||
switch (battery_status.warning) {
|
||||
|
|
Loading…
Reference in New Issue