Skip to content

Commit

Permalink
Plane: do not limit throttle in manual throttle modes (ArduPilot#32)
Browse files Browse the repository at this point in the history
  • Loading branch information
shellixyz committed Jun 15, 2022
1 parent 1f63e6d commit 5bf56ca
Showing 1 changed file with 1 addition and 2 deletions.
3 changes: 1 addition & 2 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -587,8 +587,7 @@ void Plane::set_servos_controlled(void)
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true));
} else {
// get throttle, but adjust center to output TRIM_THROTTLE if flight option set
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle,
constrain_int16(get_adjusted_throttle_input(true), min_throttle, max_throttle));
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_adjusted_throttle_input(true));
}
} else if (control_mode->is_guided_mode() &&
guided_throttle_passthru) {
Expand Down

0 comments on commit 5bf56ca

Please sign in to comment.