Skip to content

Commit

Permalink
Plane: Using TRIM_THROTTLE when TKOFF_THR_MIN==0
Browse files Browse the repository at this point in the history
This is related with the recent change of the TKOFF_THR_MIN default
value from 60 to 0.
  • Loading branch information
Georacer authored and Hwurzburg committed Sep 20, 2024
1 parent 7fc08a2 commit 40a6af8
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 @@ -258,7 +258,7 @@ void Plane::takeoff_calc_throttle() {
if (aparm.takeoff_throttle_min != 0) {
takeoff_state.throttle_lim_min = aparm.takeoff_throttle_min;
} else {
takeoff_state.throttle_lim_min = aparm.throttle_min;
takeoff_state.throttle_lim_min = aparm.throttle_cruise;
}

// Raise min to force max throttle for TKOFF_THR_MAX_T after a takeoff.
Expand Down

0 comments on commit 40a6af8

Please sign in to comment.