Plane: In FBWB make target alt track current if soaring is enabled and suppressing throttle.
This commit is contained in:
parent
ed7e359f4d
commit
e7418637ee
@ -313,9 +313,11 @@ void Plane::update_fbwb_speed_height(void)
|
||||
int32_t alt_change_cm = g.flybywire_climb_rate * elevator_input * dt * 100;
|
||||
change_target_altitude(alt_change_cm);
|
||||
|
||||
if (is_zero(elevator_input) && !is_zero(target_altitude.last_elevator_input)) {
|
||||
if ((is_zero(elevator_input) && !is_zero(target_altitude.last_elevator_input)) ||
|
||||
(g2.soaring_controller.is_active() && g2.soaring_controller.get_throttle_suppressed())) {
|
||||
// the user has just released the elevator, lock in
|
||||
// the current altitude
|
||||
// or we're in soaring mode with throttle suppressed
|
||||
set_target_altitude_current();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user