Browse Source

Copter: bug fix for autotrim's roll axis backwards

mission-4.1.18
Randy Mackay 12 years ago committed by rmackay9
parent
commit
4813526725
  1. 2
      ArduCopter/control_modes.pde

2
ArduCopter/control_modes.pde

@ -192,7 +192,7 @@ static void auto_trim() @@ -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.0f);
float roll_trim_adjustment = ToRad((float)g.rc_1.control_in / 4000.0f);
// calculate pitch trim adjustment
float pitch_trim_adjustment = ToRad((float)g.rc_2.control_in / 4000.0f);

Loading…
Cancel
Save