AP_AutoTune.cpp 9.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /**
  14. The strategy for roll/pitch autotune is to give the user a AUTOTUNE
  15. flight mode which behaves just like FBWA, but does automatic
  16. tuning.
  17. While the user is flying in AUTOTUNE the gains are saved every 10
  18. seconds, but the saved gains are not the current gains, instead it
  19. saves the gains from 10s ago. When the user exits AUTOTUNE the
  20. gains are restored from 10s ago.
  21. This allows the user to fly as much as they want in AUTOTUNE mode,
  22. and if they are ever unhappy they just exit the mode. If they stay
  23. in AUTOTUNE for more than 10s then their gains will have changed.
  24. Using this approach users don't need any special switches, they
  25. just need to be able to enter and exit AUTOTUNE mode
  26. */
  27. #include "AP_AutoTune.h"
  28. #include <AP_Common/AP_Common.h>
  29. #include <AP_HAL/AP_HAL.h>
  30. #include <AP_Logger/AP_Logger.h>
  31. #include <AP_Math/AP_Math.h>
  32. extern const AP_HAL::HAL& hal;
  33. // time in milliseconds between autotune saves
  34. #define AUTOTUNE_SAVE_PERIOD 10000U
  35. // how much time we have to overshoot for to reduce gains
  36. #define AUTOTUNE_OVERSHOOT_TIME 100
  37. // how much time we have to undershoot for to increase gains
  38. #define AUTOTUNE_UNDERSHOOT_TIME 200
  39. // step size for increasing gains, percentage
  40. #define AUTOTUNE_INCREASE_STEP 5
  41. // step size for decreasing gains, percentage
  42. #define AUTOTUNE_DECREASE_STEP 8
  43. // min/max P gains
  44. #define AUTOTUNE_MAX_P 5.0f
  45. #define AUTOTUNE_MIN_P 0.3f
  46. // tau ranges
  47. #define AUTOTUNE_MAX_TAU 0.7f
  48. #define AUTOTUNE_MIN_TAU 0.2f
  49. #define AUTOTUNE_MIN_IMAX 2000
  50. #define AUTOTUNE_MAX_IMAX 4000
  51. // constructor
  52. AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type,
  53. const AP_Vehicle::FixedWing &parms) :
  54. running(false),
  55. current(_gains),
  56. type(_type),
  57. aparm(parms),
  58. saturated_surfaces(false)
  59. {}
  60. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  61. #include <stdio.h>
  62. # define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
  63. #else
  64. # define Debug(fmt, args ...)
  65. #endif
  66. /*
  67. auto-tuning table. This table gives the starting values for key
  68. tuning parameters based on a user chosen AUTOTUNE_LEVEL parameter
  69. from 1 to 10. Level 1 is a very soft tune. Level 10 is a very
  70. aggressive tune.
  71. */
  72. static const struct {
  73. float tau;
  74. float Dratio;
  75. float rmax;
  76. } tuning_table[] = {
  77. { 0.70f, 0.050f, 20 }, // level 1
  78. { 0.65f, 0.055f, 30 }, // level 2
  79. { 0.60f, 0.060f, 40 }, // level 3
  80. { 0.55f, 0.065f, 50 }, // level 4
  81. { 0.50f, 0.070f, 60 }, // level 5
  82. { 0.45f, 0.075f, 75 }, // level 6
  83. { 0.40f, 0.080f, 90 }, // level 7
  84. { 0.30f, 0.085f, 120 }, // level 8
  85. { 0.20f, 0.090f, 160 }, // level 9
  86. { 0.10f, 0.095f, 210 }, // level 10
  87. { 0.05f, 0.100f, 300 }, // (yes, it goes to 11)
  88. };
  89. /*
  90. start an autotune session
  91. */
  92. void AP_AutoTune::start(void)
  93. {
  94. running = true;
  95. state = DEMAND_UNSATURATED;
  96. uint32_t now = AP_HAL::millis();
  97. state_enter_ms = now;
  98. last_save_ms = now;
  99. last_save = current;
  100. restore = current;
  101. uint8_t level = aparm.autotune_level;
  102. if (level > ARRAY_SIZE(tuning_table)) {
  103. level = ARRAY_SIZE(tuning_table);
  104. }
  105. if (level < 1) {
  106. level = 1;
  107. }
  108. current.rmax.set(tuning_table[level-1].rmax);
  109. // D gain is scaled to a fixed ratio of P gain
  110. current.D.set(tuning_table[level-1].Dratio * current.P);
  111. current.tau.set(tuning_table[level-1].tau);
  112. current.imax = constrain_float(current.imax, AUTOTUNE_MIN_IMAX, AUTOTUNE_MAX_IMAX);
  113. // force a fixed ratio of I to D gain on the rate feedback path
  114. current.I = 0.5f * current.D / current.tau;
  115. next_save = current;
  116. Debug("START P -> %.3f\n", current.P.get());
  117. }
  118. /*
  119. called when we change state to see if we should change gains
  120. */
  121. void AP_AutoTune::stop(void)
  122. {
  123. if (running) {
  124. running = false;
  125. save_gains(restore);
  126. }
  127. }
  128. /*
  129. one update cycle of the autotuner
  130. */
  131. void AP_AutoTune::update(float desired_rate, float achieved_rate, float servo_out)
  132. {
  133. if (!running) {
  134. return;
  135. }
  136. check_save();
  137. // see what state we are in
  138. ATState new_state;
  139. float abs_desired_rate = fabsf(desired_rate);
  140. uint32_t now = AP_HAL::millis();
  141. if (fabsf(servo_out) >= 45) {
  142. // we have saturated the servo demand (not including
  143. // integrator), we cannot get any information that would allow
  144. // us to increase the gain
  145. saturated_surfaces = true;
  146. }
  147. if (abs_desired_rate < 0.8f * current.rmax) {
  148. // we are not demanding max rate
  149. new_state = DEMAND_UNSATURATED;
  150. } else if (fabsf(achieved_rate) > abs_desired_rate) {
  151. new_state = desired_rate > 0 ? DEMAND_OVER_POS : DEMAND_OVER_NEG;
  152. } else {
  153. new_state = desired_rate > 0 ? DEMAND_UNDER_POS : DEMAND_UNDER_NEG;
  154. }
  155. if (new_state != state) {
  156. check_state_exit(now - state_enter_ms);
  157. state = new_state;
  158. state_enter_ms = now;
  159. saturated_surfaces = false;
  160. }
  161. if (state != DEMAND_UNSATURATED) {
  162. write_log(servo_out, desired_rate, achieved_rate);
  163. }
  164. }
  165. /*
  166. called when we change state to see if we should change gains
  167. */
  168. void AP_AutoTune::check_state_exit(uint32_t state_time_ms)
  169. {
  170. switch (state) {
  171. case DEMAND_UNSATURATED:
  172. break;
  173. case DEMAND_UNDER_POS:
  174. case DEMAND_UNDER_NEG:
  175. // we increase P if we have not saturated the surfaces during
  176. // this state, and we have
  177. if (state_time_ms >= AUTOTUNE_UNDERSHOOT_TIME && !saturated_surfaces) {
  178. current.P.set(current.P * (100+AUTOTUNE_INCREASE_STEP) * 0.01f);
  179. if (current.P > AUTOTUNE_MAX_P) {
  180. current.P = AUTOTUNE_MAX_P;
  181. }
  182. Debug("UNDER P -> %.3f\n", current.P.get());
  183. }
  184. current.D.set(tuning_table[aparm.autotune_level-1].Dratio * current.P);
  185. break;
  186. case DEMAND_OVER_POS:
  187. case DEMAND_OVER_NEG:
  188. if (state_time_ms >= AUTOTUNE_OVERSHOOT_TIME) {
  189. current.P.set(current.P * (100-AUTOTUNE_DECREASE_STEP) * 0.01f);
  190. if (current.P < AUTOTUNE_MIN_P) {
  191. current.P = AUTOTUNE_MIN_P;
  192. }
  193. Debug("OVER P -> %.3f\n", current.P.get());
  194. }
  195. current.D.set(tuning_table[aparm.autotune_level-1].Dratio * current.P);
  196. break;
  197. }
  198. }
  199. /*
  200. see if we should save new values
  201. */
  202. void AP_AutoTune::check_save(void)
  203. {
  204. if (AP_HAL::millis() - last_save_ms < AUTOTUNE_SAVE_PERIOD) {
  205. return;
  206. }
  207. // save the next_save values, which are the autotune value from
  208. // the last save period. This means the pilot has
  209. // AUTOTUNE_SAVE_PERIOD milliseconds to decide they don't like the
  210. // gains and switch out of autotune
  211. ATGains tmp = current;
  212. save_gains(next_save);
  213. Debug("SAVE P -> %.3f\n", current.P.get());
  214. // restore our current gains
  215. current = tmp;
  216. // if the pilot exits autotune they get these saved values
  217. restore = next_save;
  218. // the next values to save will be the ones we are flying now
  219. next_save = current;
  220. last_save_ms = AP_HAL::millis();
  221. }
  222. /*
  223. log a parameter change from autotune
  224. */
  225. void AP_AutoTune::log_param_change(float v, const char *suffix)
  226. {
  227. AP_Logger *logger = AP_Logger::get_singleton();
  228. if (!logger->logging_started()) {
  229. return;
  230. }
  231. char key[AP_MAX_NAME_SIZE+1];
  232. if (type == AUTOTUNE_ROLL) {
  233. strncpy(key, "RLL2SRV_", 9);
  234. strncpy(&key[8], suffix, AP_MAX_NAME_SIZE-8);
  235. } else {
  236. strncpy(key, "PTCH2SRV_", 10);
  237. strncpy(&key[9], suffix, AP_MAX_NAME_SIZE-9);
  238. }
  239. key[AP_MAX_NAME_SIZE] = 0;
  240. logger->Write_Parameter(key, v);
  241. }
  242. /*
  243. set a float and save a float if it has changed by more than
  244. 0.1%. This reduces the number of insignificant EEPROM writes
  245. */
  246. void AP_AutoTune::save_float_if_changed(AP_Float &v, float value, const char *suffix)
  247. {
  248. float old_value = v.get();
  249. v.set(value);
  250. if (value <= 0 || fabsf((value-old_value)/value) > 0.001f) {
  251. v.save();
  252. log_param_change(v.get(), suffix);
  253. }
  254. }
  255. /*
  256. set a int16 and save if changed
  257. */
  258. void AP_AutoTune::save_int16_if_changed(AP_Int16 &v, int16_t value, const char *suffix)
  259. {
  260. int16_t old_value = v.get();
  261. v.set(value);
  262. if (old_value != v.get()) {
  263. v.save();
  264. log_param_change(v.get(), suffix);
  265. }
  266. }
  267. /*
  268. save a set of gains
  269. */
  270. void AP_AutoTune::save_gains(const ATGains &v)
  271. {
  272. current = last_save;
  273. save_float_if_changed(current.tau, v.tau, "TCONST");
  274. save_float_if_changed(current.P, v.P, "P");
  275. save_float_if_changed(current.I, v.I, "I");
  276. save_float_if_changed(current.D, v.D, "D");
  277. save_int16_if_changed(current.rmax, v.rmax, "RMAX");
  278. save_int16_if_changed(current.imax, v.imax, "IMAX");
  279. last_save = current;
  280. }
  281. void AP_AutoTune::write_log(float servo, float demanded, float achieved)
  282. {
  283. AP_Logger *logger = AP_Logger::get_singleton();
  284. if (!logger->logging_started()) {
  285. return;
  286. }
  287. struct log_ATRP pkt = {
  288. LOG_PACKET_HEADER_INIT(LOG_ATRP_MSG),
  289. time_us : AP_HAL::micros64(),
  290. type : static_cast<uint8_t>(type),
  291. state : (uint8_t)state,
  292. servo : (int16_t)(servo*100),
  293. demanded : demanded,
  294. achieved : achieved,
  295. P : current.P.get()
  296. };
  297. logger->WriteBlock(&pkt, sizeof(pkt));
  298. }