Skip to content

Commit

Permalink
Plane: During takeoff keep limit at LEVEL_ROLL_LIMIT until rotate spe…
Browse files Browse the repository at this point in the history
…ed is reached.
  • Loading branch information
samuelctabor authored and tridge committed Feb 8, 2021
1 parent 2ab8ad0 commit db8aaeb
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ArduPlane/takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ void Plane::takeoff_calc_roll(void)
const float lim1 = 5;
// at 15m allow for full roll
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;
} else if (baro_alt < auto_state.baro_takeoff_alt+lim2) {
float proportion = (baro_alt - (auto_state.baro_takeoff_alt+lim1)) / (lim2 - lim1);
Expand Down

0 comments on commit db8aaeb

Please sign in to comment.