mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 04:33:10 +08:00
Commander: call battery_status_check on update instead of early return
This commit is contained in:
@@ -2190,7 +2190,9 @@ Commander::run()
|
||||
|
||||
_cpuload_sub.update(&_cpuload);
|
||||
|
||||
battery_status_check();
|
||||
if (_battery_status_subs.updated()) {
|
||||
battery_status_check();
|
||||
}
|
||||
|
||||
/* If in INIT state, try to proceed to STANDBY state */
|
||||
if (!_status_flags.condition_calibration_enabled && _status.arming_state == vehicle_status_s::ARMING_STATE_INIT) {
|
||||
@@ -3604,13 +3606,6 @@ void Commander::avoidance_check()
|
||||
|
||||
void Commander::battery_status_check()
|
||||
{
|
||||
// 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)
|
||||
if (!_battery_status_subs.updated()) {
|
||||
// Nothing has changed since the last time this function was called, so nothing needs to be done now.
|
||||
return;
|
||||
}
|
||||
|
||||
battery_status_s batteries[_battery_status_subs.size()];
|
||||
size_t num_connected_batteries = 0;
|
||||
|
||||
|
||||
Reference in New Issue
Block a user