mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: bug fix for autotrim's roll axis backwards
This commit is contained in:
parent
9c3b9907dd
commit
4813526725
@ -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…
Reference in New Issue
Block a user