AP_Compass_Calibration.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374
  1. #include <AP_HAL/AP_HAL.h>
  2. #include <AP_Notify/AP_Notify.h>
  3. #include <GCS_MAVLink/GCS.h>
  4. #include "AP_Compass.h"
  5. extern AP_HAL::HAL& hal;
  6. #if COMPASS_CAL_ENABLED
  7. void
  8. Compass::cal_update()
  9. {
  10. if (hal.util->get_soft_armed()) {
  11. return;
  12. }
  13. bool running = false;
  14. for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  15. bool failure;
  16. _calibrator[i].update(failure);
  17. if (failure) {
  18. AP_Notify::events.compass_cal_failed = 1;
  19. }
  20. if (_calibrator[i].check_for_timeout()) {
  21. AP_Notify::events.compass_cal_failed = 1;
  22. cancel_calibration_all();
  23. }
  24. if (_calibrator[i].running()) {
  25. running = true;
  26. } else if (_cal_autosave && !_cal_saved[i] && _calibrator[i].get_status() == COMPASS_CAL_SUCCESS) {
  27. _accept_calibration(i);
  28. }
  29. }
  30. AP_Notify::flags.compass_cal_running = running;
  31. if (is_calibrating()) {
  32. _cal_has_run = true;
  33. return;
  34. } else if (_cal_has_run && _auto_reboot()) {
  35. hal.scheduler->delay(1000);
  36. hal.scheduler->reboot(false);
  37. }
  38. }
  39. bool
  40. Compass::_start_calibration(uint8_t i, bool retry, float delay)
  41. {
  42. if (!healthy(i)) {
  43. return false;
  44. }
  45. if (!use_for_yaw(i)) {
  46. return false;
  47. }
  48. if (!is_calibrating()) {
  49. AP_Notify::events.initiated_compass_cal = 1;
  50. }
  51. if (i == get_primary() && _state[i].external != 0) {
  52. _calibrator[i].set_tolerance(_calibration_threshold);
  53. } else {
  54. // internal compasses or secondary compasses get twice the
  55. // threshold. This is because internal compasses tend to be a
  56. // lot noisier
  57. _calibrator[i].set_tolerance(_calibration_threshold*2);
  58. }
  59. if (_rotate_auto) {
  60. enum Rotation r = _state[i].external?(enum Rotation)_state[i].orientation.get():ROTATION_NONE;
  61. if (r != ROTATION_CUSTOM) {
  62. _calibrator[i].set_orientation(r, _state[i].external, _rotate_auto>=2);
  63. }
  64. }
  65. _cal_saved[i] = false;
  66. _calibrator[i].start(retry, delay, get_offsets_max(), i);
  67. // disable compass learning both for calibration and after completion
  68. _learn.set_and_save(0);
  69. return true;
  70. }
  71. bool
  72. Compass::_start_calibration_mask(uint8_t mask, bool retry, bool autosave, float delay, bool autoreboot)
  73. {
  74. _cal_autosave = autosave;
  75. _compass_cal_autoreboot = autoreboot;
  76. for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  77. if ((1<<i) & mask) {
  78. if (!_start_calibration(i,retry,delay)) {
  79. _cancel_calibration_mask(mask);
  80. return false;
  81. }
  82. }
  83. }
  84. return true;
  85. }
  86. void
  87. Compass::start_calibration_all(bool retry, bool autosave, float delay, bool autoreboot)
  88. {
  89. _cal_autosave = autosave;
  90. _compass_cal_autoreboot = autoreboot;
  91. for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  92. // ignore any compasses that fail to start calibrating
  93. // start all should only calibrate compasses that are being used
  94. _start_calibration(i,retry,delay);
  95. }
  96. }
  97. void
  98. Compass::_cancel_calibration(uint8_t i)
  99. {
  100. AP_Notify::events.initiated_compass_cal = 0;
  101. if (_calibrator[i].running() || _calibrator[i].get_status() == COMPASS_CAL_WAITING_TO_START) {
  102. AP_Notify::events.compass_cal_canceled = 1;
  103. }
  104. _cal_saved[i] = false;
  105. _calibrator[i].clear();
  106. }
  107. void
  108. Compass::_cancel_calibration_mask(uint8_t mask)
  109. {
  110. for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  111. if((1<<i) & mask) {
  112. _cancel_calibration(i);
  113. }
  114. }
  115. }
  116. void
  117. Compass::cancel_calibration_all()
  118. {
  119. _cancel_calibration_mask(0xFF);
  120. }
  121. bool
  122. Compass::_accept_calibration(uint8_t i)
  123. {
  124. CompassCalibrator& cal = _calibrator[i];
  125. uint8_t cal_status = cal.get_status();
  126. if (_cal_saved[i] || cal_status == COMPASS_CAL_NOT_STARTED) {
  127. return true;
  128. } else if (cal_status == COMPASS_CAL_SUCCESS) {
  129. _cal_complete_requires_reboot = true;
  130. _cal_saved[i] = true;
  131. Vector3f ofs, diag, offdiag;
  132. cal.get_calibration(ofs, diag, offdiag);
  133. set_and_save_offsets(i, ofs);
  134. set_and_save_diagonals(i,diag);
  135. set_and_save_offdiagonals(i,offdiag);
  136. if (_state[i].external && _rotate_auto >= 2) {
  137. _state[i].orientation.set_and_save_ifchanged(cal.get_orientation());
  138. }
  139. if (!is_calibrating()) {
  140. AP_Notify::events.compass_cal_saved = 1;
  141. }
  142. return true;
  143. } else {
  144. return false;
  145. }
  146. }
  147. bool
  148. Compass::_accept_calibration_mask(uint8_t mask)
  149. {
  150. bool success = true;
  151. for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  152. if ((1<<i) & mask) {
  153. if (!_accept_calibration(i)) {
  154. success = false;
  155. }
  156. _calibrator[i].clear();
  157. }
  158. }
  159. return success;
  160. }
  161. bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link)
  162. {
  163. uint8_t cal_mask = _get_cal_mask();
  164. for (uint8_t compass_id=0; compass_id<COMPASS_MAX_INSTANCES; compass_id++) {
  165. // ensure we don't try to send with no space available
  166. if (!HAVE_PAYLOAD_SPACE(link.get_chan(), MAG_CAL_PROGRESS)) {
  167. // ideally we would only send one progress message per
  168. // call. If we don't return true here we may end up
  169. // hogging *all* the bandwidth
  170. return true;
  171. }
  172. auto& calibrator = _calibrator[compass_id];
  173. uint8_t cal_status = calibrator.get_status();
  174. if (cal_status == COMPASS_CAL_WAITING_TO_START ||
  175. cal_status == COMPASS_CAL_RUNNING_STEP_ONE ||
  176. cal_status == COMPASS_CAL_RUNNING_STEP_TWO) {
  177. uint8_t completion_pct = calibrator.get_completion_percent();
  178. auto& completion_mask = calibrator.get_completion_mask();
  179. const Vector3f direction;
  180. uint8_t attempt = _calibrator[compass_id].get_attempt();
  181. mavlink_msg_mag_cal_progress_send(
  182. link.get_chan(),
  183. compass_id, cal_mask,
  184. cal_status, attempt, completion_pct, completion_mask,
  185. direction.x, direction.y, direction.z
  186. );
  187. }
  188. }
  189. return true;
  190. }
  191. bool Compass::send_mag_cal_report(const GCS_MAVLINK& link)
  192. {
  193. uint8_t cal_mask = _get_cal_mask();
  194. for (uint8_t compass_id=0; compass_id<COMPASS_MAX_INSTANCES; compass_id++) {
  195. // ensure we don't try to send with no space available
  196. if (!HAVE_PAYLOAD_SPACE(link.get_chan(), MAG_CAL_REPORT)) {
  197. // ideally we would only send one progress message per
  198. // call. If we don't return true here we may end up
  199. // hogging *all* the bandwidth
  200. return true;
  201. }
  202. uint8_t cal_status = _calibrator[compass_id].get_status();
  203. if (cal_status == COMPASS_CAL_SUCCESS ||
  204. cal_status == COMPASS_CAL_FAILED ||
  205. cal_status == COMPASS_CAL_BAD_ORIENTATION) {
  206. float fitness = _calibrator[compass_id].get_fitness();
  207. Vector3f ofs, diag, offdiag;
  208. _calibrator[compass_id].get_calibration(ofs, diag, offdiag);
  209. uint8_t autosaved = _cal_saved[compass_id];
  210. mavlink_msg_mag_cal_report_send(
  211. link.get_chan(),
  212. compass_id, cal_mask,
  213. cal_status, autosaved,
  214. fitness,
  215. ofs.x, ofs.y, ofs.z,
  216. diag.x, diag.y, diag.z,
  217. offdiag.x, offdiag.y, offdiag.z,
  218. _calibrator[compass_id].get_orientation_confidence(),
  219. _calibrator[compass_id].get_original_orientation(),
  220. _calibrator[compass_id].get_orientation()
  221. );
  222. }
  223. }
  224. return true;
  225. }
  226. bool
  227. Compass::is_calibrating() const
  228. {
  229. for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  230. switch(_calibrator[i].get_status()) {
  231. case COMPASS_CAL_NOT_STARTED:
  232. case COMPASS_CAL_SUCCESS:
  233. case COMPASS_CAL_FAILED:
  234. case COMPASS_CAL_BAD_ORIENTATION:
  235. break;
  236. default:
  237. return true;
  238. }
  239. }
  240. return false;
  241. }
  242. uint8_t
  243. Compass::_get_cal_mask() const
  244. {
  245. uint8_t cal_mask = 0;
  246. for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
  247. if (_calibrator[i].get_status() != COMPASS_CAL_NOT_STARTED) {
  248. cal_mask |= 1 << i;
  249. }
  250. }
  251. return cal_mask;
  252. }
  253. /*
  254. handle an incoming MAG_CAL command
  255. */
  256. MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
  257. {
  258. MAV_RESULT result = MAV_RESULT_FAILED;
  259. switch (packet.command) {
  260. case MAV_CMD_DO_START_MAG_CAL: {
  261. result = MAV_RESULT_ACCEPTED;
  262. if (hal.util->get_soft_armed()) {
  263. hal.console->printf("Disarm for compass calibration\n");
  264. result = MAV_RESULT_FAILED;
  265. break;
  266. }
  267. if (packet.param1 < 0 || packet.param1 > 255) {
  268. result = MAV_RESULT_FAILED;
  269. break;
  270. }
  271. uint8_t mag_mask = packet.param1;
  272. bool retry = !is_zero(packet.param2);
  273. bool autosave = !is_zero(packet.param3);
  274. float delay = packet.param4;
  275. bool autoreboot = !is_zero(packet.param5);
  276. if (mag_mask == 0) { // 0 means all
  277. start_calibration_all(retry, autosave, delay, autoreboot);
  278. } else {
  279. if (!_start_calibration_mask(mag_mask, retry, autosave, delay, autoreboot)) {
  280. result = MAV_RESULT_FAILED;
  281. }
  282. }
  283. break;
  284. }
  285. case MAV_CMD_DO_ACCEPT_MAG_CAL: {
  286. result = MAV_RESULT_ACCEPTED;
  287. if(packet.param1 < 0 || packet.param1 > 255) {
  288. result = MAV_RESULT_FAILED;
  289. break;
  290. }
  291. uint8_t mag_mask = packet.param1;
  292. if (mag_mask == 0) { // 0 means all
  293. mag_mask = 0xFF;
  294. }
  295. if(!_accept_calibration_mask(mag_mask)) {
  296. result = MAV_RESULT_FAILED;
  297. }
  298. break;
  299. }
  300. case MAV_CMD_DO_CANCEL_MAG_CAL: {
  301. result = MAV_RESULT_ACCEPTED;
  302. if(packet.param1 < 0 || packet.param1 > 255) {
  303. result = MAV_RESULT_FAILED;
  304. break;
  305. }
  306. uint8_t mag_mask = packet.param1;
  307. if (mag_mask == 0) { // 0 means all
  308. cancel_calibration_all();
  309. break;
  310. }
  311. _cancel_calibration_mask(mag_mask);
  312. break;
  313. }
  314. }
  315. return result;
  316. }
  317. #endif // COMPASS_CAL_ENABLED