diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 781457cf51512f48695eb66e9ffb5a9a31db0200..e89b2c3ba35c9b9e022f0d6bb5f16505554068a7 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -192,7 +192,7 @@ static void auto_trim() led_mode = SAVE_TRIM_LEDS; // calculate roll trim adjustment - float roll_trim_adjustment = ToRad((float)-g.rc_1.control_in / 4000.0); + float roll_trim_adjustment = ToRad((float)g.rc_1.control_in / 4000.0); // calculate pitch trim adjustment float pitch_trim_adjustment = ToRad((float)g.rc_2.control_in / 4000.0);