AP_MotorsHeli: fix cooldown feature with new autorotation RSC library

This commit is contained in:
bnsgeyer 2024-10-02 23:30:49 -04:00 committed by Peter Barker
parent 4ce1c5db90
commit e30b4bf090
1 changed files with 14 additions and 8 deletions

View File

@ -295,6 +295,10 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
// ensure _idle_throttle not set to invalid value // ensure _idle_throttle not set to invalid value
_idle_throttle = get_idle_output(); _idle_throttle = get_idle_output();
// reset fast idle timer
_fast_idle_timer = 0.0;
break; break;
case RotorControlState::IDLE: case RotorControlState::IDLE:
@ -331,14 +335,11 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
_starting = false; _starting = false;
} }
} else { } else {
if (_cooldown_time > 0) { _idle_throttle = get_idle_output();
_idle_throttle = get_idle_output() * 1.5f; if (_fast_idle_timer > 0.0) {
_fast_idle_timer += dt; // running at fast idle for engine cool down
if (_fast_idle_timer > (float)_cooldown_time) { _idle_throttle *= 1.5;
_fast_idle_timer = 0.0f; _fast_idle_timer -= dt;
}
} else {
_idle_throttle = get_idle_output();
} }
} }
// this resets the bailout feature if the aircraft has landed. // this resets the bailout feature if the aircraft has landed.
@ -353,6 +354,11 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
// set main rotor ramp to increase to full speed // set main rotor ramp to increase to full speed
update_rotor_ramp(1.0f, dt); update_rotor_ramp(1.0f, dt);
// set fast idle timer so next time RSC goes to idle, the cooldown timer starts
if (_cooldown_time.get() > 0) {
_fast_idle_timer = _cooldown_time.get();
}
// ensure _idle_throttle not set to invalid value due to premature switch out of turbine start // ensure _idle_throttle not set to invalid value due to premature switch out of turbine start
if (_starting) { if (_starting) {
_idle_throttle = get_idle_output(); _idle_throttle = get_idle_output();