Plane: set failsafe limit for throttle left and right

This commit is contained in:
Iampete1 2022-02-16 17:10:00 +00:00 committed by Andrew Tridgell
parent 67b86867f2
commit 42a2e1094c
1 changed files with 4 additions and 0 deletions

View File

@ -86,11 +86,15 @@ void Plane::init_rc_out_main()
*/
if (!have_reverse_thrust()) {
SRV_Channels::set_trim_to_min_for(SRV_Channel::k_throttle);
SRV_Channels::set_trim_to_min_for(SRV_Channel::k_throttleLeft);
SRV_Channels::set_trim_to_min_for(SRV_Channel::k_throttleRight);
}
SRV_Channels::set_failsafe_limit(SRV_Channel::k_aileron, SRV_Channel::Limit::TRIM);
SRV_Channels::set_failsafe_limit(SRV_Channel::k_elevator, SRV_Channel::Limit::TRIM);
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttle, SRV_Channel::Limit::TRIM);
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::TRIM);
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleRight, SRV_Channel::Limit::TRIM);
SRV_Channels::set_failsafe_limit(SRV_Channel::k_rudder, SRV_Channel::Limit::TRIM);
}