mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: Fix safe disarm
This commit is contained in:
parent
0719626d2b
commit
f4a1410434
|
@ -395,8 +395,7 @@ int16_t AP_MotorsMulticopter::output_to_pwm(float actuator)
|
||||||
float pwm_output;
|
float pwm_output;
|
||||||
if (_spool_state == SpoolState::SHUT_DOWN) {
|
if (_spool_state == SpoolState::SHUT_DOWN) {
|
||||||
// in shutdown mode, use PWM 0 or minimum PWM
|
// in shutdown mode, use PWM 0 or minimum PWM
|
||||||
if (_disarm_disable_pwm && is_equal(_disarm_safe_timer, 0.0f) && !armed()) {
|
if (_disarm_disable_pwm && !armed()) {
|
||||||
// if (_disarm_disable_pwm && !armed()) {
|
|
||||||
pwm_output = 0;
|
pwm_output = 0;
|
||||||
} else {
|
} else {
|
||||||
pwm_output = get_pwm_output_min();
|
pwm_output = get_pwm_output_min();
|
||||||
|
@ -511,8 +510,8 @@ void AP_MotorsMulticopter::output_logic()
|
||||||
} else {
|
} else {
|
||||||
_disarm_safe_timer = _safe_time;
|
_disarm_safe_timer = _safe_time;
|
||||||
}
|
}
|
||||||
} else if (_disarm_safe_timer > 0.0f) {
|
} else {
|
||||||
_disarm_safe_timer -= 1.0f/_loop_rate;;
|
_disarm_safe_timer = 0.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// force desired and current spool mode if disarmed or not interlocked
|
// force desired and current spool mode if disarmed or not interlocked
|
||||||
|
|
Loading…
Reference in New Issue