Transmitter Based Tuning¶
You can perform extensive parameter tuning in flight using your R/C transmitter. This is meant for advanced users who are unable to use the Autotune features or wish to do fine tuning with full manual tuning control of each parameter
Overview¶
Transmitter based tuning allows you to tune a single parameter or a set of parameters while flying. The basic idea is to link the tuning value of a parameter to a knob or slider on your transmitter then to adjust the parameter in flight by moving the knob.
First you should set RCx_OPTION
= 219, where x
is a free RC channel that will be used for transmitter tuning.
The TUNE parameter determines which parameter is being tuned.
The TUNE_MAX parameter determines the maximum value of the parameter when the channel is at RCx_MAX
, while the TUNE_MIN parameter determines the value when tuning RC channel is at RCx_MIN
.
TUNE Values¶
Value |
Meaning |
Parameter |
---|---|---|
0 |
None |
|
1 |
Stab Roll/Pitch kP |
|
4 |
Rate Roll/Pitch kP |
|
5 |
Rate Roll/Pitch kI |
|
21 |
Rate Roll/Pitch kD |
|
3 |
Stab Yaw kP |
|
6 |
Rate Yaw kP |
|
26 |
Rate Yaw kD |
|
56 |
Rate Yaw Filter |
|
55 |
Motor Yaw Headroom |
|
14 |
AltHold kP |
|
7 |
Throttle Rate kP |
|
34 |
Throttle Accel kP |
|
35 |
Throttle Accel kI |
|
36 |
Throttle Accel kD |
|
12 |
Loiter Pos kP |
|
22 |
Velocity XY kP |
|
28 |
Velocity XY kI |
|
10 |
WP Speed |
|
25 |
Acro RollPitch kP |
|
40 |
Acro Yaw kP |
|
45 |
RC Feel |
|
13 |
Heli Ext Gyro |
|
38 |
Declination |
|
39 |
Circle Rate |
|
46 |
Rate Pitch kP |
|
47 |
Rate Pitch kI |
|
48 |
Rate Pitch kD |
|
49 |
Rate Roll kP |
|
50 |
Rate Roll kI |
|
51 |
Rate Roll kD |
|
52 |
Rate Pitch FF |
|
53 |
Rate Roll FF |
|
54 |
Rate Yaw FF |
|
57 |
Winch |
|
58 |
SysID Magnitude |
|
59 |
|
** Traditional Heli Only
These values can be either set manually or using Mission Planner
Setting with Mission Planner¶
Rate Roll P and Rate Pitch P will be used in the following example procedure
Connect your autopilot to Mission Planner
From parameter list, assign channel
x
to transmitter tuning withRCx_OPTION
= 219.On Mission Planner, select CONFIG>>Extended Tuning
Set the TUNE drop down box option to “Rate Roll/Pitch kP”
Set Min to 0.08, Max to 0.20 (most copters ideal gain is within this range although from a small number of copter the Max can be as high as 0.25)
Push the “Write Params” button
Turn your transmitter’s CHx tuning knob to the minimum position, press the “Refresh Params” button and ensure that the Rate Roll P and Rate Pitch P values become 0.08 (or something very close)
Turn the CHx knob to its maximum position, press “Refresh Params” and ensure the Rate Roll P moves to 0.20
Move the CHx knob back to the middle
Arm and fly your copter in Stabilize mode adjusting the CHx knob until you get a copter that is responsive but not wobbly
After the flight, disconnect your LiPo battery and reconnect the autopilot to the mission planner
With the CHx knob in the position that gave the best performance, return to the Copter Pids screen and push the “Refresh Params” button
In the Rate Roll P and Rate Pitch P fields re-type the value that you see but just slightly modified so that the mission planner recognizes that it’s changed and resends to the autopilot (Note: if you re-type exactly the same number as what appears in Rate Roll P it won’t be updated). So for example, if the Rate Roll P appears as “0.1213” make it “0.1200”
Set CHx Opt back to “None” and push “Write Params”
Push the Disconnect button on the top right, and the Connect
Ensure that the Rate Roll P value is the value that you retyped in step #13
Note
While you are moving the tuning knob the values update at 3 times per second. The need to press the Refresh button in the mission planner in steps #7 and #8 above is just because the Copter is not sending the updates to the mission planner in real-time.