mirror of https://github.com/ArduPilot/ardupilot
Plane: In transition use TRIM_THROTTLE when TKOFF_THR_MIN==0
This commit is contained in:
parent
6fee0eccad
commit
bc1e490257
|
@ -156,7 +156,7 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 60),
|
||||
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0),
|
||||
|
||||
// @Param: TKOFF_OPTIONS
|
||||
// @DisplayName: Takeoff options
|
||||
|
|
|
@ -567,6 +567,8 @@ float Plane::apply_throttle_limits(float throttle_in)
|
|||
) {
|
||||
if (aparm.takeoff_throttle_min.get() != 0) {
|
||||
min_throttle = MAX(min_throttle, aparm.takeoff_throttle_min.get());
|
||||
} else {
|
||||
min_throttle = MAX(min_throttle, aparm.throttle_cruise.get());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue