Plane: fixed flaperon auto-trim

fixed direction of flaperon automatic trim with SERVO_AUTO_TRIM
This commit is contained in:
Andrew Tridgell 2020-03-23 09:42:15 +11:00
parent 62ff0a5d4f
commit 00585ebc3f

View File

@ -872,7 +872,7 @@ void Plane::servos_auto_trim(void)
g2.servo_channels.adjust_trim(SRV_Channel::k_vtail_right, pitch_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_flaperon_right, roll_I);
// cope with various dspoiler options
const int8_t bitmask = g2.crow_flap_options.get();