Skip to content

Commit

Permalink
Plane: Improve autotrim requirements and trim process
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 authored and Hwurzburg committed Jan 5, 2025
1 parent 8b7dd6b commit 8ca10a0
Showing 1 changed file with 8 additions and 3 deletions.
11 changes: 8 additions & 3 deletions plane/source/docs/auto-trim.rst
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,14 @@ ArduPlane provides a means to trim the pitch and roll control surfaces to correc
SERVO AUTO TRIM
---------------

By setting :ref:`SERVO_AUTO_TRIM<SERVO_AUTO_TRIM>` to 1, ArduPlane will constantly monitor how much it needs to correct the flying trim (on Roll and Pitch output control surfaces) to maintain level AHRS pitch and roll while in the aforementioned modes. Every 10 seconds, it will store this trim into the appropriate ``SERVOx_TRIM`` values for outputs assigned to control roll and pitch (ie Aileron/Elevator, Elevons, etc.). This includes flaperon and differential spoiler configurations. After a minute or so of flight, the trims will be adjusted such that minor trim errors will be canceled out when switching back to MANUAL and ACRO modes.

The amount that can be trimmed is center in the servo output range and limited to about 20% of the total ``SEROVX_MAX/MIN`` range, so very radical out-of-trim conditions are not correctable. Also, it will not be updated unless there is no pilot input, the plane is being controlled by the autopilot to be in generally level flight, and the plane is flying above 8m/s ground speed.
By setting :ref:`SERVO_AUTO_TRIM<SERVO_AUTO_TRIM>` to 1, ArduPlane will constantly monitor how much it needs to correct the flying trim (on Roll and Pitch output control surfaces) to maintain level AHRS pitch and roll while in the aforementioned modes.
Every 10 seconds, it will store this trim into the appropriate ``SERVOx_TRIM`` values for outputs assigned to control roll and pitch (ie Aileron/Elevator, Elevons, etc.).
This includes flaperon and differential spoiler configurations. After a minute or so of flight, the trims will be adjusted such that minor trim errors will be canceled out when switching back to MANUAL and ACRO modes.

The amount that can be trimmed is center in the servo output range and limited to about 20% of the total ``SEROVX_MAX/MIN`` range, so very radical out-of-trim conditions are not correctable.
These must be corrected mechanically. Once you correct them mechanically, fly again with :ref:`SERVO_AUTO_TRIM<SERVO_AUTO_TRIM>` enabled and verify the new ``SERVOx_TRIM`` is within 20% of the total ``SEROVX_MAX/MIN`` range.
Also, it will not be updated unless there is no pilot input, the plane is being controlled by the autopilot to be in generally level flight, and the plane is flying above 8m/s ground speed.
This means that that AHRS must have a ground speed estimate (from GPS usually).

For example if the elevator servo has the following values for min/max, 1100/1900, then the auto trim can change the trim value in the range of 1420 to 1580us.

Expand Down

0 comments on commit 8ca10a0

Please sign in to comment.