|
|
@ -3717,7 +3717,7 @@ void Commander::battery_status_check() |
|
|
|
size_t num_connected_batteries = 0; |
|
|
|
size_t num_connected_batteries = 0; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
for (int i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) { |
|
|
|
for (size_t i = 0; i < sizeof(_battery_subs) / sizeof(_battery_subs[0]); i++) { |
|
|
|
if (_battery_subs[i].updated() && _battery_subs[i].copy(&batteries[num_connected_batteries])) { |
|
|
|
if (_battery_subs[i].updated() && _battery_subs[i].copy(&batteries[num_connected_batteries])) { |
|
|
|
// We need to update the status flag if ANY battery is updated, because the system source might have
|
|
|
|
// We need to update the status flag if ANY battery is updated, because the system source might have
|
|
|
|
// changed, or might be nothing (if there is no battery connected)
|
|
|
|
// changed, or might be nothing (if there is no battery connected)
|
|
|
@ -3729,15 +3729,15 @@ void Commander::battery_status_check() |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
/* update battery status */ |
|
|
|
if (!battery_sub_updated) { |
|
|
|
if (battery_sub_updated) { |
|
|
|
// Nothing has changed since the last time this function was called, so nothing needs to be done now.
|
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// There are possibly multiple batteries, and we can't know which ones serve which purpose. So the safest
|
|
|
|
// There are possibly multiple batteries, and we can't know which ones serve which purpose. So the safest
|
|
|
|
// option is to check if ANY of them have a warning, and specifically find which one has the most
|
|
|
|
// option is to check if ANY of them have a warning, and specifically find which one has the most
|
|
|
|
// urgent warning.
|
|
|
|
// urgent warning.
|
|
|
|
uint8_t worst_warning = battery_status_s::BATTERY_WARNING_NONE; |
|
|
|
uint8_t worst_warning = battery_status_s::BATTERY_WARNING_NONE; |
|
|
|
// Sum the total current of all connected batteries. This is used to detect engine failure.
|
|
|
|
|
|
|
|
float total_current = 0; |
|
|
|
|
|
|
|
// To make sure that all connected batteries are being regularly reported, we check which one has the
|
|
|
|
// To make sure that all connected batteries are being regularly reported, we check which one has the
|
|
|
|
// oldest timestamp.
|
|
|
|
// oldest timestamp.
|
|
|
|
hrt_abstime oldest_update = hrt_absolute_time(); |
|
|
|
hrt_abstime oldest_update = hrt_absolute_time(); |
|
|
@ -3752,7 +3752,9 @@ void Commander::battery_status_check() |
|
|
|
oldest_update = batteries[i].timestamp; |
|
|
|
oldest_update = batteries[i].timestamp; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
total_current += batteries[i].current_filtered_a; |
|
|
|
if (batteries[i].system_source) { |
|
|
|
|
|
|
|
_battery_current = batteries[i].current_filtered_a; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
bool battery_warning_level_increased_while_armed = false; |
|
|
|
bool battery_warning_level_increased_while_armed = false; |
|
|
@ -3805,9 +3807,6 @@ void Commander::battery_status_check() |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
_battery_current = total_current; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void Commander::estimator_check() |
|
|
|
void Commander::estimator_check() |
|
|
|