Browse Source

Plane: fixed flaperon auto-trim

fixed direction of flaperon automatic trim with SERVO_AUTO_TRIM
zr-v5.1
Andrew Tridgell 5 years ago
parent
commit
bd341691e2
  1. 2
      ArduPlane/servos.cpp

2
ArduPlane/servos.cpp

@ -907,7 +907,7 @@ void Plane::servos_auto_trim(void) @@ -907,7 +907,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();

Loading…
Cancel
Save