Copter: bug fix for autotrim's roll axis backwards

This commit is contained in:
Randy Mackay 2013-01-30 22:09:07 +09:00
parent 21ff3853f1
commit 391236416b
1 changed files with 1 additions and 1 deletions

View File

@ -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);