mirror of https://github.com/ArduPilot/ardupilot
Copter: bug fix for autotrim's roll axis backwards
This commit is contained in:
parent
21ff3853f1
commit
391236416b
|
@ -192,7 +192,7 @@ static void auto_trim()
|
||||||
led_mode = SAVE_TRIM_LEDS;
|
led_mode = SAVE_TRIM_LEDS;
|
||||||
|
|
||||||
// calculate roll trim adjustment
|
// 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
|
// calculate pitch trim adjustment
|
||||||
float pitch_trim_adjustment = ToRad((float)g.rc_2.control_in / 4000.0);
|
float pitch_trim_adjustment = ToRad((float)g.rc_2.control_in / 4000.0);
|
||||||
|
|
Loading…
Reference in New Issue