AccelCalibrator.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466
  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. // Authored by Jonathan Challinger, 3D Robotics Inc.
  14. #include "AccelCalibrator.h"
  15. #include <stdio.h>
  16. #include <AP_HAL/AP_HAL.h>
  17. const extern AP_HAL::HAL& hal;
  18. /*
  19. * TODO
  20. * - time out when not receiving samples
  21. */
  22. ////////////////////////////////////////////////////////////
  23. ///////////////////// PUBLIC INTERFACE /////////////////////
  24. ////////////////////////////////////////////////////////////
  25. AccelCalibrator::AccelCalibrator() :
  26. _conf_tolerance(ACCEL_CAL_TOLERANCE),
  27. _sample_buffer(nullptr)
  28. {
  29. clear();
  30. }
  31. /*
  32. Select options, initialise variables and initiate accel calibration
  33. Options:
  34. Fit Type: Will assume that if accelerometer static samples around all possible orientatio
  35. are spread in space will cover a surface of AXIS_ALIGNED_ELLIPSOID or any general
  36. ELLIPSOID as chosen
  37. Num Samples: Number of samples user should will be gathering, please note that with type of surface
  38. chosen the minimum number of samples required will vary, for instance in the case of AXIS
  39. ALIGNED ELLIPSOID atleast 6 distinct samples are required while for generic ELLIPSOIDAL fit
  40. which will include calculation of offdiagonal parameters too requires atleast 8 parameters
  41. to form a distinct ELLIPSOID
  42. Sample Time: Time over which the samples will be gathered and averaged to add to a single sample for least
  43. square regression
  44. offset,diag,offdiag: initial parameter values for LSQ calculation
  45. */
  46. void AccelCalibrator::start(enum accel_cal_fit_type_t fit_type, uint8_t num_samples, float sample_time) {
  47. start(fit_type, num_samples, sample_time, Vector3f(0,0,0), Vector3f(1,1,1), Vector3f(0,0,0));
  48. }
  49. void AccelCalibrator::start(enum accel_cal_fit_type_t fit_type, uint8_t num_samples, float sample_time, Vector3f offset, Vector3f diag, Vector3f offdiag) {
  50. if (_status == ACCEL_CAL_FAILED || _status == ACCEL_CAL_SUCCESS) {
  51. clear();
  52. }
  53. if (_status != ACCEL_CAL_NOT_STARTED) {
  54. return;
  55. }
  56. _conf_num_samples = num_samples;
  57. _conf_sample_time = sample_time;
  58. _conf_fit_type = fit_type;
  59. const uint16_t faces = 2*_conf_num_samples-4;
  60. const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;
  61. const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));
  62. _min_sample_dist = GRAVITY_MSS * 2*sinf(theta/2);
  63. _param.s.offset = offset;
  64. _param.s.diag = diag;
  65. _param.s.offdiag = offdiag;
  66. switch (_conf_fit_type) {
  67. case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:
  68. if (_conf_num_samples < 6) {
  69. set_status(ACCEL_CAL_FAILED);
  70. return;
  71. }
  72. break;
  73. case ACCEL_CAL_ELLIPSOID:
  74. if (_conf_num_samples < 8) {
  75. set_status(ACCEL_CAL_FAILED);
  76. return;
  77. }
  78. break;
  79. }
  80. set_status(ACCEL_CAL_WAITING_FOR_ORIENTATION);
  81. }
  82. // set Accel calibrator status to make itself ready for future accel cals
  83. void AccelCalibrator::clear() {
  84. set_status(ACCEL_CAL_NOT_STARTED);
  85. }
  86. // returns true if accel calibrator is running
  87. bool AccelCalibrator::running() {
  88. return _status == ACCEL_CAL_WAITING_FOR_ORIENTATION || _status == ACCEL_CAL_COLLECTING_SAMPLE;
  89. }
  90. // set Accel calibrator to start collecting samples in the next cycle
  91. void AccelCalibrator::collect_sample() {
  92. set_status(ACCEL_CAL_COLLECTING_SAMPLE);
  93. }
  94. // collect and avg sample to be passed onto LSQ estimator after all requisite orientations are done
  95. void AccelCalibrator::new_sample(const Vector3f& delta_velocity, float dt) {
  96. if (_status != ACCEL_CAL_COLLECTING_SAMPLE) {
  97. return;
  98. }
  99. if (_samples_collected >= _conf_num_samples) {
  100. set_status(ACCEL_CAL_FAILED);
  101. return;
  102. }
  103. _sample_buffer[_samples_collected].delta_velocity += delta_velocity;
  104. _sample_buffer[_samples_collected].delta_time += dt;
  105. _last_samp_frag_collected_ms = AP_HAL::millis();
  106. if (_sample_buffer[_samples_collected].delta_time > _conf_sample_time) {
  107. Vector3f sample = _sample_buffer[_samples_collected].delta_velocity/_sample_buffer[_samples_collected].delta_time;
  108. if (!accept_sample(sample)) {
  109. set_status(ACCEL_CAL_FAILED);
  110. return;
  111. }
  112. _samples_collected++;
  113. if (_samples_collected >= _conf_num_samples) {
  114. run_fit(MAX_ITERATIONS, _fitness);
  115. if (_fitness < _conf_tolerance && accept_result()) {
  116. set_status(ACCEL_CAL_SUCCESS);
  117. } else {
  118. set_status(ACCEL_CAL_FAILED);
  119. }
  120. } else {
  121. set_status(ACCEL_CAL_WAITING_FOR_ORIENTATION);
  122. }
  123. }
  124. }
  125. // determines if the result is acceptable
  126. bool AccelCalibrator::accept_result() const {
  127. if (fabsf(_param.s.offset.x) > GRAVITY_MSS ||
  128. fabsf(_param.s.offset.y) > GRAVITY_MSS ||
  129. fabsf(_param.s.offset.z) > GRAVITY_MSS ||
  130. _param.s.diag.x < 0.8f || _param.s.diag.x > 1.2f ||
  131. _param.s.diag.y < 0.8f || _param.s.diag.y > 1.2f ||
  132. _param.s.diag.z < 0.8f || _param.s.diag.z > 1.2f) {
  133. return false;
  134. } else {
  135. return true;
  136. }
  137. }
  138. // interface for LSq estimator to read sample buffer sent after conversion from delta velocity
  139. // to averaged acc over time
  140. bool AccelCalibrator::get_sample(uint8_t i, Vector3f& s) const {
  141. if (i >= _samples_collected) {
  142. return false;
  143. }
  144. s = _sample_buffer[i].delta_velocity / _sample_buffer[i].delta_time;
  145. return true;
  146. }
  147. // returns truen and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure
  148. // returns false if no correct parameter exists to be applied along with existing sample without corrections
  149. bool AccelCalibrator::get_sample_corrected(uint8_t i, Vector3f& s) const {
  150. if (_status != ACCEL_CAL_SUCCESS || !get_sample(i,s)) {
  151. return false;
  152. }
  153. Matrix3f M (
  154. _param.s.diag.x , _param.s.offdiag.x , _param.s.offdiag.y,
  155. _param.s.offdiag.x , _param.s.diag.y , _param.s.offdiag.z,
  156. _param.s.offdiag.y , _param.s.offdiag.z , _param.s.diag.z
  157. );
  158. s = M*(s+_param.s.offset);
  159. return true;
  160. }
  161. // checks if no new sample has been received for considerable amount of time
  162. void AccelCalibrator::check_for_timeout() {
  163. const uint32_t timeout = _conf_sample_time*2*1000 + 500;
  164. if (_status == ACCEL_CAL_COLLECTING_SAMPLE && AP_HAL::millis() - _last_samp_frag_collected_ms > timeout) {
  165. set_status(ACCEL_CAL_FAILED);
  166. }
  167. }
  168. // returns spherical fit paramteters
  169. void AccelCalibrator::get_calibration(Vector3f& offset) const {
  170. offset = -_param.s.offset;
  171. }
  172. // returns axis aligned ellipsoidal fit parameters
  173. void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag) const {
  174. offset = -_param.s.offset;
  175. diag = _param.s.diag;
  176. }
  177. // returns generic ellipsoidal fit parameters
  178. void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag, Vector3f& offdiag) const {
  179. offset = -_param.s.offset;
  180. diag = _param.s.diag;
  181. offdiag = _param.s.offdiag;
  182. }
  183. /////////////////////////////////////////////////////////////
  184. ////////////////////// PRIVATE METHODS //////////////////////
  185. /////////////////////////////////////////////////////////////
  186. /*
  187. The sample acceptance distance is determined as follows:
  188. For any regular polyhedron with triangular faces, the angle theta subtended
  189. by two closest points is defined as
  190. theta = arccos(cos(A)/(1-cos(A)))
  191. Where:
  192. A = (4pi/F + pi)/3
  193. and
  194. F = 2V - 4 is the number of faces for the polyhedron in consideration,
  195. which depends on the number of vertices V
  196. The above equation was proved after solving for spherical triangular excess
  197. and related equations.
  198. */
  199. bool AccelCalibrator::accept_sample(const Vector3f& sample)
  200. {
  201. if (_sample_buffer == nullptr) {
  202. return false;
  203. }
  204. for(uint8_t i=0; i < _samples_collected; i++) {
  205. Vector3f other_sample;
  206. get_sample(i, other_sample);
  207. if ((other_sample - sample).length() < _min_sample_dist){
  208. return false;
  209. }
  210. }
  211. return true;
  212. }
  213. // sets status of calibrator and takes appropriate actions
  214. void AccelCalibrator::set_status(enum accel_cal_status_t status) {
  215. switch (status) {
  216. case ACCEL_CAL_NOT_STARTED:
  217. //Calibrator not started
  218. _status = ACCEL_CAL_NOT_STARTED;
  219. _samples_collected = 0;
  220. if (_sample_buffer != nullptr) {
  221. free(_sample_buffer);
  222. _sample_buffer = nullptr;
  223. }
  224. break;
  225. case ACCEL_CAL_WAITING_FOR_ORIENTATION:
  226. //Callibrator has been started and is waiting for user to ack after orientation setting
  227. if (!running()) {
  228. _samples_collected = 0;
  229. if (_sample_buffer == nullptr) {
  230. _sample_buffer = (struct AccelSample*)calloc(_conf_num_samples,sizeof(struct AccelSample));
  231. if (_sample_buffer == nullptr) {
  232. set_status(ACCEL_CAL_FAILED);
  233. break;
  234. }
  235. }
  236. }
  237. if (_samples_collected >= _conf_num_samples) {
  238. break;
  239. }
  240. _status = ACCEL_CAL_WAITING_FOR_ORIENTATION;
  241. break;
  242. case ACCEL_CAL_COLLECTING_SAMPLE:
  243. // Calibrator is waiting on collecting samples from acceleromter for amount of
  244. // time as requested by user/GCS
  245. if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) {
  246. break;
  247. }
  248. _last_samp_frag_collected_ms = AP_HAL::millis();
  249. _status = ACCEL_CAL_COLLECTING_SAMPLE;
  250. break;
  251. case ACCEL_CAL_SUCCESS:
  252. // Calibrator has successfully fitted the samples to user requested surface model
  253. // and has passed tolerance test
  254. if (_status != ACCEL_CAL_COLLECTING_SAMPLE) {
  255. break;
  256. }
  257. _status = ACCEL_CAL_SUCCESS;
  258. break;
  259. case ACCEL_CAL_FAILED:
  260. // Calibration has failed with reasons that can range from
  261. // bad sample data leading to faillure in tolerance test to lack of distinct samples
  262. if (_status == ACCEL_CAL_NOT_STARTED) {
  263. break;
  264. }
  265. _status = ACCEL_CAL_FAILED;
  266. break;
  267. };
  268. }
  269. /*
  270. Run Gauss Newton fitting algorithm over the sample space and come up with offsets, diagonal/scale factors
  271. and crosstalk/offdiagonal parameters
  272. */
  273. void AccelCalibrator::run_fit(uint8_t max_iterations, float& fitness)
  274. {
  275. if (_sample_buffer == nullptr) {
  276. return;
  277. }
  278. fitness = calc_mean_squared_residuals(_param.s);
  279. float min_fitness = fitness;
  280. union param_u fit_param = _param;
  281. uint8_t num_iterations = 0;
  282. while(num_iterations < max_iterations) {
  283. float JTJ[ACCEL_CAL_MAX_NUM_PARAMS*ACCEL_CAL_MAX_NUM_PARAMS] {};
  284. VectorP JTFI;
  285. for(uint16_t k = 0; k<_samples_collected; k++) {
  286. Vector3f sample;
  287. get_sample(k, sample);
  288. VectorN<float,ACCEL_CAL_MAX_NUM_PARAMS> jacob;
  289. calc_jacob(sample, fit_param.s, jacob);
  290. for(uint8_t i = 0; i < get_num_params(); i++) {
  291. // compute JTJ
  292. for(uint8_t j = 0; j < get_num_params(); j++) {
  293. JTJ[i*get_num_params()+j] += jacob[i] * jacob[j];
  294. }
  295. // compute JTFI
  296. JTFI[i] += jacob[i] * calc_residual(sample, fit_param.s);
  297. }
  298. }
  299. if (!inverse(JTJ, JTJ, get_num_params())) {
  300. return;
  301. }
  302. for(uint8_t row=0; row < get_num_params(); row++) {
  303. for(uint8_t col=0; col < get_num_params(); col++) {
  304. fit_param.a[row] -= JTFI[col] * JTJ[row*get_num_params()+col];
  305. }
  306. }
  307. fitness = calc_mean_squared_residuals(fit_param.s);
  308. if (isnan(fitness) || isinf(fitness)) {
  309. return;
  310. }
  311. if (fitness < min_fitness) {
  312. min_fitness = fitness;
  313. _param = fit_param;
  314. }
  315. num_iterations++;
  316. }
  317. }
  318. // calculates residual from samples(corrected using supplied parameter) to gravity
  319. // used to create Fitness column matrix
  320. float AccelCalibrator::calc_residual(const Vector3f& sample, const struct param_t& params) const {
  321. Matrix3f M (
  322. params.diag.x , params.offdiag.x , params.offdiag.y,
  323. params.offdiag.x , params.diag.y , params.offdiag.z,
  324. params.offdiag.y , params.offdiag.z , params.diag.z
  325. );
  326. return GRAVITY_MSS - (M*(sample+params.offset)).length();
  327. }
  328. // calculated the total mean squared fitness of all the collected samples using parameters
  329. // converged to LSq estimator so far
  330. float AccelCalibrator::calc_mean_squared_residuals() const
  331. {
  332. return calc_mean_squared_residuals(_param.s);
  333. }
  334. // calculated the total mean squared fitness of all the collected samples using parameters
  335. // supplied
  336. float AccelCalibrator::calc_mean_squared_residuals(const struct param_t& params) const
  337. {
  338. if (_sample_buffer == nullptr || _samples_collected == 0) {
  339. return 1.0e30f;
  340. }
  341. float sum = 0.0f;
  342. for(uint16_t i=0; i < _samples_collected; i++){
  343. Vector3f sample;
  344. get_sample(i, sample);
  345. float resid = calc_residual(sample, params);
  346. sum += sq(resid);
  347. }
  348. sum /= _samples_collected;
  349. return sum;
  350. }
  351. // calculate jacobian, a matrix that defines relation to variation in fitness with variation in each of the parameters
  352. // this is used in LSq estimator to adjust variation in parameter to be used for next iteration of LSq
  353. void AccelCalibrator::calc_jacob(const Vector3f& sample, const struct param_t& params, VectorP &ret) const {
  354. switch (_conf_fit_type) {
  355. case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:
  356. case ACCEL_CAL_ELLIPSOID: {
  357. const Vector3f &offset = params.offset;
  358. const Vector3f &diag = params.diag;
  359. const Vector3f &offdiag = params.offdiag;
  360. Matrix3f M(
  361. diag.x , offdiag.x , offdiag.y,
  362. offdiag.x , diag.y , offdiag.z,
  363. offdiag.y , offdiag.z , diag.z
  364. );
  365. float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));
  366. float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));
  367. float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));
  368. float length = (M*(sample+offset)).length();
  369. // 0-2: offsets
  370. ret[0] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);
  371. ret[1] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);
  372. ret[2] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);
  373. // 3-5: diagonals
  374. ret[3] = -1.0f * ((sample.x + offset.x) * A)/length;
  375. ret[4] = -1.0f * ((sample.y + offset.y) * B)/length;
  376. ret[5] = -1.0f * ((sample.z + offset.z) * C)/length;
  377. // 6-8: off-diagonals
  378. ret[6] = -1.0f * (((sample.y + offset.y) * A) + ((sample.x + offset.x) * B))/length;
  379. ret[7] = -1.0f * (((sample.z + offset.z) * A) + ((sample.x + offset.x) * C))/length;
  380. ret[8] = -1.0f * (((sample.z + offset.z) * B) + ((sample.y + offset.y) * C))/length;
  381. return;
  382. }
  383. };
  384. }
  385. // returns number of parameters are required for selected Fit type
  386. uint8_t AccelCalibrator::get_num_params() const {
  387. switch (_conf_fit_type) {
  388. case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:
  389. return 6;
  390. case ACCEL_CAL_ELLIPSOID:
  391. return 9;
  392. default:
  393. return 6;
  394. }
  395. }