Preparing for Tuning

It is important to conduct the steps in this wiki to prepare for manual or autotune. The following video covers the steps described on this wiki page.

Reduce Noisy Control Signals

Prior to starting to manually tune or AutoTune, make sure that the noise in the control signals is reduced as low as possible. The best way to do this is to use the harmonic notch filter. Follow the instructions in Helicopter Dynamic Notch Filter Setup.

A good way to check the control signals is to set the LOG_BITMASK parameter so that the FAST ATTITUDE and PID messages are selected in addition to the default selections. Use a GCS software like Mission Planner to view the PIDR.Act, PIDP.Act, and PIDY.Act. The noise in these signals should be low. The example below shows the target roll rate (red) and actual roll rate (green). The rates are given in rad/s. Note the vibration (noise) in the actual roll rate with peaks reaching 0.2 to -0.2 rad/s. This would be a lot of noise and could cause the autotune to fail or cause a poor tune. Ultimately, the deviation in the actual rates should be small (< 0.05 rad/s).

../_images/tradheli-vibration-example.png

Note

Before tuning, it is recommended to check that high frequency vibrations are not causing the “leans” (see Traditional Helicopter Tips)

Ensure Helicopter does not drift in a Hover

Follow the procedures in the Hover Trim section of the First Flight Tests wiki page to ensure the heli maintains a near driftless hover (< 1 m/s).

Initial Setup of Parameters

Pitch and Roll Axes

Below are the initial parameters values that should be used to start the tuning of your helicopter. The helicopter will be easily controllable with just the FF set to 0.15 on pitch and roll in the event that you need to modify the tail settings from the defaults.

ATC_ACCEL_P_MAX

110000

ATC_ACCEL_R_MAX

110000

ATC_ANG_PIT_P

4.5

ATC_ANG_RLL_P

4.5

ATC_RAT_PIT_D

0

ATC_RAT_PIT_FLTD

0

ATC_RAT_PIT_FLTE

20

ATC_RAT_PIT_FLTT

20

ATC_RAT_PIT_I

0.1

ATC_RAT_PIT_ILMI

0.05

ATC_RAT_PIT_IMAX

0.40

ATC_RAT_PIT_P

0

ATC_RAT_PIT_FF

0.15

ATC_RAT_RLL_D

0

ATC_RAT_RLL_FLTD

0

ATC_RAT_RLL_FLTE

20

ATC_RAT_RLL_FLTT

20

ATC_RAT_RLL_I

0.1

ATC_RAT_RLL_ILMI

0.05

ATC_RAT_RLL_IMAX

0.40

ATC_RAT_RLL_P

0

ATC_RAT_RLL_FF

0.15

ATC_INPUT_TC

0.15

Yaw Axis (Rudder)

It is recommended to make sure the tail functions properly before proceeding with tuning pitch and roll. Below are the suggested settings for yaw.

Note

UAV helicopters, as opposed to sport helicopters, will usually be running low headspeed and higher disc loading. With a mechanically driven tail this also means lower than normal tail speed and reduced tail authority. If your helicopter meets this description, it is recommended to set ATC_RAT_YAW_FF to 0.05 before the first test hover.

ATC_ACCEL_Y_MAX

80000

ATC_ANG_YAW_P

4.5

ATC_RAT_YAW_D

0.003

ATC_RAT_YAW_FLTD

0

ATC_RAT_YAW_FLTE

20

ATC_RAT_YAW_FLTT

20

ATC_RAT_YAW_I

0.12

ATC_RAT_YAW_ILMI

0.0

ATC_RAT_YAW_IMAX

0.33

ATC_RAT_YAW_P

0.18

ATC_RAT_YAW_FF

0.0