mirror of https://github.com/ArduPilot/ardupilot
Plane: removed forcing of trim for motors in quadplane
this caused problems with tricopter tail servos
This commit is contained in:
parent
642e5aa5b7
commit
0d4405106f
|
@ -487,7 +487,6 @@ bool QuadPlane::setup(void)
|
|||
for (uint8_t i=0; i<8; i++) {
|
||||
SRV_Channel::Aux_servo_function_t func = (SRV_Channel::Aux_servo_function_t)(SRV_Channel::k_motor1+i);
|
||||
SRV_Channels::set_failsafe_pwm(func, thr_min_pwm);
|
||||
SRV_Channels::set_trim_to_pwm_for(func, thr_min_pwm);
|
||||
}
|
||||
|
||||
#if HAVE_PX4_MIXER
|
||||
|
|
Loading…
Reference in New Issue