Plane: fixed auto-adjustment of flaperon trim

This commit is contained in:
Andrew Tridgell 2017-07-02 08:38:33 +10:00
parent 2cb511c049
commit d3f9afd4e7

View File

@ -826,8 +826,8 @@ void Plane::servos_auto_trim(void)
g2.servo_channels.adjust_trim(SRV_Channel::k_vtail_left, pitch_I);
g2.servo_channels.adjust_trim(SRV_Channel::k_vtail_right, pitch_I);
g2.servo_channels.adjust_trim(SRV_Channel::k_flaperon_left, pitch_I - roll_I);
g2.servo_channels.adjust_trim(SRV_Channel::k_flaperon_right, pitch_I + roll_I);
g2.servo_channels.adjust_trim(SRV_Channel::k_flaperon_left, roll_I);
g2.servo_channels.adjust_trim(SRV_Channel::k_flaperon_right, -roll_I);
g2.servo_channels.adjust_trim(SRV_Channel::k_dspoilerLeft1, pitch_I - roll_I);
g2.servo_channels.adjust_trim(SRV_Channel::k_dspoilerLeft2, pitch_I - roll_I);