mirror of https://github.com/ArduPilot/ardupilot
Plane: set failsafe limit for throttle left and right
This commit is contained in:
parent
67b86867f2
commit
42a2e1094c
|
@ -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);
|
||||
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue