Skip to content

Commit

Permalink
AP_MotorsHeli: fix cooldown feature with new autorotation RSC library
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer authored and peterbarker committed Oct 6, 2024
1 parent 4ce1c5d commit e30b4bf
Showing 1 changed file with 14 additions and 8 deletions.
22 changes: 14 additions & 8 deletions libraries/AP_Motors/AP_MotorsHeli_RSC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,6 +295,10 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)

// ensure _idle_throttle not set to invalid value
_idle_throttle = get_idle_output();

// reset fast idle timer
_fast_idle_timer = 0.0;

break;

case RotorControlState::IDLE:
Expand Down Expand Up @@ -331,14 +335,11 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
_starting = false;
}
} else {
if (_cooldown_time > 0) {
_idle_throttle = get_idle_output() * 1.5f;
_fast_idle_timer += dt;
if (_fast_idle_timer > (float)_cooldown_time) {
_fast_idle_timer = 0.0f;
}
} else {
_idle_throttle = get_idle_output();
_idle_throttle = get_idle_output();
if (_fast_idle_timer > 0.0) {
// running at fast idle for engine cool down
_idle_throttle *= 1.5;
_fast_idle_timer -= dt;
}
}
// this resets the bailout feature if the aircraft has landed.
Expand All @@ -353,6 +354,11 @@ void AP_MotorsHeli_RSC::output(RotorControlState state)
// set main rotor ramp to increase to full speed
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
if (_starting) {
_idle_throttle = get_idle_output();
Expand Down

0 comments on commit e30b4bf

Please sign in to comment.