mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_PX4: only consider power to have changed when armed
this prevents false positives with multi-battery setups
This commit is contained in:
parent
3c9ed9b5a6
commit
020d9ea78a
@ -361,11 +361,8 @@ void PX4AnalogIn::_timer_tick(void)
|
||||
if (system_power.hipower_5V_OC) flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT;
|
||||
if (_power_flags != 0 &&
|
||||
_power_flags != flags &&
|
||||
hal.scheduler->millis() > 5000) {
|
||||
// the power status has changed since boot, and more
|
||||
// than 5s after power on. The 5 second threshold is
|
||||
// for users who have multiple switches, and they
|
||||
// don't switch both at the same time.
|
||||
hal.util->get_soft_armed()) {
|
||||
// the power status has changed while armed
|
||||
flags |= MAV_POWER_STATUS_CHANGED;
|
||||
}
|
||||
_power_flags = flags;
|
||||
|
Loading…
Reference in New Issue
Block a user