AP_AccelCal.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384
  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. #include "AP_AccelCal.h"
  14. #include <stdarg.h>
  15. #include <GCS_MAVLink/GCS.h>
  16. #include <GCS_MAVLink/GCS_MAVLink.h>
  17. #include <AP_HAL/AP_HAL.h>
  18. #define AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS 1000
  19. #define _printf(fmt, args ...) do { \
  20. if (_gcs != nullptr) { \
  21. _gcs->send_text(MAV_SEVERITY_CRITICAL, fmt, ## args); \
  22. } \
  23. } while (0)
  24. const extern AP_HAL::HAL& hal;
  25. static bool _start_collect_sample;
  26. uint8_t AP_AccelCal::_num_clients = 0;
  27. AP_AccelCal_Client* AP_AccelCal::_clients[AP_ACCELCAL_MAX_NUM_CLIENTS] {};
  28. void AP_AccelCal::update()
  29. {
  30. if (!get_calibrator(0)) {
  31. // no calibrators
  32. return;
  33. }
  34. if (_started) {
  35. update_status();
  36. AccelCalibrator *cal;
  37. uint8_t num_active_calibrators = 0;
  38. for(uint8_t i=0; (cal = get_calibrator(i)); i++) {
  39. num_active_calibrators++;
  40. }
  41. if (num_active_calibrators != _num_active_calibrators) {
  42. fail();
  43. return;
  44. }
  45. if(_start_collect_sample) {
  46. collect_sample();
  47. }
  48. switch(_status) {
  49. case ACCEL_CAL_NOT_STARTED:
  50. fail();
  51. return;
  52. case ACCEL_CAL_WAITING_FOR_ORIENTATION: {
  53. // if we're waiting for orientation, first ensure that all calibrators are on the same step
  54. uint8_t step;
  55. if ((cal = get_calibrator(0)) == nullptr) {
  56. fail();
  57. return;
  58. }
  59. step = cal->get_num_samples_collected()+1;
  60. for(uint8_t i=1 ; (cal = get_calibrator(i)) ; i++) {
  61. if (step != cal->get_num_samples_collected()+1) {
  62. fail();
  63. return;
  64. }
  65. }
  66. // if we're on a new step, print a message describing the step
  67. if (step != _step) {
  68. _step = step;
  69. if(_use_gcs_snoop) {
  70. const char *msg;
  71. switch (step) {
  72. case ACCELCAL_VEHICLE_POS_LEVEL:
  73. msg = "level";
  74. break;
  75. case ACCELCAL_VEHICLE_POS_LEFT:
  76. msg = "on its LEFT side";
  77. break;
  78. case ACCELCAL_VEHICLE_POS_RIGHT:
  79. msg = "on its RIGHT side";
  80. break;
  81. case ACCELCAL_VEHICLE_POS_NOSEDOWN:
  82. msg = "nose DOWN";
  83. break;
  84. case ACCELCAL_VEHICLE_POS_NOSEUP:
  85. msg = "nose UP";
  86. break;
  87. case ACCELCAL_VEHICLE_POS_BACK:
  88. msg = "on its BACK";
  89. break;
  90. default:
  91. fail();
  92. return;
  93. }
  94. _printf("Place vehicle %s and press any key.", msg);
  95. _waiting_for_mavlink_ack = true;
  96. }
  97. }
  98. uint32_t now = AP_HAL::millis();
  99. if (now - _last_position_request_ms > AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS) {
  100. _last_position_request_ms = now;
  101. _gcs->send_accelcal_vehicle_position(step);
  102. }
  103. break;
  104. }
  105. case ACCEL_CAL_COLLECTING_SAMPLE:
  106. // check for timeout
  107. for(uint8_t i=0; (cal = get_calibrator(i)); i++) {
  108. cal->check_for_timeout();
  109. }
  110. update_status();
  111. if (_status == ACCEL_CAL_FAILED) {
  112. fail();
  113. }
  114. return;
  115. case ACCEL_CAL_SUCCESS:
  116. // save
  117. if (_saving) {
  118. bool done = true;
  119. for(uint8_t i=0; i<_num_clients; i++) {
  120. if (client_active(i) && _clients[i]->_acal_get_saving()) {
  121. done = false;
  122. break;
  123. }
  124. }
  125. if (done) {
  126. success();
  127. }
  128. return;
  129. } else {
  130. for(uint8_t i=0; i<_num_clients; i++) {
  131. if(client_active(i) && _clients[i]->_acal_get_fail()) {
  132. fail();
  133. return;
  134. }
  135. }
  136. for(uint8_t i=0; i<_num_clients; i++) {
  137. if(client_active(i)) {
  138. _clients[i]->_acal_save_calibrations();
  139. }
  140. }
  141. _saving = true;
  142. }
  143. return;
  144. default:
  145. case ACCEL_CAL_FAILED:
  146. fail();
  147. return;
  148. }
  149. } else if (_last_result != ACCEL_CAL_NOT_STARTED) {
  150. // only continuously report if we have ever completed a calibration
  151. uint32_t now = AP_HAL::millis();
  152. if (now - _last_position_request_ms > AP_ACCELCAL_POSITION_REQUEST_INTERVAL_MS) {
  153. _last_position_request_ms = now;
  154. switch (_last_result) {
  155. case ACCEL_CAL_SUCCESS:
  156. _gcs->send_accelcal_vehicle_position(ACCELCAL_VEHICLE_POS_SUCCESS);
  157. break;
  158. case ACCEL_CAL_FAILED:
  159. _gcs->send_accelcal_vehicle_position(ACCELCAL_VEHICLE_POS_FAILED);
  160. break;
  161. default:
  162. // should never hit this state
  163. break;
  164. }
  165. }
  166. }
  167. }
  168. void AP_AccelCal::start(GCS_MAVLINK *gcs)
  169. {
  170. if (gcs == nullptr || _started) {
  171. return;
  172. }
  173. _start_collect_sample = false;
  174. _num_active_calibrators = 0;
  175. AccelCalibrator *cal;
  176. for(uint8_t i=0; (cal = get_calibrator(i)); i++) {
  177. cal->clear();
  178. cal->start(ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID, 6, 0.5f);
  179. _num_active_calibrators++;
  180. }
  181. _started = true;
  182. _saving = false;
  183. _gcs = gcs;
  184. _use_gcs_snoop = true;
  185. _last_position_request_ms = 0;
  186. _step = 0;
  187. _last_result = ACCEL_CAL_NOT_STARTED;
  188. update_status();
  189. }
  190. void AP_AccelCal::success()
  191. {
  192. _printf("Calibration successful");
  193. for(uint8_t i=0 ; i < _num_clients ; i++) {
  194. _clients[i]->_acal_event_success();
  195. }
  196. _last_result = ACCEL_CAL_SUCCESS;
  197. clear();
  198. }
  199. void AP_AccelCal::cancel()
  200. {
  201. _printf("Calibration cancelled");
  202. for(uint8_t i=0 ; i < _num_clients ; i++) {
  203. _clients[i]->_acal_event_cancellation();
  204. }
  205. _last_result = ACCEL_CAL_NOT_STARTED;
  206. clear();
  207. }
  208. void AP_AccelCal::fail()
  209. {
  210. _printf("Calibration FAILED");
  211. for(uint8_t i=0 ; i < _num_clients ; i++) {
  212. _clients[i]->_acal_event_failure();
  213. }
  214. _last_result = ACCEL_CAL_FAILED;
  215. clear();
  216. }
  217. void AP_AccelCal::clear()
  218. {
  219. if (!_started) {
  220. return;
  221. }
  222. AccelCalibrator *cal;
  223. for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
  224. cal->clear();
  225. }
  226. _step = 0;
  227. _started = false;
  228. _saving = false;
  229. update_status();
  230. }
  231. void AP_AccelCal::collect_sample()
  232. {
  233. if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) {
  234. return;
  235. }
  236. for(uint8_t i=0; i<_num_clients; i++) {
  237. if (client_active(i) && !_clients[i]->_acal_get_ready_to_sample()) {
  238. _printf("Not ready to sample");
  239. return;
  240. }
  241. }
  242. AccelCalibrator *cal;
  243. for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
  244. cal->collect_sample();
  245. }
  246. _start_collect_sample = false;
  247. update_status();
  248. }
  249. void AP_AccelCal::register_client(AP_AccelCal_Client* client) {
  250. if (client == nullptr || _num_clients >= AP_ACCELCAL_MAX_NUM_CLIENTS) {
  251. return;
  252. }
  253. for(uint8_t i=0; i<_num_clients; i++) {
  254. if(_clients[i] == client) {
  255. return;
  256. }
  257. }
  258. _clients[_num_clients] = client;
  259. _num_clients++;
  260. }
  261. AccelCalibrator* AP_AccelCal::get_calibrator(uint8_t index) {
  262. AccelCalibrator* ret;
  263. for(uint8_t i=0; i<_num_clients; i++) {
  264. for(uint8_t j=0 ; (ret = _clients[i]->_acal_get_calibrator(j)) ; j++) {
  265. if (index == 0) {
  266. return ret;
  267. }
  268. index--;
  269. }
  270. }
  271. return nullptr;
  272. }
  273. void AP_AccelCal::update_status() {
  274. AccelCalibrator *cal;
  275. if (!get_calibrator(0)) {
  276. // no calibrators
  277. _status = ACCEL_CAL_NOT_STARTED;
  278. return;
  279. }
  280. for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
  281. if (cal->get_status() == ACCEL_CAL_FAILED) {
  282. _status = ACCEL_CAL_FAILED; //fail if even one of the calibration has
  283. return;
  284. }
  285. }
  286. for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
  287. if (cal->get_status() == ACCEL_CAL_COLLECTING_SAMPLE) {
  288. _status = ACCEL_CAL_COLLECTING_SAMPLE; // move to Collecting sample state if all the callibrators have
  289. return;
  290. }
  291. }
  292. for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
  293. if (cal->get_status() == ACCEL_CAL_WAITING_FOR_ORIENTATION) {
  294. _status = ACCEL_CAL_WAITING_FOR_ORIENTATION; // move to waiting for user ack for orientation confirmation
  295. return;
  296. }
  297. }
  298. for(uint8_t i=0 ; (cal = get_calibrator(i)) ; i++) {
  299. if (cal->get_status() == ACCEL_CAL_NOT_STARTED) {
  300. _status = ACCEL_CAL_NOT_STARTED; // we haven't started if all the calibrators haven't
  301. return;
  302. }
  303. }
  304. _status = ACCEL_CAL_SUCCESS; // we have succeeded calibration if all the calibrators have
  305. return;
  306. }
  307. bool AP_AccelCal::client_active(uint8_t client_num)
  308. {
  309. return (bool)_clients[client_num]->_acal_get_calibrator(0);
  310. }
  311. void AP_AccelCal::handleMessage(const mavlink_message_t &msg)
  312. {
  313. if (!_waiting_for_mavlink_ack) {
  314. return;
  315. }
  316. _waiting_for_mavlink_ack = false;
  317. if (msg.msgid == MAVLINK_MSG_ID_COMMAND_ACK) {
  318. _start_collect_sample = true;
  319. }
  320. }
  321. bool AP_AccelCal::gcs_vehicle_position(float position)
  322. {
  323. _use_gcs_snoop = false;
  324. if (_status == ACCEL_CAL_WAITING_FOR_ORIENTATION && is_equal((float) _step, position)) {
  325. _start_collect_sample = true;
  326. return true;
  327. }
  328. return false;
  329. }