mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_Motors: stricter batt_voltage misconfiguration check
This commit is contained in:
parent
7de5bccc93
commit
d148039f65
@ -279,7 +279,7 @@ void AP_Motors::update_lift_max_from_batt_voltage()
|
||||
_batt_voltage_min = max(_batt_voltage_min, _batt_voltage_max * 0.6f);
|
||||
|
||||
// if disabled or misconfigured exit immediately
|
||||
if(_batt_voltage_max <= 0 && _batt_voltage_min >= _batt_voltage_max) {
|
||||
if((_batt_voltage_max <= 0) || (_batt_voltage_min >= _batt_voltage_max)) {
|
||||
_batt_voltage_filt.reset(1.0f);
|
||||
_lift_max = 1.0f;
|
||||
return;
|
||||
|
Loading…
Reference in New Issue
Block a user