Plane: During takeoff keep limit at LEVEL_ROLL_LIMIT until rotate speed is reached.

This commit is contained in:
Samuel Tabor 2019-11-07 13:58:55 -05:00 committed by Andrew Tridgell
parent 2ab8ad0ef0
commit db8aaeb63a

View File

@ -137,7 +137,7 @@ void Plane::takeoff_calc_roll(void)
const float lim1 = 5; const float lim1 = 5;
// at 15m allow for full roll // at 15m allow for full roll
const float lim2 = 15; const float lim2 = 15;
if (baro_alt < auto_state.baro_takeoff_alt+lim1) { if ((baro_alt < auto_state.baro_takeoff_alt+lim1) || (auto_state.highest_airspeed < g.takeoff_rotate_speed)) {
roll_limit = g.level_roll_limit; roll_limit = g.level_roll_limit;
} else if (baro_alt < auto_state.baro_takeoff_alt+lim2) { } else if (baro_alt < auto_state.baro_takeoff_alt+lim2) {
float proportion = (baro_alt - (auto_state.baro_takeoff_alt+lim1)) / (lim2 - lim1); float proportion = (baro_alt - (auto_state.baro_takeoff_alt+lim1)) / (lim2 - lim1);