AP_Tuning.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346
  1. #include "AP_Tuning.h"
  2. #include <AP_Logger/AP_Logger.h>
  3. #include <GCS_MAVLink/GCS.h>
  4. #include <RC_Channel/RC_Channel.h>
  5. extern const AP_HAL::HAL& hal;
  6. const AP_Param::GroupInfo AP_Tuning::var_info[] = {
  7. // @Param: CHAN
  8. // @DisplayName: Transmitter tuning channel
  9. // @Description: This sets the channel for transmitter tuning. This should be connected to a knob or slider on your transmitter. It needs to be setup to use the PWM range given by TUNE_CHAN_MIN to TUNE_CHAN_MAX
  10. // @Values: 0:Disable,5:Chan5,6:Chan6,7:Chan7,8:Chan8,9:Chan9,10:Chan10,11:Chan11,12:Chan12,13:Chan13,14:Chan14,15:Chan15,16:Chan16
  11. // @User: Standard
  12. AP_GROUPINFO("CHAN", 1, AP_Tuning, channel, 0),
  13. // @Param: CHAN_MIN
  14. // @DisplayName: Transmitter tuning channel minimum pwm
  15. // @Description: This sets the PWM lower limit for the tuning channel
  16. // @Range: 900 2100
  17. // @User: Standard
  18. AP_GROUPINFO("CHAN_MIN", 2, AP_Tuning, channel_min, 1000),
  19. // @Param: CHAN_MAX
  20. // @DisplayName: Transmitter tuning channel maximum pwm
  21. // @Description: This sets the PWM upper limit for the tuning channel
  22. // @Range: 900 2100
  23. // @User: Standard
  24. AP_GROUPINFO("CHAN_MAX", 3, AP_Tuning, channel_max, 2000),
  25. // @Param: SELECTOR
  26. // @DisplayName: Transmitter tuning selector channel
  27. // @Description: This sets the channel for the transmitter tuning selector switch. This should be a 2 position switch, preferably spring loaded. A PWM above 1700 means high, below 1300 means low. If no selector is set then you won't be able to switch between parameters during flight or re-center the tuning knob
  28. // @Values: 0:Disable,1:Chan1,2:Chan3,3:Chan3,4:Chan4,5:Chan5,6:Chan6,7:Chan7,8:Chan8,9:Chan9,10:Chan10,11:Chan11,12:Chan12,13:Chan13,14:Chan14,15:Chan15,16:Chan16
  29. // @User: Standard
  30. AP_GROUPINFO("SELECTOR", 4, AP_Tuning, selector, 0),
  31. // @Param: RANGE
  32. // @DisplayName: Transmitter tuning range
  33. // @Description: This sets the range over which tuning will change a parameter. A value of 2 means the tuning parameter will go from 0.5 times the start value to 2x the start value over the range of the tuning channel
  34. // @User: Standard
  35. AP_GROUPINFO("RANGE", 5, AP_Tuning, range, 2.0f),
  36. // @Param: MODE_REVERT
  37. // @DisplayName: Revert on mode change
  38. // @Description: This controls whether tuning values will revert on a flight mode change.
  39. // @Values: 0:Disable,1:Enable
  40. // @User: Standard
  41. AP_GROUPINFO("MODE_REVERT", 6, AP_Tuning, mode_revert, 1),
  42. // @Param: ERR_THRESH
  43. // @DisplayName: Controller error threshold
  44. // @Description: This sets the controller error threshold above which an alarm will sound and a message will be sent to the GCS to warn of controller instability
  45. // @Range: 0 1
  46. // @User: Standard
  47. AP_GROUPINFO("ERR_THRESH", 7, AP_Tuning, error_threshold, 0.15f),
  48. AP_GROUPEND
  49. };
  50. /*
  51. handle selector switch input
  52. */
  53. void AP_Tuning::check_selector_switch(void)
  54. {
  55. if (selector == 0) {
  56. // no selector switch enabled
  57. return;
  58. }
  59. if (!rc().has_valid_input()) {
  60. selector_start_ms = 0;
  61. return;
  62. }
  63. RC_Channel *selchan = rc().channel(selector-1);
  64. if (selchan == nullptr) {
  65. return;
  66. }
  67. uint16_t selector_in = selchan->get_radio_in();
  68. if (selector_in >= 1700) {
  69. // high selector
  70. if (selector_start_ms == 0) {
  71. selector_start_ms = AP_HAL::millis();
  72. }
  73. uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
  74. if (hold_time > 5000 && changed) {
  75. // save tune
  76. save_parameters();
  77. re_center();
  78. gcs().send_text(MAV_SEVERITY_INFO, "Tuning: Saved");
  79. AP_Notify::events.tune_save = 1;
  80. changed = false;
  81. need_revert = 0;
  82. }
  83. } else if (selector_in <= 1300) {
  84. // low selector
  85. if (selector_start_ms != 0) {
  86. uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
  87. if (hold_time < 200) {
  88. // debounce!
  89. } else if (hold_time < 2000) {
  90. // re-center the value
  91. re_center();
  92. gcs().send_text(MAV_SEVERITY_INFO, "Tuning: recentered %s", get_tuning_name(current_parm));
  93. } else if (hold_time < 5000) {
  94. // change parameter
  95. next_parameter();
  96. }
  97. selector_start_ms = 0;
  98. }
  99. }
  100. }
  101. /*
  102. re-center the tuning value
  103. */
  104. void AP_Tuning::re_center(void)
  105. {
  106. AP_Float *f = get_param_pointer(current_parm);
  107. if (f != nullptr) {
  108. center_value = f->get();
  109. }
  110. mid_point_wait = true;
  111. }
  112. /*
  113. check for changed tuning input
  114. */
  115. void AP_Tuning::check_input(uint8_t flightmode)
  116. {
  117. if (channel <= 0 || parmset <= 0) {
  118. // disabled
  119. return;
  120. }
  121. // check for revert on changed flightmode
  122. if (flightmode != last_flightmode) {
  123. if (need_revert != 0 && mode_revert != 0) {
  124. gcs().send_text(MAV_SEVERITY_INFO, "Tuning: reverted");
  125. revert_parameters();
  126. re_center();
  127. }
  128. last_flightmode = flightmode;
  129. }
  130. // only adjust values at 10Hz
  131. uint32_t now = AP_HAL::millis();
  132. uint32_t dt_ms = now - last_check_ms;
  133. if (dt_ms < 100) {
  134. return;
  135. }
  136. last_check_ms = now;
  137. if (channel > RC_Channels::get_valid_channel_count()) {
  138. // not valid channel
  139. return;
  140. }
  141. // check for invalid range
  142. if (range < 1.1f) {
  143. range.set(1.1f);
  144. }
  145. if (current_parm == 0) {
  146. next_parameter();
  147. }
  148. // cope with user changing parmset while tuning
  149. if (current_set != parmset) {
  150. re_center();
  151. }
  152. current_set = parmset;
  153. check_selector_switch();
  154. if (selector_start_ms) {
  155. // no tuning while selector high
  156. return;
  157. }
  158. if (current_parm == 0) {
  159. return;
  160. }
  161. RC_Channel *chan = rc().channel(channel-1);
  162. if (chan == nullptr) {
  163. return;
  164. }
  165. float chan_value = linear_interpolate(-1, 1, chan->get_radio_in(), channel_min, channel_max);
  166. if (dt_ms > 500) {
  167. last_channel_value = chan_value;
  168. }
  169. // check for controller error
  170. check_controller_error();
  171. if (fabsf(chan_value - last_channel_value) < 0.01) {
  172. // ignore changes of less than 1%
  173. return;
  174. }
  175. //hal.console->printf("chan_value %.2f last_channel_value %.2f\n", chan_value, last_channel_value);
  176. if (mid_point_wait) {
  177. // see if we have crossed the mid-point. We use a small deadzone to make it easier
  178. // to move to the "indent" portion of a slider to start tuning
  179. const float dead_zone = 0.02;
  180. if ((chan_value > dead_zone && last_channel_value > 0) ||
  181. (chan_value < -dead_zone && last_channel_value < 0)) {
  182. // still waiting
  183. return;
  184. }
  185. // starting tuning
  186. mid_point_wait = false;
  187. gcs().send_text(MAV_SEVERITY_INFO, "Tuning: mid-point %s", get_tuning_name(current_parm));
  188. AP_Notify::events.tune_started = 1;
  189. }
  190. last_channel_value = chan_value;
  191. float new_value;
  192. if (chan_value > 0) {
  193. new_value = linear_interpolate(center_value, range*center_value, chan_value, 0, 1);
  194. } else {
  195. new_value = linear_interpolate(center_value/range, center_value, chan_value, -1, 0);
  196. }
  197. changed = true;
  198. need_revert |= (1U << current_parm_index);
  199. set_value(current_parm, new_value);
  200. Log_Write_Parameter_Tuning(new_value);
  201. }
  202. /*
  203. log a tuning change
  204. */
  205. void AP_Tuning::Log_Write_Parameter_Tuning(float value)
  206. {
  207. AP::logger().Write("PTUN", "TimeUS,Set,Parm,Value,CenterValue", "QBBff",
  208. AP_HAL::micros64(),
  209. parmset,
  210. current_parm,
  211. (double)value,
  212. (double)center_value);
  213. }
  214. /*
  215. save parameters in the set
  216. */
  217. void AP_Tuning::save_parameters(void)
  218. {
  219. uint8_t set = (uint8_t)parmset.get();
  220. if (set < set_base) {
  221. // single parameter tuning
  222. save_value(set);
  223. return;
  224. }
  225. // multiple parameter tuning
  226. for (uint8_t i=0; tuning_sets[i].num_parms != 0; i++) {
  227. if (tuning_sets[i].set+set_base == set) {
  228. for (uint8_t p=0; p<tuning_sets[i].num_parms; p++) {
  229. save_value(tuning_sets[i].parms[p]);
  230. }
  231. break;
  232. }
  233. }
  234. }
  235. /*
  236. save parameters in the set
  237. */
  238. void AP_Tuning::revert_parameters(void)
  239. {
  240. uint8_t set = (uint8_t)parmset.get();
  241. if (set < set_base) {
  242. // single parameter tuning
  243. reload_value(set);
  244. return;
  245. }
  246. for (uint8_t i=0; tuning_sets[i].num_parms != 0; i++) {
  247. if (tuning_sets[i].set+set_base == set) {
  248. for (uint8_t p=0; p<tuning_sets[i].num_parms; p++) {
  249. if (p >= 32 || (need_revert & (1U<<p))) {
  250. reload_value(tuning_sets[i].parms[p]);
  251. }
  252. }
  253. need_revert = 0;
  254. break;
  255. }
  256. }
  257. }
  258. /*
  259. switch to the next parameter in the set
  260. */
  261. void AP_Tuning::next_parameter(void)
  262. {
  263. uint8_t set = (uint8_t)parmset.get();
  264. if (set < set_base) {
  265. // nothing to do but re-center
  266. current_parm = set;
  267. re_center();
  268. return;
  269. }
  270. for (uint8_t i=0; tuning_sets[i].num_parms != 0; i++) {
  271. if (tuning_sets[i].set+set_base == set) {
  272. if (current_parm == 0) {
  273. current_parm_index = 0;
  274. } else {
  275. current_parm_index = (current_parm_index + 1) % tuning_sets[i].num_parms;
  276. }
  277. current_parm = tuning_sets[i].parms[current_parm_index];
  278. re_center();
  279. gcs().send_text(MAV_SEVERITY_INFO, "Tuning: started %s", get_tuning_name(current_parm));
  280. AP_Notify::events.tune_next = current_parm_index+1;
  281. break;
  282. }
  283. }
  284. }
  285. /*
  286. return a string representing a tuning parameter
  287. */
  288. const char *AP_Tuning::get_tuning_name(uint8_t parm)
  289. {
  290. for (uint8_t i=0; tuning_names[i].name != nullptr; i++) {
  291. if (parm == tuning_names[i].parm) {
  292. return tuning_names[i].name;
  293. }
  294. }
  295. return "UNKNOWN";
  296. }
  297. /*
  298. check for controller error
  299. */
  300. void AP_Tuning::check_controller_error(void)
  301. {
  302. float err = controller_error(current_parm);
  303. if (err > error_threshold) {
  304. uint32_t now = AP_HAL::millis();
  305. if (now - last_controller_error_ms > 2000 && hal.util->get_soft_armed()) {
  306. AP_Notify::events.tune_error = 1;
  307. gcs().send_text(MAV_SEVERITY_INFO, "Tuning: error %.2f", (double)err);
  308. last_controller_error_ms = now;
  309. }
  310. }
  311. }