From 391236416bf58088f69a5745bfeba8e1012370e3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 30 Jan 2013 22:09:07 +0900 Subject: [PATCH] Copter: bug fix for autotrim's roll axis backwards --- ArduCopter/control_modes.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 781457cf51..e89b2c3ba3 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);