AC_AutoTune.cpp 72 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728
  1. #include "AC_AutoTune.h"
  2. #include <GCS_MAVLink/GCS.h>
  3. #include <AP_Scheduler/AP_Scheduler.h>
  4. /*
  5. * autotune support for multicopters
  6. *
  7. * Instructions:
  8. * 1) Set up one flight mode switch position to be AltHold.
  9. * 2) Set the Ch7 Opt or Ch8 Opt to AutoTune to allow you to turn the auto tuning on/off with the ch7 or ch8 switch.
  10. * 3) Ensure the ch7 or ch8 switch is in the LOW position.
  11. * 4) Wait for a calm day and go to a large open area.
  12. * 5) Take off and put the vehicle into AltHold mode at a comfortable altitude.
  13. * 6) Set the ch7/ch8 switch to the HIGH position to engage auto tuning:
  14. * a) You will see it twitch about 20 degrees left and right for a few minutes, then it will repeat forward and back.
  15. * b) Use the roll and pitch stick at any time to reposition the copter if it drifts away (it will use the original PID gains during repositioning and between tests).
  16. * When you release the sticks it will continue auto tuning where it left off.
  17. * c) Move the ch7/ch8 switch into the LOW position at any time to abandon the autotuning and return to the origin PIDs.
  18. * d) Make sure that you do not have any trim set on your transmitter or the autotune may not get the signal that the sticks are centered.
  19. * 7) When the tune completes the vehicle will change back to the original PID gains.
  20. * 8) Put the ch7/ch8 switch into the LOW position then back to the HIGH position to test the tuned PID gains.
  21. * 9) Put the ch7/ch8 switch into the LOW position to fly using the original PID gains.
  22. * 10) If you are happy with the autotuned PID gains, leave the ch7/ch8 switch in the HIGH position, land and disarm to save the PIDs permanently.
  23. * If you DO NOT like the new PIDS, switch ch7/ch8 LOW to return to the original PIDs. The gains will not be saved when you disarm
  24. *
  25. * What it's doing during each "twitch":
  26. * a) invokes 90 deg/sec rate request
  27. * b) records maximum "forward" roll rate and bounce back rate
  28. * c) when copter reaches 20 degrees or 1 second has passed, it commands level
  29. * d) tries to keep max rotation rate between 80% ~ 100% of requested rate (90deg/sec) by adjusting rate P
  30. * e) increases rate D until the bounce back becomes greater than 10% of requested rate (90deg/sec)
  31. * f) decreases rate D until the bounce back becomes less than 10% of requested rate (90deg/sec)
  32. * g) increases rate P until the max rotate rate becomes greater than the request rate (90deg/sec)
  33. * h) invokes a 20deg angle request on roll or pitch
  34. * i) increases stab P until the maximum angle becomes greater than 110% of the requested angle (20deg)
  35. * j) decreases stab P by 25%
  36. *
  37. */
  38. #define AUTOTUNE_AXIS_BITMASK_ROLL 1
  39. #define AUTOTUNE_AXIS_BITMASK_PITCH 2
  40. #define AUTOTUNE_AXIS_BITMASK_YAW 4
  41. #define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds
  42. #define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 1000U // timeout for tuning mode's testing step
  43. #define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level
  44. #define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch
  45. #define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw
  46. #define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 500 // time we require the aircraft to be level
  47. #define AUTOTUNE_LEVEL_TIMEOUT_MS 2000 // time out for level
  48. #define AUTOTUNE_RD_STEP 0.05f // minimum increment when increasing/decreasing Rate D term
  49. #define AUTOTUNE_RP_STEP 0.05f // minimum increment when increasing/decreasing Rate P term
  50. #define AUTOTUNE_SP_STEP 0.05f // minimum increment when increasing/decreasing Stab P term
  51. #define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1f // I is set 10x smaller than P during testing
  52. #define AUTOTUNE_PI_RATIO_FINAL 1.0f // I is set 1x P after testing
  53. #define AUTOTUNE_YAW_PI_RATIO_FINAL 0.1f // I is set 1x P after testing
  54. #define AUTOTUNE_RD_MAX 0.200f // maximum Rate D value
  55. #define AUTOTUNE_RLPF_MIN 1.0f // minimum Rate Yaw filter value
  56. #define AUTOTUNE_RLPF_MAX 5.0f // maximum Rate Yaw filter value
  57. #define AUTOTUNE_RP_MIN 0.01f // minimum Rate P value
  58. #define AUTOTUNE_RP_MAX 2.0f // maximum Rate P value
  59. #define AUTOTUNE_SP_MAX 20.0f // maximum Stab P value
  60. #define AUTOTUNE_SP_MIN 0.5f // maximum Stab P value
  61. #define AUTOTUNE_RP_ACCEL_MIN 4000.0f // Minimum acceleration for Roll and Pitch
  62. #define AUTOTUNE_Y_ACCEL_MIN 1000.0f // Minimum acceleration for Yaw
  63. #define AUTOTUNE_Y_FILT_FREQ 10.0f // Autotune filter frequency when testing Yaw
  64. #define AUTOTUNE_SUCCESS_COUNT 4 // The number of successful iterations we need to freeze at current gains
  65. #define AUTOTUNE_D_UP_DOWN_MARGIN 0.2f // The margin below the target that we tune D in
  66. #define AUTOTUNE_RD_BACKOFF 1.0f // Rate D gains are reduced to 50% of their maximum value discovered during tuning
  67. #define AUTOTUNE_RP_BACKOFF 1.0f // Rate P gains are reduced to 97.5% of their maximum value discovered during tuning
  68. #define AUTOTUNE_SP_BACKOFF 0.9f // Stab P gains are reduced to 90% of their maximum value discovered during tuning
  69. #define AUTOTUNE_ACCEL_RP_BACKOFF 1.0f // back off from maximum acceleration
  70. #define AUTOTUNE_ACCEL_Y_BACKOFF 1.0f // back off from maximum acceleration
  71. // roll and pitch axes
  72. #define AUTOTUNE_TARGET_ANGLE_RLLPIT_CD 2000 // target angle during TESTING_RATE step that will cause us to move to next step
  73. #define AUTOTUNE_TARGET_RATE_RLLPIT_CDS 18000 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
  74. #define AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD 1000 // minimum target angle during TESTING_RATE step that will cause us to move to next step
  75. #define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
  76. // yaw axis
  77. #define AUTOTUNE_TARGET_ANGLE_YAW_CD 3000 // target angle during TESTING_RATE step that will cause us to move to next step
  78. #define AUTOTUNE_TARGET_RATE_YAW_CDS 9000 // target yaw rate during AUTOTUNE_STEP_TWITCHING step
  79. #define AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD 500 // minimum target angle during TESTING_RATE step that will cause us to move to next step
  80. #define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500 // minimum target yaw rate during AUTOTUNE_STEP_TWITCHING step
  81. // Auto Tune message ids for ground station
  82. #define AUTOTUNE_MESSAGE_STARTED 0
  83. #define AUTOTUNE_MESSAGE_STOPPED 1
  84. #define AUTOTUNE_MESSAGE_SUCCESS 2
  85. #define AUTOTUNE_MESSAGE_FAILED 3
  86. #define AUTOTUNE_MESSAGE_SAVED_GAINS 4
  87. #define AUTOTUNE_ANNOUNCE_INTERVAL_MS 2000
  88. // second table of user settable parameters for quadplanes, this
  89. // allows us to go beyond the 64 parameter limit
  90. const AP_Param::GroupInfo AC_AutoTune::var_info[] = {
  91. // @Param: AXES
  92. // @DisplayName: Autotune axis bitmask
  93. // @Description: 1-byte bitmap of axes to autotune
  94. // @Values: 7:All,1:Roll Only,2:Pitch Only,4:Yaw Only,3:Roll and Pitch,5:Roll and Yaw,6:Pitch and Yaw
  95. // @Bitmask: 0:Roll,1:Pitch,2:Yaw
  96. // @User: Standard
  97. AP_GROUPINFO("AXES", 1, AC_AutoTune, axis_bitmask, 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT
  98. // @Param: AGGR
  99. // @DisplayName: Autotune aggressiveness
  100. // @Description: Autotune aggressiveness. Defines the bounce back used to detect size of the D term.
  101. // @Range: 0.05 0.10
  102. // @User: Standard
  103. AP_GROUPINFO("AGGR", 2, AC_AutoTune, aggressiveness, 0.1f),
  104. // @Param: MIN_D
  105. // @DisplayName: AutoTune minimum D
  106. // @Description: Defines the minimum D gain
  107. // @Range: 0.001 0.006
  108. // @User: Standard
  109. AP_GROUPINFO("MIN_D", 3, AC_AutoTune, min_d, 0.001f),
  110. AP_GROUPEND
  111. };
  112. AC_AutoTune::AC_AutoTune()
  113. {
  114. AP_Param::setup_object_defaults(this, var_info);
  115. }
  116. // autotune_init - should be called when autotune mode is selected
  117. bool AC_AutoTune::init_internals(bool _use_poshold,
  118. AC_AttitudeControl_Multi *_attitude_control,
  119. AC_PosControl *_pos_control,
  120. AP_AHRS_View *_ahrs_view,
  121. AP_InertialNav *_inertial_nav)
  122. {
  123. bool success = true;
  124. use_poshold = _use_poshold;
  125. attitude_control = _attitude_control;
  126. pos_control = _pos_control;
  127. ahrs_view = _ahrs_view;
  128. inertial_nav = _inertial_nav;
  129. motors = AP_Motors::get_singleton();
  130. switch (mode) {
  131. case FAILED:
  132. // autotune has been run but failed so reset state to uninitialized
  133. mode = UNINITIALISED;
  134. // fall through to restart the tuning
  135. FALLTHROUGH;
  136. case UNINITIALISED:
  137. // autotune has never been run
  138. success = start();
  139. if (success) {
  140. // so store current gains as original gains
  141. backup_gains_and_initialise();
  142. // advance mode to tuning
  143. mode = TUNING;
  144. // send message to ground station that we've started tuning
  145. update_gcs(AUTOTUNE_MESSAGE_STARTED);
  146. }
  147. break;
  148. case TUNING:
  149. // we are restarting tuning after the user must have switched ch7/ch8 off so we restart tuning where we left off
  150. success = start();
  151. if (success) {
  152. // reset gains to tuning-start gains (i.e. low I term)
  153. load_gains(GAIN_INTRA_TEST);
  154. Log_Write_Event(EVENT_AUTOTUNE_RESTART);
  155. update_gcs(AUTOTUNE_MESSAGE_STARTED);
  156. }
  157. break;
  158. case SUCCESS:
  159. // we have completed a tune and the pilot wishes to test the new gains in the current flight mode
  160. // so simply apply tuning gains (i.e. do not change flight mode)
  161. load_gains(GAIN_TUNED);
  162. Log_Write_Event(EVENT_AUTOTUNE_PILOT_TESTING);
  163. break;
  164. }
  165. have_position = false;
  166. return success;
  167. }
  168. // stop - should be called when the ch7/ch8 switch is switched OFF
  169. void AC_AutoTune::stop()
  170. {
  171. // set gains to their original values
  172. load_gains(GAIN_ORIGINAL);
  173. // re-enable angle-to-rate request limits
  174. attitude_control->use_sqrt_controller(true);
  175. update_gcs(AUTOTUNE_MESSAGE_STOPPED);
  176. Log_Write_Event(EVENT_AUTOTUNE_OFF);
  177. // Note: we leave the mode as it was so that we know how the autotune ended
  178. // we expect the caller will change the flight mode back to the flight mode indicated by the flight mode switch
  179. }
  180. // start - Initialize autotune flight mode
  181. bool AC_AutoTune::start(void)
  182. {
  183. if (!motors->armed()) {
  184. return false;
  185. }
  186. // initialize vertical speeds and leash lengths
  187. init_z_limits();
  188. // initialise position and desired velocity
  189. if (!pos_control->is_active_z()) {
  190. pos_control->set_alt_target_to_current_alt();
  191. pos_control->set_desired_velocity_z(inertial_nav->get_velocity_z());
  192. }
  193. return true;
  194. }
  195. const char *AC_AutoTune::level_issue_string() const
  196. {
  197. switch (level_problem.issue) {
  198. case LevelIssue::NONE:
  199. return "None";
  200. case LevelIssue::ANGLE_ROLL:
  201. return "Angle(R)";
  202. case LevelIssue::ANGLE_PITCH:
  203. return "Angle(P)";
  204. case LevelIssue::ANGLE_YAW:
  205. return "Angle(Y)";
  206. case LevelIssue::RATE_ROLL:
  207. return "Rate(R)";
  208. case LevelIssue::RATE_PITCH:
  209. return "Rate(P)";
  210. case LevelIssue::RATE_YAW:
  211. return "Rate(Y)";
  212. }
  213. return "Bug";
  214. }
  215. void AC_AutoTune::send_step_string()
  216. {
  217. if (pilot_override) {
  218. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active");
  219. return;
  220. }
  221. switch (step) {
  222. case WAITING_FOR_LEVEL:
  223. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: WFL (%s) (%f > %f)", level_issue_string(), (double)(level_problem.current*0.01f), (double)(level_problem.maximum*0.01f));
  224. return;
  225. case UPDATE_GAINS:
  226. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: UPDATING_GAINS");
  227. return;
  228. case TWITCHING:
  229. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: TWITCHING");
  230. return;
  231. }
  232. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: unknown step");
  233. }
  234. const char *AC_AutoTune::type_string() const
  235. {
  236. switch (tune_type) {
  237. case RD_UP:
  238. return "Rate D Up";
  239. case RD_DOWN:
  240. return "Rate D Down";
  241. case RP_UP:
  242. return "Rate P Up";
  243. case SP_DOWN:
  244. return "Angle P Down";
  245. case SP_UP:
  246. return "Angle P Up";
  247. }
  248. return "Bug";
  249. }
  250. void AC_AutoTune::do_gcs_announcements()
  251. {
  252. const uint32_t now = AP_HAL::millis();
  253. if (now - announce_time < AUTOTUNE_ANNOUNCE_INTERVAL_MS) {
  254. return;
  255. }
  256. float tune_rp = 0.0f;
  257. float tune_rd = 0.0f;
  258. float tune_sp = 0.0f;
  259. float tune_accel = 0.0f;
  260. char axis_char = '?';
  261. switch (axis) {
  262. case ROLL:
  263. tune_rp = tune_roll_rp;
  264. tune_rd = tune_roll_rd;
  265. tune_sp = tune_roll_sp;
  266. tune_accel = tune_roll_accel;
  267. axis_char = 'R';
  268. break;
  269. case PITCH:
  270. tune_rp = tune_pitch_rp;
  271. tune_rd = tune_pitch_rd;
  272. tune_sp = tune_pitch_sp;
  273. tune_accel = tune_pitch_accel;
  274. axis_char = 'P';
  275. break;
  276. case YAW:
  277. tune_rp = tune_yaw_rp;
  278. tune_rd = tune_yaw_rLPF;
  279. tune_sp = tune_yaw_sp;
  280. tune_accel = tune_yaw_accel;
  281. axis_char = 'Y';
  282. break;
  283. }
  284. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: (%c) %s", axis_char, type_string());
  285. send_step_string();
  286. if (!is_zero(lean_angle)) {
  287. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: lean=%f target=%f", (double)lean_angle, (double)target_angle);
  288. }
  289. if (!is_zero(rotation_rate)) {
  290. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: rotation=%f target=%f", (double)(rotation_rate*0.01f), (double)(target_rate*0.01f));
  291. }
  292. switch (tune_type) {
  293. case RD_UP:
  294. case RD_DOWN:
  295. case RP_UP:
  296. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: p=%f d=%f", (double)tune_rp, (double)tune_rd);
  297. break;
  298. case SP_DOWN:
  299. case SP_UP:
  300. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: p=%f accel=%f", (double)tune_sp, (double)tune_accel);
  301. break;
  302. }
  303. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: success %u/%u", counter, AUTOTUNE_SUCCESS_COUNT);
  304. announce_time = now;
  305. }
  306. // run - runs the autotune flight mode
  307. // should be called at 100hz or more
  308. void AC_AutoTune::run()
  309. {
  310. // initialize vertical speeds and acceleration
  311. init_z_limits();
  312. // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
  313. // this should not actually be possible because of the init() checks
  314. if (!motors->armed() || !motors->get_interlock()) {
  315. motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  316. attitude_control->set_throttle_out(0.0f, true, 0.0f);
  317. pos_control->relax_alt_hold_controllers(0.0f);
  318. return;
  319. }
  320. float target_roll_cd, target_pitch_cd, target_yaw_rate_cds;
  321. get_pilot_desired_rp_yrate_cd(target_roll_cd, target_pitch_cd, target_yaw_rate_cds);
  322. // get pilot desired climb rate
  323. const float target_climb_rate_cms = get_pilot_desired_climb_rate_cms();
  324. const bool zero_rp_input = is_zero(target_roll_cd) && is_zero(target_pitch_cd);
  325. const uint32_t now = AP_HAL::millis();
  326. if (!zero_rp_input || !is_zero(target_yaw_rate_cds) || !is_zero(target_climb_rate_cms)) {
  327. if (!pilot_override) {
  328. pilot_override = true;
  329. // set gains to their original values
  330. load_gains(GAIN_ORIGINAL);
  331. attitude_control->use_sqrt_controller(true);
  332. }
  333. // reset pilot override time
  334. override_time = now;
  335. if (!zero_rp_input) {
  336. // only reset position on roll or pitch input
  337. have_position = false;
  338. }
  339. } else if (pilot_override) {
  340. // check if we should resume tuning after pilot's override
  341. if (now - override_time > AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS) {
  342. pilot_override = false; // turn off pilot override
  343. // set gains to their intra-test values (which are very close to the original gains)
  344. // load_gains(GAIN_INTRA_TEST); //I think we should be keeping the originals here to let the I term settle quickly
  345. step = WAITING_FOR_LEVEL; // set tuning step back from beginning
  346. step_start_time_ms = now;
  347. level_start_time_ms = now;
  348. desired_yaw_cd = ahrs_view->yaw_sensor;
  349. }
  350. }
  351. if (pilot_override) {
  352. if (now - last_pilot_override_warning > 1000) {
  353. gcs().send_text(MAV_SEVERITY_INFO, "AUTOTUNE: pilot overrides active");
  354. last_pilot_override_warning = now;
  355. }
  356. }
  357. if (zero_rp_input) {
  358. // pilot input on throttle and yaw will still use position hold if enabled
  359. get_poshold_attitude(target_roll_cd, target_pitch_cd, desired_yaw_cd);
  360. }
  361. // set motors to full range
  362. motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  363. // if pilot override call attitude controller
  364. if (pilot_override || mode != TUNING) {
  365. attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll_cd, target_pitch_cd, target_yaw_rate_cds);
  366. } else {
  367. // somehow get attitude requests from autotuning
  368. control_attitude();
  369. // tell the user what's going on
  370. do_gcs_announcements();
  371. }
  372. // call position controller
  373. pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate_cms, AP::scheduler().get_last_loop_time_s(), false);
  374. pos_control->update_z_controller();
  375. }
  376. bool AC_AutoTune::check_level(const LevelIssue issue, const float current, const float maximum)
  377. {
  378. if (current > maximum) {
  379. level_problem.current = current;
  380. level_problem.maximum = maximum;
  381. level_problem.issue = issue;
  382. return false;
  383. }
  384. return true;
  385. }
  386. bool AC_AutoTune::currently_level()
  387. {
  388. float threshold_mul = 1.0;
  389. if (AP_HAL::millis() - level_start_time_ms > AUTOTUNE_LEVEL_TIMEOUT_MS) {
  390. // after a long wait we use looser threshold, to allow tuning
  391. // with poor initial gains
  392. threshold_mul *= 2;
  393. }
  394. if (!check_level(LevelIssue::ANGLE_ROLL,
  395. abs(ahrs_view->roll_sensor - roll_cd),
  396. threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
  397. return false;
  398. }
  399. if (!check_level(LevelIssue::ANGLE_PITCH,
  400. abs(ahrs_view->pitch_sensor - pitch_cd),
  401. threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
  402. return false;
  403. }
  404. if (!check_level(LevelIssue::ANGLE_YAW,
  405. fabsf(wrap_180_cd(ahrs_view->yaw_sensor - desired_yaw_cd)),
  406. threshold_mul*AUTOTUNE_LEVEL_ANGLE_CD)) {
  407. return false;
  408. }
  409. if (!check_level(LevelIssue::RATE_ROLL,
  410. (ToDeg(ahrs_view->get_gyro().x) * 100.0f),
  411. threshold_mul*AUTOTUNE_LEVEL_RATE_RP_CD)) {
  412. return false;
  413. }
  414. if (!check_level(LevelIssue::RATE_PITCH,
  415. (ToDeg(ahrs_view->get_gyro().y) * 100.0f),
  416. threshold_mul*AUTOTUNE_LEVEL_RATE_RP_CD)) {
  417. return false;
  418. }
  419. if (!check_level(LevelIssue::RATE_YAW,
  420. (ToDeg(ahrs_view->get_gyro().z) * 100.0f),
  421. threshold_mul*AUTOTUNE_LEVEL_RATE_Y_CD)) {
  422. return false;
  423. }
  424. return true;
  425. }
  426. // attitude_controller - sets attitude control targets during tuning
  427. void AC_AutoTune::control_attitude()
  428. {
  429. rotation_rate = 0.0f; // rotation rate in radians/second
  430. lean_angle = 0.0f;
  431. const float direction_sign = positive_direction ? 1.0f : -1.0f;
  432. const uint32_t now = AP_HAL::millis();
  433. // check tuning step
  434. switch (step) {
  435. case WAITING_FOR_LEVEL: {
  436. // Note: we should be using intra-test gains (which are very close to the original gains but have lower I)
  437. // re-enable rate limits
  438. attitude_control->use_sqrt_controller(true);
  439. get_poshold_attitude(roll_cd, pitch_cd, desired_yaw_cd);
  440. // hold level attitude
  441. attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw_cd, true);
  442. // hold the copter level for 0.5 seconds before we begin a twitch
  443. // reset counter if we are no longer level
  444. if (!currently_level()) {
  445. step_start_time_ms = now;
  446. }
  447. // if we have been level for a sufficient amount of time (0.5 seconds) move onto tuning step
  448. if (now - step_start_time_ms > AUTOTUNE_REQUIRED_LEVEL_TIME_MS) {
  449. gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Twitch");
  450. // initiate variables for next step
  451. step = TWITCHING;
  452. step_start_time_ms = now;
  453. step_time_limit_ms = AUTOTUNE_TESTING_STEP_TIMEOUT_MS;
  454. twitch_first_iter = true;
  455. test_rate_max = 0.0f;
  456. test_rate_min = 0.0f;
  457. test_angle_max = 0.0f;
  458. test_angle_min = 0.0f;
  459. rotation_rate_filt.reset(0.0f);
  460. rate_max = 0.0f;
  461. // set gains to their to-be-tested values
  462. load_gains(GAIN_TWITCH);
  463. } else {
  464. // when waiting for level we use the intra-test gains
  465. load_gains(GAIN_INTRA_TEST);
  466. }
  467. float target_max_rate;
  468. switch (axis) {
  469. case ROLL:
  470. target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler*AUTOTUNE_TARGET_RATE_RLLPIT_CDS);
  471. target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_roll())*100.0f, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate);
  472. target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_roll())*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD, AUTOTUNE_TARGET_ANGLE_RLLPIT_CD);
  473. abort_angle = AUTOTUNE_TARGET_ANGLE_RLLPIT_CD;
  474. start_rate = ToDeg(ahrs_view->get_gyro().x) * 100.0f;
  475. start_angle = ahrs_view->roll_sensor;
  476. rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_roll_pid().filt_D_hz()*2.0f);
  477. break;
  478. case PITCH:
  479. target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler*AUTOTUNE_TARGET_RATE_RLLPIT_CDS);
  480. target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_pitch())*100.0f, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate);
  481. target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_pitch())*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD, AUTOTUNE_TARGET_ANGLE_RLLPIT_CD);
  482. abort_angle = AUTOTUNE_TARGET_ANGLE_RLLPIT_CD;
  483. start_rate = ToDeg(ahrs_view->get_gyro().y) * 100.0f;
  484. start_angle = ahrs_view->pitch_sensor;
  485. rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_pitch_pid().filt_D_hz()*2.0f);
  486. break;
  487. case YAW:
  488. target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler*AUTOTUNE_TARGET_RATE_YAW_CDS);
  489. target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_yaw()*0.75f)*100.0f, AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, target_max_rate);
  490. target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_yaw()*0.75f)*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD, AUTOTUNE_TARGET_ANGLE_YAW_CD);
  491. abort_angle = AUTOTUNE_TARGET_ANGLE_YAW_CD;
  492. start_rate = ToDeg(ahrs_view->get_gyro().z) * 100.0f;
  493. start_angle = ahrs_view->yaw_sensor;
  494. rotation_rate_filt.set_cutoff_frequency(AUTOTUNE_Y_FILT_FREQ);
  495. break;
  496. }
  497. if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
  498. rotation_rate_filt.reset(start_rate);
  499. } else {
  500. rotation_rate_filt.reset(0);
  501. }
  502. break;
  503. }
  504. case TWITCHING: {
  505. // Run the twitching step
  506. load_gains(GAIN_TWITCH);
  507. // disable rate limits
  508. attitude_control->use_sqrt_controller(false);
  509. // hold current attitude
  510. attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f);
  511. if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
  512. // step angle targets on first iteration
  513. if (twitch_first_iter) {
  514. twitch_first_iter = false;
  515. // Testing increasing stabilize P gain so will set lean angle target
  516. switch (axis) {
  517. case ROLL:
  518. // request roll to 20deg
  519. attitude_control->input_angle_step_bf_roll_pitch_yaw(direction_sign * target_angle, 0.0f, 0.0f);
  520. break;
  521. case PITCH:
  522. // request pitch to 20deg
  523. attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0f, direction_sign * target_angle, 0.0f);
  524. break;
  525. case YAW:
  526. // request pitch to 20deg
  527. attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0f, 0.0f, direction_sign * target_angle);
  528. break;
  529. }
  530. }
  531. } else {
  532. // Testing rate P and D gains so will set body-frame rate targets.
  533. // Rate controller will use existing body-frame rates and convert to motor outputs
  534. // for all axes except the one we override here.
  535. switch (axis) {
  536. case ROLL:
  537. // override body-frame roll rate
  538. attitude_control->rate_bf_roll_target(direction_sign * target_rate + start_rate);
  539. break;
  540. case PITCH:
  541. // override body-frame pitch rate
  542. attitude_control->rate_bf_pitch_target(direction_sign * target_rate + start_rate);
  543. break;
  544. case YAW:
  545. // override body-frame yaw rate
  546. attitude_control->rate_bf_yaw_target(direction_sign * target_rate + start_rate);
  547. break;
  548. }
  549. }
  550. // capture this iterations rotation rate and lean angle
  551. float gyro_reading = 0;
  552. switch (axis) {
  553. case ROLL:
  554. gyro_reading = ahrs_view->get_gyro().x;
  555. lean_angle = direction_sign * (ahrs_view->roll_sensor - (int32_t)start_angle);
  556. break;
  557. case PITCH:
  558. gyro_reading = ahrs_view->get_gyro().y;
  559. lean_angle = direction_sign * (ahrs_view->pitch_sensor - (int32_t)start_angle);
  560. break;
  561. case YAW:
  562. gyro_reading = ahrs_view->get_gyro().z;
  563. lean_angle = direction_sign * wrap_180_cd(ahrs_view->yaw_sensor-(int32_t)start_angle);
  564. break;
  565. }
  566. // Add filter to measurements
  567. float filter_value;
  568. switch (tune_type) {
  569. case SP_DOWN:
  570. case SP_UP:
  571. filter_value = direction_sign * (ToDeg(gyro_reading) * 100.0f);
  572. break;
  573. default:
  574. filter_value = direction_sign * (ToDeg(gyro_reading) * 100.0f - start_rate);
  575. break;
  576. }
  577. rotation_rate = rotation_rate_filt.apply(filter_value,
  578. AP::scheduler().get_loop_period_s());
  579. switch (tune_type) {
  580. case RD_UP:
  581. case RD_DOWN:
  582. twitching_test_rate(rotation_rate, target_rate, test_rate_min, test_rate_max);
  583. twitching_measure_acceleration(test_accel_max, rotation_rate, rate_max);
  584. twitching_abort_rate(lean_angle, rotation_rate, abort_angle, test_rate_min);
  585. if (lean_angle >= target_angle) {
  586. step = UPDATE_GAINS;
  587. }
  588. break;
  589. case RP_UP:
  590. twitching_test_rate(rotation_rate, target_rate*(1+0.5f*aggressiveness), test_rate_min, test_rate_max);
  591. twitching_measure_acceleration(test_accel_max, rotation_rate, rate_max);
  592. twitching_abort_rate(lean_angle, rotation_rate, abort_angle, test_rate_min);
  593. break;
  594. case SP_DOWN:
  595. case SP_UP:
  596. twitching_test_angle(lean_angle, rotation_rate, target_angle*(1+0.5f*aggressiveness), test_angle_min, test_angle_max, test_rate_min, test_rate_max);
  597. twitching_measure_acceleration(test_accel_max, rotation_rate - direction_sign * start_rate, rate_max);
  598. break;
  599. }
  600. // log this iterations lean angle and rotation rate
  601. Log_Write_AutoTuneDetails(lean_angle, rotation_rate);
  602. AP::logger().Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
  603. log_pids();
  604. break;
  605. }
  606. case UPDATE_GAINS:
  607. // re-enable rate limits
  608. attitude_control->use_sqrt_controller(true);
  609. // log the latest gains
  610. if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
  611. switch (axis) {
  612. case ROLL:
  613. Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max);
  614. break;
  615. case PITCH:
  616. Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max);
  617. break;
  618. case YAW:
  619. Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, test_accel_max);
  620. break;
  621. }
  622. } else {
  623. switch (axis) {
  624. case ROLL:
  625. Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max);
  626. break;
  627. case PITCH:
  628. Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max);
  629. break;
  630. case YAW:
  631. Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, test_accel_max);
  632. break;
  633. }
  634. }
  635. // Check results after mini-step to increase rate D gain
  636. switch (tune_type) {
  637. case RD_UP:
  638. switch (axis) {
  639. case ROLL:
  640. updating_rate_d_up(tune_roll_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
  641. break;
  642. case PITCH:
  643. updating_rate_d_up(tune_pitch_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
  644. break;
  645. case YAW:
  646. updating_rate_d_up(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RLPF_MAX, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
  647. break;
  648. }
  649. break;
  650. // Check results after mini-step to decrease rate D gain
  651. case RD_DOWN:
  652. switch (axis) {
  653. case ROLL:
  654. updating_rate_d_down(tune_roll_rd, min_d, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
  655. break;
  656. case PITCH:
  657. updating_rate_d_down(tune_pitch_rd, min_d, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
  658. break;
  659. case YAW:
  660. updating_rate_d_down(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
  661. break;
  662. }
  663. break;
  664. // Check results after mini-step to increase rate P gain
  665. case RP_UP:
  666. switch (axis) {
  667. case ROLL:
  668. updating_rate_p_up_d_down(tune_roll_rd, min_d, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
  669. break;
  670. case PITCH:
  671. updating_rate_p_up_d_down(tune_pitch_rd, min_d, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
  672. break;
  673. case YAW:
  674. updating_rate_p_up_d_down(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
  675. break;
  676. }
  677. break;
  678. // Check results after mini-step to increase stabilize P gain
  679. case SP_DOWN:
  680. switch (axis) {
  681. case ROLL:
  682. updating_angle_p_down(tune_roll_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
  683. break;
  684. case PITCH:
  685. updating_angle_p_down(tune_pitch_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
  686. break;
  687. case YAW:
  688. updating_angle_p_down(tune_yaw_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
  689. break;
  690. }
  691. break;
  692. // Check results after mini-step to increase stabilize P gain
  693. case SP_UP:
  694. switch (axis) {
  695. case ROLL:
  696. updating_angle_p_up(tune_roll_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
  697. break;
  698. case PITCH:
  699. updating_angle_p_up(tune_pitch_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
  700. break;
  701. case YAW:
  702. updating_angle_p_up(tune_yaw_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
  703. break;
  704. }
  705. break;
  706. }
  707. // we've complete this step, finalize pids and move to next step
  708. if (counter >= AUTOTUNE_SUCCESS_COUNT) {
  709. // reset counter
  710. counter = 0;
  711. // reset scaling factor
  712. step_scaler = 1;
  713. // move to the next tuning type
  714. switch (tune_type) {
  715. case RD_UP:
  716. tune_type = TuneType(tune_type + 1);
  717. break;
  718. case RD_DOWN:
  719. tune_type = TuneType(tune_type + 1);
  720. switch (axis) {
  721. case ROLL:
  722. tune_roll_rd = MAX(min_d, tune_roll_rd * AUTOTUNE_RD_BACKOFF);
  723. tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RD_BACKOFF);
  724. break;
  725. case PITCH:
  726. tune_pitch_rd = MAX(min_d, tune_pitch_rd * AUTOTUNE_RD_BACKOFF);
  727. tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RD_BACKOFF);
  728. break;
  729. case YAW:
  730. tune_yaw_rLPF = MAX(AUTOTUNE_RLPF_MIN, tune_yaw_rLPF * AUTOTUNE_RD_BACKOFF);
  731. tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RD_BACKOFF);
  732. break;
  733. }
  734. break;
  735. case RP_UP:
  736. tune_type = TuneType(tune_type + 1);
  737. switch (axis) {
  738. case ROLL:
  739. tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RP_BACKOFF);
  740. break;
  741. case PITCH:
  742. tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RP_BACKOFF);
  743. break;
  744. case YAW:
  745. tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RP_BACKOFF);
  746. break;
  747. }
  748. break;
  749. case SP_DOWN:
  750. tune_type = TuneType(tune_type + 1);
  751. break;
  752. case SP_UP:
  753. // we've reached the end of a D-up-down PI-up-down tune type cycle
  754. tune_type = RD_UP;
  755. // advance to the next axis
  756. bool complete = false;
  757. switch (axis) {
  758. case ROLL:
  759. axes_completed |= AUTOTUNE_AXIS_BITMASK_ROLL;
  760. tune_roll_sp = MAX(AUTOTUNE_SP_MIN, tune_roll_sp * AUTOTUNE_SP_BACKOFF);
  761. tune_roll_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF);
  762. if (pitch_enabled()) {
  763. axis = PITCH;
  764. } else if (yaw_enabled()) {
  765. axis = YAW;
  766. } else {
  767. complete = true;
  768. }
  769. break;
  770. case PITCH:
  771. axes_completed |= AUTOTUNE_AXIS_BITMASK_PITCH;
  772. tune_pitch_sp = MAX(AUTOTUNE_SP_MIN, tune_pitch_sp * AUTOTUNE_SP_BACKOFF);
  773. tune_pitch_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF);
  774. if (yaw_enabled()) {
  775. axis = YAW;
  776. } else {
  777. complete = true;
  778. }
  779. break;
  780. case YAW:
  781. axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW;
  782. tune_yaw_sp = MAX(AUTOTUNE_SP_MIN, tune_yaw_sp * AUTOTUNE_SP_BACKOFF);
  783. tune_yaw_accel = MAX(AUTOTUNE_Y_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_Y_BACKOFF);
  784. complete = true;
  785. break;
  786. }
  787. // if we've just completed all axes we have successfully completed the autotune
  788. // change to TESTING mode to allow user to fly with new gains
  789. if (complete) {
  790. mode = SUCCESS;
  791. update_gcs(AUTOTUNE_MESSAGE_SUCCESS);
  792. Log_Write_Event(EVENT_AUTOTUNE_SUCCESS);
  793. AP_Notify::events.autotune_complete = true;
  794. } else {
  795. AP_Notify::events.autotune_next_axis = true;
  796. }
  797. break;
  798. }
  799. }
  800. // reverse direction
  801. positive_direction = !positive_direction;
  802. if (axis == YAW) {
  803. attitude_control->input_euler_angle_roll_pitch_yaw(0.0f, 0.0f, ahrs_view->yaw_sensor, false);
  804. }
  805. // set gains to their intra-test values (which are very close to the original gains)
  806. load_gains(GAIN_INTRA_TEST);
  807. // reset testing step
  808. step = WAITING_FOR_LEVEL;
  809. step_start_time_ms = now;
  810. level_start_time_ms = step_start_time_ms;
  811. step_time_limit_ms = AUTOTUNE_REQUIRED_LEVEL_TIME_MS;
  812. break;
  813. }
  814. }
  815. // backup_gains_and_initialise - store current gains as originals
  816. // called before tuning starts to backup original gains
  817. void AC_AutoTune::backup_gains_and_initialise()
  818. {
  819. // initialise state because this is our first time
  820. if (roll_enabled()) {
  821. axis = ROLL;
  822. } else if (pitch_enabled()) {
  823. axis = PITCH;
  824. } else if (yaw_enabled()) {
  825. axis = YAW;
  826. }
  827. // no axes are complete
  828. axes_completed = 0;
  829. current_gain_type = GAIN_ORIGINAL;
  830. positive_direction = false;
  831. step = WAITING_FOR_LEVEL;
  832. step_start_time_ms = AP_HAL::millis();
  833. level_start_time_ms = step_start_time_ms;
  834. tune_type = RD_UP;
  835. step_scaler = 1;
  836. desired_yaw_cd = ahrs_view->yaw_sensor;
  837. aggressiveness = constrain_float(aggressiveness, 0.05f, 0.2f);
  838. orig_bf_feedforward = attitude_control->get_bf_feedforward();
  839. // backup original pids and initialise tuned pid values
  840. orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
  841. orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
  842. orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
  843. orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
  844. orig_roll_sp = attitude_control->get_angle_roll_p().kP();
  845. orig_roll_accel = attitude_control->get_accel_roll_max();
  846. tune_roll_rp = attitude_control->get_rate_roll_pid().kP();
  847. tune_roll_rd = attitude_control->get_rate_roll_pid().kD();
  848. tune_roll_sp = attitude_control->get_angle_roll_p().kP();
  849. tune_roll_accel = attitude_control->get_accel_roll_max();
  850. orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
  851. orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
  852. orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
  853. orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
  854. orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
  855. orig_pitch_accel = attitude_control->get_accel_pitch_max();
  856. tune_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
  857. tune_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
  858. tune_pitch_sp = attitude_control->get_angle_pitch_p().kP();
  859. tune_pitch_accel = attitude_control->get_accel_pitch_max();
  860. orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
  861. orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
  862. orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
  863. orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
  864. orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
  865. orig_yaw_accel = attitude_control->get_accel_yaw_max();
  866. orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
  867. tune_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
  868. tune_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
  869. tune_yaw_sp = attitude_control->get_angle_yaw_p().kP();
  870. tune_yaw_accel = attitude_control->get_accel_yaw_max();
  871. Log_Write_Event(EVENT_AUTOTUNE_INITIALISED);
  872. }
  873. // load_orig_gains - set gains to their original values
  874. // called by stop and failed functions
  875. void AC_AutoTune::load_orig_gains()
  876. {
  877. attitude_control->bf_feedforward(orig_bf_feedforward);
  878. if (roll_enabled()) {
  879. if (!is_zero(orig_roll_rp)) {
  880. attitude_control->get_rate_roll_pid().kP(orig_roll_rp);
  881. attitude_control->get_rate_roll_pid().kI(orig_roll_ri);
  882. attitude_control->get_rate_roll_pid().kD(orig_roll_rd);
  883. attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
  884. attitude_control->get_angle_roll_p().kP(orig_roll_sp);
  885. attitude_control->set_accel_roll_max(orig_roll_accel);
  886. }
  887. }
  888. if (pitch_enabled()) {
  889. if (!is_zero(orig_pitch_rp)) {
  890. attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp);
  891. attitude_control->get_rate_pitch_pid().kI(orig_pitch_ri);
  892. attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd);
  893. attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
  894. attitude_control->get_angle_pitch_p().kP(orig_pitch_sp);
  895. attitude_control->set_accel_pitch_max(orig_pitch_accel);
  896. }
  897. }
  898. if (yaw_enabled()) {
  899. if (!is_zero(orig_yaw_rp)) {
  900. attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp);
  901. attitude_control->get_rate_yaw_pid().kI(orig_yaw_ri);
  902. attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd);
  903. attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
  904. attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF);
  905. attitude_control->get_angle_yaw_p().kP(orig_yaw_sp);
  906. attitude_control->set_accel_yaw_max(orig_yaw_accel);
  907. }
  908. }
  909. }
  910. // load_tuned_gains - load tuned gains
  911. void AC_AutoTune::load_tuned_gains()
  912. {
  913. if (!attitude_control->get_bf_feedforward()) {
  914. attitude_control->bf_feedforward(true);
  915. attitude_control->set_accel_roll_max(0.0f);
  916. attitude_control->set_accel_pitch_max(0.0f);
  917. }
  918. if (roll_enabled()) {
  919. if (!is_zero(tune_roll_rp)) {
  920. attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
  921. attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
  922. attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
  923. attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
  924. attitude_control->get_angle_roll_p().kP(tune_roll_sp);
  925. attitude_control->set_accel_roll_max(tune_roll_accel);
  926. }
  927. }
  928. if (pitch_enabled()) {
  929. if (!is_zero(tune_pitch_rp)) {
  930. attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
  931. attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
  932. attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
  933. attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
  934. attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
  935. attitude_control->set_accel_pitch_max(tune_pitch_accel);
  936. }
  937. }
  938. if (yaw_enabled()) {
  939. if (!is_zero(tune_yaw_rp)) {
  940. attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
  941. attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
  942. attitude_control->get_rate_yaw_pid().kD(0.0f);
  943. attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
  944. attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
  945. attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
  946. attitude_control->set_accel_yaw_max(tune_yaw_accel);
  947. }
  948. }
  949. }
  950. // load_intra_test_gains - gains used between tests
  951. // called during testing mode's update-gains step to set gains ahead of return-to-level step
  952. void AC_AutoTune::load_intra_test_gains()
  953. {
  954. // we are restarting tuning so reset gains to tuning-start gains (i.e. low I term)
  955. // sanity check the gains
  956. attitude_control->bf_feedforward(true);
  957. if (roll_enabled()) {
  958. attitude_control->get_rate_roll_pid().kP(orig_roll_rp);
  959. attitude_control->get_rate_roll_pid().kI(orig_roll_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
  960. attitude_control->get_rate_roll_pid().kD(orig_roll_rd);
  961. attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
  962. attitude_control->get_angle_roll_p().kP(orig_roll_sp);
  963. }
  964. if (pitch_enabled()) {
  965. attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp);
  966. attitude_control->get_rate_pitch_pid().kI(orig_pitch_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
  967. attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd);
  968. attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
  969. attitude_control->get_angle_pitch_p().kP(orig_pitch_sp);
  970. }
  971. if (yaw_enabled()) {
  972. attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp);
  973. attitude_control->get_rate_yaw_pid().kI(orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
  974. attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd);
  975. attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
  976. attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF);
  977. attitude_control->get_angle_yaw_p().kP(orig_yaw_sp);
  978. }
  979. }
  980. // load_twitch_gains - load the to-be-tested gains for a single axis
  981. // called by control_attitude() just before it beings testing a gain (i.e. just before it twitches)
  982. void AC_AutoTune::load_twitch_gains()
  983. {
  984. switch (axis) {
  985. case ROLL:
  986. attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
  987. attitude_control->get_rate_roll_pid().kI(tune_roll_rp*0.01f);
  988. attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
  989. attitude_control->get_rate_roll_pid().ff(0.0f);
  990. attitude_control->get_angle_roll_p().kP(tune_roll_sp);
  991. break;
  992. case PITCH:
  993. attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
  994. attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*0.01f);
  995. attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
  996. attitude_control->get_rate_pitch_pid().ff(0.0f);
  997. attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
  998. break;
  999. case YAW:
  1000. attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
  1001. attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*0.01f);
  1002. attitude_control->get_rate_yaw_pid().kD(0.0f);
  1003. attitude_control->get_rate_yaw_pid().ff(0.0f);
  1004. attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
  1005. attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
  1006. break;
  1007. }
  1008. }
  1009. /*
  1010. load a specified set of gains
  1011. */
  1012. void AC_AutoTune::load_gains(enum GainType gain_type)
  1013. {
  1014. if (current_gain_type == gain_type) {
  1015. return;
  1016. }
  1017. switch (gain_type) {
  1018. case GAIN_ORIGINAL:
  1019. load_orig_gains();
  1020. break;
  1021. case GAIN_INTRA_TEST:
  1022. load_intra_test_gains();
  1023. break;
  1024. case GAIN_TWITCH:
  1025. load_twitch_gains();
  1026. break;
  1027. case GAIN_TUNED:
  1028. load_tuned_gains();
  1029. break;
  1030. }
  1031. }
  1032. // save_tuning_gains - save the final tuned gains for each axis
  1033. // save discovered gains to eeprom if autotuner is enabled (i.e. switch is in the high position)
  1034. void AC_AutoTune::save_tuning_gains()
  1035. {
  1036. // see if we successfully completed tuning of at least one axis
  1037. if (axes_completed == 0) {
  1038. return;
  1039. }
  1040. if (!attitude_control->get_bf_feedforward()) {
  1041. attitude_control->bf_feedforward_save(true);
  1042. attitude_control->save_accel_roll_max(0.0f);
  1043. attitude_control->save_accel_pitch_max(0.0f);
  1044. }
  1045. // sanity check the rate P values
  1046. if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled() && !is_zero(tune_roll_rp)) {
  1047. // rate roll gains
  1048. attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
  1049. attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
  1050. attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
  1051. attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
  1052. attitude_control->get_rate_roll_pid().save_gains();
  1053. // stabilize roll
  1054. attitude_control->get_angle_roll_p().kP(tune_roll_sp);
  1055. attitude_control->get_angle_roll_p().save_gains();
  1056. // acceleration roll
  1057. attitude_control->save_accel_roll_max(tune_roll_accel);
  1058. // resave pids to originals in case the autotune is run again
  1059. orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
  1060. orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
  1061. orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
  1062. orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
  1063. orig_roll_sp = attitude_control->get_angle_roll_p().kP();
  1064. orig_roll_accel = attitude_control->get_accel_roll_max();
  1065. }
  1066. if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled() && !is_zero(tune_pitch_rp)) {
  1067. // rate pitch gains
  1068. attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
  1069. attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
  1070. attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
  1071. attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
  1072. attitude_control->get_rate_pitch_pid().save_gains();
  1073. // stabilize pitch
  1074. attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
  1075. attitude_control->get_angle_pitch_p().save_gains();
  1076. // acceleration pitch
  1077. attitude_control->save_accel_pitch_max(tune_pitch_accel);
  1078. // resave pids to originals in case the autotune is run again
  1079. orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
  1080. orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
  1081. orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
  1082. orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
  1083. orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
  1084. orig_pitch_accel = attitude_control->get_accel_pitch_max();
  1085. }
  1086. if ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled() && !is_zero(tune_yaw_rp)) {
  1087. // rate yaw gains
  1088. attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
  1089. attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
  1090. attitude_control->get_rate_yaw_pid().kD(0.0f);
  1091. attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
  1092. attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
  1093. attitude_control->get_rate_yaw_pid().save_gains();
  1094. // stabilize yaw
  1095. attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
  1096. attitude_control->get_angle_yaw_p().save_gains();
  1097. // acceleration yaw
  1098. attitude_control->save_accel_yaw_max(tune_yaw_accel);
  1099. // resave pids to originals in case the autotune is run again
  1100. orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
  1101. orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
  1102. orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
  1103. orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
  1104. orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
  1105. orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
  1106. orig_yaw_accel = attitude_control->get_accel_pitch_max();
  1107. }
  1108. // update GCS and log save gains event
  1109. update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);
  1110. Log_Write_Event(EVENT_AUTOTUNE_SAVEDGAINS);
  1111. reset();
  1112. }
  1113. // update_gcs - send message to ground station
  1114. void AC_AutoTune::update_gcs(uint8_t message_id)
  1115. {
  1116. switch (message_id) {
  1117. case AUTOTUNE_MESSAGE_STARTED:
  1118. gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Started");
  1119. break;
  1120. case AUTOTUNE_MESSAGE_STOPPED:
  1121. gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Stopped");
  1122. break;
  1123. case AUTOTUNE_MESSAGE_SUCCESS:
  1124. gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Success");
  1125. break;
  1126. case AUTOTUNE_MESSAGE_FAILED:
  1127. gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Failed");
  1128. break;
  1129. case AUTOTUNE_MESSAGE_SAVED_GAINS:
  1130. gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Saved gains for %s%s%s",
  1131. (axes_completed&AUTOTUNE_AXIS_BITMASK_ROLL)?"Roll ":"",
  1132. (axes_completed&AUTOTUNE_AXIS_BITMASK_PITCH)?"Pitch ":"",
  1133. (axes_completed&AUTOTUNE_AXIS_BITMASK_YAW)?"Yaw":"");
  1134. break;
  1135. }
  1136. }
  1137. // axis helper functions
  1138. inline bool AC_AutoTune::roll_enabled()
  1139. {
  1140. return axis_bitmask & AUTOTUNE_AXIS_BITMASK_ROLL;
  1141. }
  1142. inline bool AC_AutoTune::pitch_enabled()
  1143. {
  1144. return axis_bitmask & AUTOTUNE_AXIS_BITMASK_PITCH;
  1145. }
  1146. inline bool AC_AutoTune::yaw_enabled()
  1147. {
  1148. return axis_bitmask & AUTOTUNE_AXIS_BITMASK_YAW;
  1149. }
  1150. // twitching_test_rate - twitching tests
  1151. // update min and max and test for end conditions
  1152. void AC_AutoTune::twitching_test_rate(float rate, float rate_target_max, float &meas_rate_min, float &meas_rate_max)
  1153. {
  1154. const uint32_t now = AP_HAL::millis();
  1155. // capture maximum rate
  1156. if (rate > meas_rate_max) {
  1157. // the measurement is continuing to increase without stopping
  1158. meas_rate_max = rate;
  1159. meas_rate_min = rate;
  1160. }
  1161. // capture minimum measurement after the measurement has peaked (aka "bounce back")
  1162. if ((rate < meas_rate_min) && (meas_rate_max > rate_target_max * 0.5f)) {
  1163. // the measurement is bouncing back
  1164. meas_rate_min = rate;
  1165. }
  1166. // calculate early stopping time based on the time it takes to get to 75%
  1167. if (meas_rate_max < rate_target_max * 0.75f) {
  1168. // the measurement not reached the 75% threshold yet
  1169. step_time_limit_ms = (now - step_start_time_ms) * 3;
  1170. step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);
  1171. }
  1172. if (meas_rate_max > rate_target_max) {
  1173. // the measured rate has passed the maximum target rate
  1174. step = UPDATE_GAINS;
  1175. }
  1176. if (meas_rate_max-meas_rate_min > meas_rate_max*aggressiveness) {
  1177. // the measurement has passed 50% of the maximum rate and bounce back is larger than the threshold
  1178. step = UPDATE_GAINS;
  1179. }
  1180. if (now - step_start_time_ms >= step_time_limit_ms) {
  1181. // we have passed the maximum stop time
  1182. step = UPDATE_GAINS;
  1183. }
  1184. }
  1185. // twitching_test_rate - twitching tests
  1186. // update min and max and test for end conditions
  1187. void AC_AutoTune::twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min)
  1188. {
  1189. if (angle >= angle_max) {
  1190. if (is_equal(rate, meas_rate_min) && step_scaler > 0.5) {
  1191. // we have reached the angle limit before completing the measurement of maximum and minimum
  1192. // reduce the maximum target rate
  1193. step_scaler *= 0.9f;
  1194. // ignore result and start test again
  1195. step = WAITING_FOR_LEVEL;
  1196. } else {
  1197. step = UPDATE_GAINS;
  1198. }
  1199. }
  1200. }
  1201. // twitching_test_angle - twitching tests
  1202. // update min and max and test for end conditions
  1203. void AC_AutoTune::twitching_test_angle(float angle, float rate, float angle_target_max, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max)
  1204. {
  1205. const uint32_t now = AP_HAL::millis();
  1206. // capture maximum angle
  1207. if (angle > meas_angle_max) {
  1208. // the angle still increasing
  1209. meas_angle_max = angle;
  1210. meas_angle_min = angle;
  1211. }
  1212. // capture minimum angle after we have reached a reasonable maximum angle
  1213. if ((angle < meas_angle_min) && (meas_angle_max > angle_target_max * 0.5f)) {
  1214. // the measurement is bouncing back
  1215. meas_angle_min = angle;
  1216. }
  1217. // capture maximum rate
  1218. if (rate > meas_rate_max) {
  1219. // the measurement is still increasing
  1220. meas_rate_max = rate;
  1221. meas_rate_min = rate;
  1222. }
  1223. // capture minimum rate after we have reached maximum rate
  1224. if (rate < meas_rate_min) {
  1225. // the measurement is still decreasing
  1226. meas_rate_min = rate;
  1227. }
  1228. // calculate early stopping time based on the time it takes to get to 75%
  1229. if (meas_angle_max < angle_target_max * 0.75f) {
  1230. // the measurement not reached the 75% threshold yet
  1231. step_time_limit_ms = (now - step_start_time_ms) * 3;
  1232. step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);
  1233. }
  1234. if (meas_angle_max > angle_target_max) {
  1235. // the measurement has passed the maximum angle
  1236. step = UPDATE_GAINS;
  1237. }
  1238. if (meas_angle_max-meas_angle_min > meas_angle_max*aggressiveness) {
  1239. // the measurement has passed 50% of the maximum angle and bounce back is larger than the threshold
  1240. step = UPDATE_GAINS;
  1241. }
  1242. if (now - step_start_time_ms >= step_time_limit_ms) {
  1243. // we have passed the maximum stop time
  1244. step = UPDATE_GAINS;
  1245. }
  1246. }
  1247. // twitching_measure_acceleration - measure rate of change of measurement
  1248. void AC_AutoTune::twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max)
  1249. {
  1250. if (rate_measurement_max < rate_measurement) {
  1251. rate_measurement_max = rate_measurement;
  1252. rate_of_change = (1000.0f*rate_measurement_max)/(AP_HAL::millis() - step_start_time_ms);
  1253. }
  1254. }
  1255. // updating_rate_d_up - increase D and adjust P to optimize the D term for a little bounce back
  1256. // optimize D term while keeping the maximum just below the target by adjusting P
  1257. void AC_AutoTune::updating_rate_d_up(float &tune_d, float tune_d_min, float tune_d_max, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
  1258. {
  1259. if (meas_rate_max > rate_target) {
  1260. // if maximum measurement was higher than target
  1261. // reduce P gain (which should reduce maximum)
  1262. tune_p -= tune_p*tune_p_step_ratio;
  1263. if (tune_p < tune_p_min) {
  1264. // P gain is at minimum so start reducing D
  1265. tune_p = tune_p_min;
  1266. tune_d -= tune_d*tune_d_step_ratio;
  1267. if (tune_d <= tune_d_min) {
  1268. // We have reached minimum D gain so stop tuning
  1269. tune_d = tune_d_min;
  1270. counter = AUTOTUNE_SUCCESS_COUNT;
  1271. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1272. }
  1273. }
  1274. } else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {
  1275. // we have not achieved a high enough maximum to get a good measurement of bounce back.
  1276. // increase P gain (which should increase maximum)
  1277. tune_p += tune_p*tune_p_step_ratio;
  1278. if (tune_p >= tune_p_max) {
  1279. tune_p = tune_p_max;
  1280. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1281. }
  1282. } else {
  1283. // we have a good measurement of bounce back
  1284. if (meas_rate_max-meas_rate_min > meas_rate_max*aggressiveness) {
  1285. // ignore the next result unless it is the same as this one
  1286. ignore_next = true;
  1287. // bounce back is bigger than our threshold so increment the success counter
  1288. counter++;
  1289. } else {
  1290. if (ignore_next == false) {
  1291. // bounce back is smaller than our threshold so decrement the success counter
  1292. if (counter > 0) {
  1293. counter--;
  1294. }
  1295. // increase D gain (which should increase bounce back)
  1296. tune_d += tune_d*tune_d_step_ratio*2.0f;
  1297. // stop tuning if we hit maximum D
  1298. if (tune_d >= tune_d_max) {
  1299. tune_d = tune_d_max;
  1300. counter = AUTOTUNE_SUCCESS_COUNT;
  1301. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1302. }
  1303. } else {
  1304. ignore_next = false;
  1305. }
  1306. }
  1307. }
  1308. }
  1309. // updating_rate_d_down - decrease D and adjust P to optimize the D term for no bounce back
  1310. // optimize D term while keeping the maximum just below the target by adjusting P
  1311. void AC_AutoTune::updating_rate_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
  1312. {
  1313. if (meas_rate_max > rate_target) {
  1314. // if maximum measurement was higher than target
  1315. // reduce P gain (which should reduce maximum)
  1316. tune_p -= tune_p*tune_p_step_ratio;
  1317. if (tune_p < tune_p_min) {
  1318. // P gain is at minimum so start reducing D gain
  1319. tune_p = tune_p_min;
  1320. tune_d -= tune_d*tune_d_step_ratio;
  1321. if (tune_d <= tune_d_min) {
  1322. // We have reached minimum D so stop tuning
  1323. tune_d = tune_d_min;
  1324. counter = AUTOTUNE_SUCCESS_COUNT;
  1325. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1326. }
  1327. }
  1328. } else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {
  1329. // we have not achieved a high enough maximum to get a good measurement of bounce back.
  1330. // increase P gain (which should increase maximum)
  1331. tune_p += tune_p*tune_p_step_ratio;
  1332. if (tune_p >= tune_p_max) {
  1333. tune_p = tune_p_max;
  1334. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1335. }
  1336. } else {
  1337. // we have a good measurement of bounce back
  1338. if (meas_rate_max-meas_rate_min < meas_rate_max*aggressiveness) {
  1339. if (ignore_next == false) {
  1340. // bounce back is less than our threshold so increment the success counter
  1341. counter++;
  1342. } else {
  1343. ignore_next = false;
  1344. }
  1345. } else {
  1346. // ignore the next result unless it is the same as this one
  1347. ignore_next = true;
  1348. // bounce back is larger than our threshold so decrement the success counter
  1349. if (counter > 0) {
  1350. counter--;
  1351. }
  1352. // decrease D gain (which should decrease bounce back)
  1353. tune_d -= tune_d*tune_d_step_ratio;
  1354. // stop tuning if we hit minimum D
  1355. if (tune_d <= tune_d_min) {
  1356. tune_d = tune_d_min;
  1357. counter = AUTOTUNE_SUCCESS_COUNT;
  1358. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1359. }
  1360. }
  1361. }
  1362. }
  1363. // updating_rate_p_up_d_down - increase P to ensure the target is reached while checking bounce back isn't increasing
  1364. // P is increased until we achieve our target within a reasonable time while reducing D if bounce back increases above the threshold
  1365. void AC_AutoTune::updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
  1366. {
  1367. if (meas_rate_max > rate_target*(1+0.5f*aggressiveness)) {
  1368. // ignore the next result unless it is the same as this one
  1369. ignore_next = true;
  1370. // if maximum measurement was greater than target so increment the success counter
  1371. counter++;
  1372. } else if ((meas_rate_max < rate_target) && (meas_rate_max > rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (meas_rate_max-meas_rate_min > meas_rate_max*aggressiveness) && (tune_d > tune_d_min)) {
  1373. // if bounce back was larger than the threshold so decrement the success counter
  1374. if (counter > 0) {
  1375. counter--;
  1376. }
  1377. // decrease D gain (which should decrease bounce back)
  1378. tune_d -= tune_d*tune_d_step_ratio;
  1379. // do not decrease the D term past the minimum
  1380. if (tune_d <= tune_d_min) {
  1381. tune_d = tune_d_min;
  1382. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1383. }
  1384. // decrease P gain to match D gain reduction
  1385. tune_p -= tune_p*tune_p_step_ratio;
  1386. // do not decrease the P term past the minimum
  1387. if (tune_p <= tune_p_min) {
  1388. tune_p = tune_p_min;
  1389. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1390. }
  1391. // cancel change in direction
  1392. positive_direction = !positive_direction;
  1393. } else {
  1394. if (ignore_next == false) {
  1395. // if maximum measurement was lower than target so decrement the success counter
  1396. if (counter > 0) {
  1397. counter--;
  1398. }
  1399. // increase P gain (which should increase the maximum)
  1400. tune_p += tune_p*tune_p_step_ratio;
  1401. // stop tuning if we hit maximum P
  1402. if (tune_p >= tune_p_max) {
  1403. tune_p = tune_p_max;
  1404. counter = AUTOTUNE_SUCCESS_COUNT;
  1405. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1406. }
  1407. } else {
  1408. ignore_next = false;
  1409. }
  1410. }
  1411. }
  1412. // updating_angle_p_down - decrease P until we don't reach the target before time out
  1413. // P is decreased to ensure we are not overshooting the target
  1414. void AC_AutoTune::updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)
  1415. {
  1416. if (meas_angle_max < angle_target*(1+0.5f*aggressiveness)) {
  1417. if (ignore_next == false) {
  1418. // if maximum measurement was lower than target so increment the success counter
  1419. counter++;
  1420. } else {
  1421. ignore_next = false;
  1422. }
  1423. } else {
  1424. // ignore the next result unless it is the same as this one
  1425. ignore_next = true;
  1426. // if maximum measurement was higher than target so decrement the success counter
  1427. if (counter > 0) {
  1428. counter--;
  1429. }
  1430. // decrease P gain (which should decrease the maximum)
  1431. tune_p -= tune_p*tune_p_step_ratio;
  1432. // stop tuning if we hit maximum P
  1433. if (tune_p <= tune_p_min) {
  1434. tune_p = tune_p_min;
  1435. counter = AUTOTUNE_SUCCESS_COUNT;
  1436. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1437. }
  1438. }
  1439. }
  1440. // updating_angle_p_up - increase P to ensure the target is reached
  1441. // P is increased until we achieve our target within a reasonable time
  1442. void AC_AutoTune::updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)
  1443. {
  1444. if ((meas_angle_max > angle_target*(1+0.5f*aggressiveness)) ||
  1445. ((meas_angle_max > angle_target) && (meas_rate_min < -meas_rate_max*aggressiveness))) {
  1446. // ignore the next result unless it is the same as this one
  1447. ignore_next = true;
  1448. // if maximum measurement was greater than target so increment the success counter
  1449. counter++;
  1450. } else {
  1451. if (ignore_next == false) {
  1452. // if maximum measurement was lower than target so decrement the success counter
  1453. if (counter > 0) {
  1454. counter--;
  1455. }
  1456. // increase P gain (which should increase the maximum)
  1457. tune_p += tune_p*tune_p_step_ratio;
  1458. // stop tuning if we hit maximum P
  1459. if (tune_p >= tune_p_max) {
  1460. tune_p = tune_p_max;
  1461. counter = AUTOTUNE_SUCCESS_COUNT;
  1462. Log_Write_Event(EVENT_AUTOTUNE_REACHED_LIMIT);
  1463. }
  1464. } else {
  1465. ignore_next = false;
  1466. }
  1467. }
  1468. }
  1469. /*
  1470. check if we have a good position estimate
  1471. */
  1472. bool AC_AutoTune::position_ok(void)
  1473. {
  1474. if (!AP::ahrs().have_inertial_nav()) {
  1475. // do not allow navigation with dcm position
  1476. return false;
  1477. }
  1478. // with EKF use filter status and ekf check
  1479. nav_filter_status filt_status = inertial_nav->get_filter_status();
  1480. // require a good absolute position and EKF must not be in const_pos_mode
  1481. return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
  1482. }
  1483. // get attitude for slow position hold in autotune mode
  1484. void AC_AutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out, float &yaw_cd_out)
  1485. {
  1486. roll_cd_out = pitch_cd_out = 0;
  1487. if (!use_poshold) {
  1488. // we are not trying to hold position
  1489. return;
  1490. }
  1491. // do we know where we are? If not then don't do poshold
  1492. if (!position_ok()) {
  1493. return;
  1494. }
  1495. if (!have_position) {
  1496. have_position = true;
  1497. start_position = inertial_nav->get_position();
  1498. }
  1499. // don't go past 10 degrees, as autotune result would deteriorate too much
  1500. const float angle_max_cd = 1000;
  1501. // hit the 10 degree limit at 20 meters position error
  1502. const float dist_limit_cm = 2000;
  1503. // we only start adjusting yaw if we are more than 5m from the
  1504. // target position. That corresponds to a lean angle of 2.5 degrees
  1505. const float yaw_dist_limit_cm = 500;
  1506. Vector3f pdiff = inertial_nav->get_position() - start_position;
  1507. pdiff.z = 0;
  1508. float dist_cm = pdiff.length();
  1509. if (dist_cm < 10) {
  1510. // don't do anything within 10cm
  1511. return;
  1512. }
  1513. /*
  1514. very simple linear controller
  1515. */
  1516. float scaling = constrain_float(angle_max_cd * dist_cm / dist_limit_cm, 0, angle_max_cd);
  1517. Vector2f angle_ne(pdiff.x, pdiff.y);
  1518. angle_ne *= scaling / dist_cm;
  1519. // rotate into body frame
  1520. pitch_cd_out = angle_ne.x * ahrs_view->cos_yaw() + angle_ne.y * ahrs_view->sin_yaw();
  1521. roll_cd_out = angle_ne.x * ahrs_view->sin_yaw() - angle_ne.y * ahrs_view->cos_yaw();
  1522. if (dist_cm < yaw_dist_limit_cm) {
  1523. // no yaw adjustment
  1524. return;
  1525. }
  1526. /*
  1527. also point so that twitching occurs perpendicular to the wind,
  1528. if we have drifted more than yaw_dist_limit_cm from the desired
  1529. position. This ensures that autotune doesn't have to deal with
  1530. more than 2.5 degrees of attitude on the axis it is tuning
  1531. */
  1532. float target_yaw_cd = degrees(atan2f(pdiff.y, pdiff.x)) * 100;
  1533. if (axis == PITCH) {
  1534. // for roll and yaw tuning we point along the wind, for pitch
  1535. // we point across the wind
  1536. target_yaw_cd += 9000;
  1537. }
  1538. // go to the nearest 180 degree mark, with 5 degree slop to prevent oscillation
  1539. if (fabsf(yaw_cd_out - target_yaw_cd) > 9500) {
  1540. target_yaw_cd += 18000;
  1541. }
  1542. yaw_cd_out = target_yaw_cd;
  1543. }
  1544. // Write an Autotune data packet
  1545. void AC_AutoTune::Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt)
  1546. {
  1547. AP::logger().Write(
  1548. "ATUN",
  1549. "TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt",
  1550. "s--ddd---o",
  1551. "F--000---0",
  1552. "QBBfffffff",
  1553. AP_HAL::micros64(),
  1554. axis,
  1555. tune_step,
  1556. meas_target*0.01f,
  1557. meas_min*0.01f,
  1558. meas_max*0.01f,
  1559. new_gain_rp,
  1560. new_gain_rd,
  1561. new_gain_sp,
  1562. new_ddt);
  1563. }
  1564. // Write an Autotune data packet
  1565. void AC_AutoTune::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
  1566. {
  1567. AP::logger().Write(
  1568. "ATDE",
  1569. "TimeUS,Angle,Rate",
  1570. "sdk",
  1571. "F00",
  1572. "Qff",
  1573. AP_HAL::micros64(),
  1574. angle_cd*0.01f,
  1575. rate_cds*0.01f);
  1576. }