TuningGuide.txt 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411
  1. Tuning Overview
  2. ---------------
  3. The following instruction assume that:
  4. a) your model is trimmed correctly in manual mode
  5. b) you have done your radio calibration
  6. c) you have calibrated your airspeed sensor
  7. d) you have set your APM and transmitter to be able to select FBW-A mode
  8. e) You have checked your pitch roll and yaw angle on the HUD and
  9. verified that they match the rotation of the model
  10. Ground checks
  11. -------------
  12. 1) On the ground select FBW-A mode
  13. 2) Rotate your model nose up - you should see the elevators/elevons deflect down
  14. 3) Rotate your model nose down - you should see the elevators/elevons deflect up
  15. 4) roll the model to the right - you should see the LH aileron/elevon
  16. go up and the RH aileron/elevon go down.
  17. 5) roll the model to the left - you should see the LH aileron/elevon
  18. go down and the RH aileron/elevon go up.
  19. 6) level the model - the control surfaces should be close to
  20. neutral. There will be a little bit of offset, but any more than
  21. 10% of your maximum throw indicates that the APM has not been
  22. leveled or the radio calibration needs to be repeated.
  23. 7) With the model level apply LH and RH roll stick inputs on your
  24. transmitter - the controls should deflect in the same direction that
  25. they would in manual mode.
  26. 8) With the model level apply up and down pitch stick inputs on your
  27. transmitter the controls should deflect in the same direction that
  28. they would in manual mode.
  29. 6) If you have an airspeed sensor enabled then blow air towards the
  30. front of the pitot tube and watch the HUD. You should see the
  31. airspeed reading increase
  32. Flight testing
  33. --------------
  34. Ideally you will need a second person to do this - one person to fly
  35. the plane and one person to adjust the parameters. To follow the
  36. manual parts of this procedure you need to be a proficient RC pilot
  37. and have the skills to be able to recover from an unusual attitude. If
  38. not, then get someone who can to help you.
  39. Initial assessment
  40. ------------------
  41. 1) Takeoff in manual and adjust the trims and throttle to a cruise
  42. position so that the plane flies straight and level at a speed that
  43. you are comfortable with. This will normally be somewhere between
  44. 30 and 60% throttle depending on how overpowered your model is.
  45. 2) With the plane flying away from you switch to FBW-A. It should
  46. continue to fly wings level and at a fairly constant height (it
  47. will climb or descend slowly). If it wants to roll or pitch more
  48. than a small amount then there is a problem with the models trim or
  49. radio calibration and you need to solve that first before
  50. proceeding further.
  51. 3) If the model starts to wag its wings, then the autopilot default
  52. gain is too high for your model (this is unlikely but could happen)
  53. and you need to switch back to manual immediately and ask your
  54. assistant to halve the CTL_RLL_K_P parameter before switching back
  55. into FBW-A
  56. 4) If the model starts to porpoise, the default autopilot gain is too
  57. high (this is unlikely but could happen) and you need to switch
  58. back to manual immediately and ask your assistant to halve the
  59. CTL_PTCH_K_P parameter before switching back into FBW-A
  60. Roll control tuning
  61. -------------------
  62. Method 1:
  63. This method is the simplest, but won't give the best result. For those
  64. users familiar with tuning the old PID controller gains, the K_P, K_I
  65. and K_D gains in this controller have the same effect, but there are some
  66. additional values that can be set by more advanced users.
  67. 1) With the model in FBW-A mode, put in a rapid bank angle demand,
  68. hold it and release. Do the same in the other direction. You want
  69. the model to roll quickly and smoothly to the new bank angle and
  70. back again without overshoot or any wing 'waggle'. If the roll
  71. response is too slow, then progressively increase the CTL_RLL_K_P
  72. gain in increments of 0.1 until you are happy with the response.
  73. 2) If during 1) the wings start to 'waggle' and you are not happy with
  74. the speed of the response, then CTL_RLL_K_D can be increased in small
  75. increments of 0.01 until the wing waggle goes away and step 1 can be
  76. repeated. Do not go above 0.1 for CTL_RLL_K_D without checking the
  77. temperature of your servos when you land as in extreme cases turning
  78. up this gain can cause rapid servo movement and overheat the servos
  79. leading to premature failure.
  80. Method 2:
  81. This method can give a better result, but requires more caution because
  82. step 2) can produce a high frequency instability that unless reversion
  83. back to manual is done quickly, could overstress the plane.
  84. 1) Follow basic method 1) first
  85. 2) Increase CTL_RLL_K_D in increments of 0.01 until it it starts to
  86. oscillate, then halve it.
  87. 3) Reduce CTL_RLL_TAU from the default value of 0.7 for a more rapid
  88. response if desired and if your aircraft is capable of doing so.
  89. If the bank angle starts to overshoot or you see wing 'waggle',
  90. you have gone too far.
  91. Advanced:
  92. 1) Select the tuning box on the bottom of the Mission planers Flight
  93. Data page. You should get a scrolling black window above the
  94. map. Double click in the black window and you should get a list of
  95. parameters to plot. Change the selection until you have the roll
  96. and nav_roll plotted. Nav_roll is the demand and roll is the
  97. response. You can use this to look for overshoot and other behavior
  98. that isn't so obvious from the ground looking at the model.
  99. 2) Check for any steady offset between nav-roll and roll. If there is
  100. one you can set the CTL_RLL_K_I to a small value (say 0.01) which
  101. will allow the control loop to slowly trim the aileron demand to
  102. remove the steady error. If you want it to trim faster, you can
  103. increase the value for this gain.
  104. 3) If you can slow down the rate of roll and make the model bank more
  105. smoothly by setting the roll rate limit CTL_RLL_RMAX parameter to a
  106. non zero value. A value of 60 deg/sec works weel for most models.
  107. The default is 0 which turns the rate limiter off and makes the
  108. effect of tuning easier to see.
  109. Pitch Control Tuning
  110. --------------------
  111. Method 1:
  112. This method is the simplest and but won't give the best result. For those
  113. users familiar with tuning the old PID controller gains, the K_P, K_I
  114. and K_D gains in this controller have the same effect, but there are some
  115. additional values that anbe set by more advanced users.
  116. 1) With the model in FBW-A mode and the throttle at the cruise
  117. position, put in a pitch angle demand, hold it and release. Do the
  118. same in the other direction. You want the model to pitch smoothly
  119. to the new pitch angle and back again without overshoot or
  120. proposing. If the pitch response is too slow, then progressively
  121. increase the CTL_PTCH_K_P parameter in increments of 0.1 you are happy
  122. with the speed of the response or it starts to porpoise a little. If
  123. you are happy with the response after this step, you can skip step 2)
  124. 2) If you get porposising and the response is still too sluggish, increase
  125. the CTL_RLL_K_D gain in small increments of 0.01 until the overshoot or
  126. porpoise goes away. If it hasn't worked by the time you have reached a
  127. value of 0.1 for CTL_PTCH_K_D, DON'T go any further until you have checked
  128. your servo temperatures immediately after landing as in extreme
  129. cases turning up this gain can cause rapid servo movement and overheat
  130. the servos leading to premature failure.
  131. 3) Now roll the model to maximum bank in each direction. The nose
  132. should stay fairly level during the turns without significant gain
  133. or loss of altitude. Some loss of altitude during sustained turns
  134. at constant throttle is expected, because the extra drag of turning
  135. slows the model down which will cause a mild descent. If the model
  136. gains height during the turns then you need to reduce the
  137. CTL_PTCH_K_RLL by small increments of 0.01 from the default value
  138. of 1.0. If the model descends immediately when the model banks (a
  139. mild descent later in the turn when the model slows down is normal
  140. as explained earlier) then increase the CTL_PTCH_K_RLL by small
  141. increments of 0.01 from the default value of 1.0. If you need to
  142. change the CTL_PTCH_K_RLL parameter outside the range from 0.7 to
  143. 1.4 then something is likely wrong with either the earlier tuning
  144. of your pitch loop, your airspeed calibration or you APM's bank
  145. angle estimate.
  146. Method 2:
  147. This method can give a better result, but requires more caution because
  148. step 2) can produce a high frequency instability that unless reversion
  149. back to manual is done quickly, could overstress the plane.
  150. 1) Follow Basic Method 1) first
  151. 2) Increase CTL_PTCH_K_D in increments of 0.01 until it it starts to
  152. oscillate, then halve it.
  153. 1) Reduce CTL_PTCH_TAU from the default value of 0.7 for a more rapid
  154. response if required and if your aircraft is capable of doing so.
  155. If the pitch response starts to overshoot, you have gone too far.
  156. Advanced Options:
  157. 3) Increase CTL_PTCH_K_I from the default value to more rapidly trim
  158. out errors in pitch angle (you will need to monitor the nav_pitch
  159. and pitch in the tuning graphs window to do this).
  160. 2) The maximum nose down and nose up pitch rate in degrees/second can
  161. be constrained by setting the CTL_PTCH_RMAX_D and CTL_PTCH_RMAX_U
  162. parameters to a value other than 0. These parameters can be
  163. used to limit the amount of g produced during a pull-up or push
  164. down.
  165. Yaw Control Tuning
  166. ------------------
  167. The yaw control loop can be configured either as a simple yaw damper
  168. (good for models with inadequate fin area) or as a combined yaw damper
  169. and sideslip controller. Because control of sideslip uses measured
  170. lateral acceleration, it will only work for those models that have
  171. enough fuselage side area to produce a measureable lateral
  172. acceleration when they sideslip (an extreme example of this is an
  173. aerobatic model flying a knife-edge maneuver where all of the lift is
  174. produced by the fuselage). Gliders with very skinny fuselages and
  175. flying wings cannot use this feature, but can still benefit from the
  176. yaw damper provided they have a yaw control of some sort of yaw
  177. control (rudder, differential airbrakes, etc)
  178. Tuning the yaw damper:
  179. 1) Verify that the CTL_YAW_K_A and CTL_YAW_K_I gain terms are set to
  180. zero, the CTL_YAW_K_RLL gain term is set to 1.0 and the CTL_YAW_K_D
  181. gain term is set to zero
  182. 2) Roll into and out of turns in both directions and observe the
  183. yawing motion as it rolls into the turn. If the nose yaws away from
  184. the direction of roll, you need to increase the KFF_RDDRMIX gain
  185. until the yaw goes away.
  186. 3) Increase CTL_YAW_K_D in small increments of 0.05 until the tail
  187. starts to 'wag'. Halve the gain from value at which you start to
  188. see the tail 'wag'.
  189. 4) Now roll the model into and out of turns in both directions. If the
  190. model has a tendency to yaw the nose to the outside of the turn,
  191. then increase the CTL_YAW_K_RLL gain term in increments of 0.01
  192. from its default value of 1.0. Conversely if the model has the
  193. tendency to yaw the nose to the inside of the turn on turn entry,
  194. then reduce the CTL_YAW_K_RLL gain term in increments of 0.01 from
  195. its default value of 1.0. If you have to go outside the range from
  196. 0.8 to 1.2, then there is something else that needs to be sorted
  197. and you should check step 2), the airspeed calibration and accuracy
  198. of the bank angle measurement.
  199. Tuning the sideslip controller (advanced):
  200. 1) Tune the yaw damper first
  201. 2) Set the CTL_YAW_K_I gain term to 1.0. If this causes the tail to
  202. 'wag' then reduce this gain until the wag stops
  203. 3) Bring up the tuning graph window in the mission planner and plot
  204. the lateral acceleration ay.
  205. 4) Roll the model rapidly from full bank in each direction and observe
  206. the lateral acceleration ay. If the lateral acceleration sits
  207. around zero and doesn't change when you roll into or out of turns
  208. then your model is very well trimmed and no sideslip control is
  209. required. You can change the CTL_YAW_K_I gain term back to zero.
  210. 5) IF you see that the y acceleration is offset or spikes up during
  211. turns, then progressively increase the CTL_YAW_K_A gain in steps of
  212. 0.5 until the error goes away or the tail starts to wag. If the
  213. tail starts to wag, then halve the gain from the value at which the
  214. wag appeared.
  215. Control Parameter Descriptions
  216. ------------------------------
  217. The default values for each parameter are shown.
  218. Pitch control parameters:
  219. Main Parameters:
  220. CTL_PTCH_K_P = 0.4
  221. This is the gain from demanded pitch rate to demanded
  222. elevator. Provided CTL_PTCH_OMEGA is set to 1.0, then this gain works
  223. the same way as the P term in the old PID and can be set to the same
  224. value.
  225. CTL_PTCH_K_I = 0.0
  226. This is the gain for integration of the pitch rate error. It has
  227. essentially the same effect as the I term in the old PID. This can be
  228. set to 0 as a default, however users can increment this to make the
  229. pitch angle tracking more accurate.
  230. CTL_PTCH_K_D = 0.0
  231. This is the gain from pitch rate error to demanded elevator. This
  232. adjusts the damping of the pitch control loop. It has the same effect
  233. as the D term in the old PID but without the large spikes in servo
  234. demands. this will be set to 0 as a default. Some airframes such as
  235. flying wings that have poor pitch damping can benefit from a small
  236. value of up to 0.1 on this gain term. This should be increased in 0.01
  237. increments as to high a value can lead to a high frequency pitch
  238. oscillation that could overstress the airframe.
  239. CTL_PTCH_K_RLL = 1.0
  240. This is the gain term that is applied to the pitch rate offset
  241. calculated as required to keep the nose level during turns. The
  242. default value is 1 which will work for all models. Advanced users can
  243. use it to correct for height variation in turns. If height is lost
  244. initially in the turn this can be increased in small increments of
  245. 0.05 to compensate. If height is gained initially then it can be
  246. decreased.
  247. Advanced Parameters:
  248. CTL_PTCH_RMAX_D = 0
  249. This sets the maximum nose down pitch rate that the controller will
  250. demand in (degrees/sec). Setting it to zero disables the limit.
  251. CTL_PTCH_RMAX_U = 0
  252. This sets the maximum nose up pitch rate that the controller will
  253. demand (degrees/sec). Setting it to zero disables the limit.
  254. CTL_PTCH_OMEGA = 1.0
  255. This is the gain from pitch angle error to demanded pitch rate. It
  256. controls the time constant from demanded to achieved pitch angle. For
  257. example if a time constant from demanded to achieved pitch of 0.5 sec
  258. was required, this gain would be set to 1/0.5 = 2.0. A value of 1.0 is
  259. a good default and will work with nearly all models. Advanced users
  260. may want to increase this to obtain a faster response.
  261. Roll Control Parameters:
  262. Main Parameters:
  263. CTL_RLL_K_P = 0.4
  264. This is the gain from demanded roll rate to demanded aileron. Provided
  265. CTL_RLL_OMEGA is set to 1.0, then this gain works the same way as the
  266. P term in the old PID and can be set to the same value.
  267. CTL_RLL_K_I = 0.0
  268. This is the gain for integration of the roll rate error. It has
  269. essentially the same effect as the I term in the old PID. This can be
  270. set to 0 as a default, however users can increment this to enable the
  271. controller trim out any roll trim offset.
  272. CTL_RLL_K_D = 0.0
  273. This is the gain from pitch rate error to demanded elevator. This
  274. adjusts the damping of the roll control loop. It has the same effect
  275. as the D term in the old PID but without the large spikes in servo
  276. demands. This will be set to 0 as a default. This should be increased
  277. in 0.01 increments as too high a value can lead to high frequency roll
  278. oscillation.
  279. Advanced Parameters:
  280. CTL_RLL_OMEGA = 1.0
  281. This is the gain from roll angle error to demanded roll rate. It
  282. controls the time constant from demanded to achieved roll angle. For
  283. example if a time constant from demanded to achieved roll of 0.5 sec
  284. was required, this gain would be set to 1/0.5 = 2.0. A value of 1.0 is
  285. a good default and will work with nearly all models. Advanced users
  286. may want to increase this to obtain a faster response.
  287. CTL_RLL_RMAX = 60;
  288. This sets the maximum roll rate that the controller will demand
  289. (degrees/sec). Setting it to zero disables the limit. If this value is
  290. set too low, then the roll can't keep up with the navigation demands
  291. and the plane will start weaving. If it is set too high (or disabled
  292. by setting to zero) then ailerons will get large inputs at the start
  293. of turns. A limit of 60 degrees/sec is a good default.
  294. Yaw Control Parameters:
  295. Advanced Parameters:
  296. CTL_YAW_K_A = 0.0
  297. This is the gain from measured lateral acceleration to demanded yaw
  298. rate. It should be set to zero unless active control of sideslip is
  299. desired. This will only work effectively if there is enough fuselage
  300. side area to generate a measureable lateral acceleration when the
  301. model sideslips. Flying wings and most gliders cannot use this
  302. term. This term should only be adjusted after the basic yaw damper
  303. gain K_D is tuned and the K_I integrator gain has been set. Set this
  304. gain to zero if only yaw damping is required.
  305. CTL_YAW_K_D = 0.0
  306. This is the gain from yaw rate to rudder. It acts as a damper on yaw
  307. motion. If a basic yaw damper is required, this gain term can be
  308. incremented, whilst leaving the K_A and K_I gains at zero.
  309. CTL_YAW_K_I = 0.0
  310. This is the integral gain from lateral acceleration error. This gain
  311. should only be non-zero if active control over sideslip is desired. If
  312. active control over sideslip is required then this can be set to 1.0
  313. as a first try.
  314. CTL_YAW_K_RLL = 1.0
  315. This is the gain term that is applied to the yaw rate offset
  316. calculated as required to keep the yaw rate consistent with the turn
  317. rate for a coordinated turn. The default value is 1 which will work
  318. for all models. Advanced users can use it to correct for any tendency
  319. to yaw away from or into the turn once the turn is
  320. established. Increase to make the model yaw more initially and
  321. decrease to make the model yaw less initially. If values greater than
  322. 1.1 or less than 0.9 are required then it normally indicates a problem
  323. with the airspeed calibration.