CompassCalibrator.cpp 31 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893
  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 intention of a magnetometer in a compass application is to measure
  15. * Earth's magnetic field. Measurements other than those of Earth's magnetic
  16. * field are considered errors. This algorithm computes a set of correction
  17. * parameters that null out errors from various sources:
  18. *
  19. * - Sensor bias error
  20. * - "Hard iron" error caused by materials fixed to the vehicle body that
  21. * produce static magnetic fields.
  22. * - Sensor scale-factor error
  23. * - Sensor cross-axis sensitivity
  24. * - "Soft iron" error caused by materials fixed to the vehicle body that
  25. * distort magnetic fields.
  26. *
  27. * This is done by taking a set of samples that are assumed to be the product
  28. * of rotation in earth's magnetic field and fitting an offset ellipsoid to
  29. * them, determining the correction to be applied to adjust the samples into an
  30. * origin-centered sphere.
  31. *
  32. * The state machine of this library is described entirely by the
  33. * compass_cal_status_t enum, and all state transitions are managed by the
  34. * set_status function. Normally, the library is in the NOT_STARTED state. When
  35. * the start function is called, the state transitions to WAITING_TO_START,
  36. * until two conditions are met: the delay as elapsed, and the memory for the
  37. * sample buffer has been successfully allocated.
  38. * Once these conditions are met, the state transitions to RUNNING_STEP_ONE, and
  39. * samples are collected via calls to the new_sample function. These samples are
  40. * accepted or rejected based on distance to the nearest sample. The samples are
  41. * assumed to cover the surface of a sphere, and the radius of that sphere is
  42. * initialized to a conservative value. Based on a circle-packing pattern, the
  43. * minimum distance is set such that some percentage of the surface of that
  44. * sphere must be covered by samples.
  45. *
  46. * Once the sample buffer is full, a sphere fitting algorithm is run, which
  47. * computes a new sphere radius. The sample buffer is thinned of samples which
  48. * no longer meet the acceptance criteria, and the state transitions to
  49. * RUNNING_STEP_TWO. Samples continue to be collected until the buffer is full
  50. * again, the full ellipsoid fit is run, and the state transitions to either
  51. * SUCCESS or FAILED.
  52. *
  53. * The fitting algorithm used is Levenberg-Marquardt. See also:
  54. * http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm
  55. */
  56. #include "CompassCalibrator.h"
  57. #include <AP_HAL/AP_HAL.h>
  58. #include <AP_Math/AP_GeodesicGrid.h>
  59. #include <AP_AHRS/AP_AHRS.h>
  60. #include <GCS_MAVLink/GCS.h>
  61. extern const AP_HAL::HAL& hal;
  62. ////////////////////////////////////////////////////////////
  63. ///////////////////// PUBLIC INTERFACE /////////////////////
  64. ////////////////////////////////////////////////////////////
  65. CompassCalibrator::CompassCalibrator():
  66. _tolerance(COMPASS_CAL_DEFAULT_TOLERANCE),
  67. _sample_buffer(nullptr)
  68. {
  69. clear();
  70. }
  71. void CompassCalibrator::clear() {
  72. set_status(COMPASS_CAL_NOT_STARTED);
  73. }
  74. void CompassCalibrator::start(bool retry, float delay, uint16_t offset_max, uint8_t compass_idx)
  75. {
  76. if(running()) {
  77. return;
  78. }
  79. _offset_max = offset_max;
  80. _attempt = 1;
  81. _retry = retry;
  82. _delay_start_sec = delay;
  83. _start_time_ms = AP_HAL::millis();
  84. _compass_idx = compass_idx;
  85. set_status(COMPASS_CAL_WAITING_TO_START);
  86. }
  87. void CompassCalibrator::get_calibration(Vector3f &offsets, Vector3f &diagonals, Vector3f &offdiagonals) {
  88. if (_status != COMPASS_CAL_SUCCESS) {
  89. return;
  90. }
  91. offsets = _params.offset;
  92. diagonals = _params.diag;
  93. offdiagonals = _params.offdiag;
  94. }
  95. float CompassCalibrator::get_completion_percent() const {
  96. // first sampling step is 1/3rd of the progress bar
  97. // never return more than 99% unless _status is COMPASS_CAL_SUCCESS
  98. switch(_status) {
  99. case COMPASS_CAL_NOT_STARTED:
  100. case COMPASS_CAL_WAITING_TO_START:
  101. return 0.0f;
  102. case COMPASS_CAL_RUNNING_STEP_ONE:
  103. return 33.3f * _samples_collected/COMPASS_CAL_NUM_SAMPLES;
  104. case COMPASS_CAL_RUNNING_STEP_TWO:
  105. return 33.3f + 65.7f*((float)(_samples_collected-_samples_thinned)/(COMPASS_CAL_NUM_SAMPLES-_samples_thinned));
  106. case COMPASS_CAL_SUCCESS:
  107. return 100.0f;
  108. case COMPASS_CAL_FAILED:
  109. case COMPASS_CAL_BAD_ORIENTATION:
  110. default:
  111. return 0.0f;
  112. };
  113. }
  114. void CompassCalibrator::update_completion_mask(const Vector3f& v)
  115. {
  116. Matrix3f softiron{
  117. _params.diag.x, _params.offdiag.x, _params.offdiag.y,
  118. _params.offdiag.x, _params.diag.y, _params.offdiag.z,
  119. _params.offdiag.y, _params.offdiag.z, _params.diag.z
  120. };
  121. Vector3f corrected = softiron * (v + _params.offset);
  122. int section = AP_GeodesicGrid::section(corrected, true);
  123. if (section < 0) {
  124. return;
  125. }
  126. _completion_mask[section / 8] |= 1 << (section % 8);
  127. }
  128. void CompassCalibrator::update_completion_mask()
  129. {
  130. memset(_completion_mask, 0, sizeof(_completion_mask));
  131. for (int i = 0; i < _samples_collected; i++) {
  132. update_completion_mask(_sample_buffer[i].get());
  133. }
  134. }
  135. CompassCalibrator::completion_mask_t& CompassCalibrator::get_completion_mask()
  136. {
  137. return _completion_mask;
  138. }
  139. bool CompassCalibrator::check_for_timeout() {
  140. uint32_t tnow = AP_HAL::millis();
  141. if(running() && tnow - _last_sample_ms > 1000) {
  142. _retry = false;
  143. set_status(COMPASS_CAL_FAILED);
  144. return true;
  145. }
  146. return false;
  147. }
  148. void CompassCalibrator::new_sample(const Vector3f& sample) {
  149. _last_sample_ms = AP_HAL::millis();
  150. if(_status == COMPASS_CAL_WAITING_TO_START) {
  151. set_status(COMPASS_CAL_RUNNING_STEP_ONE);
  152. }
  153. if(running() && _samples_collected < COMPASS_CAL_NUM_SAMPLES && accept_sample(sample)) {
  154. update_completion_mask(sample);
  155. _sample_buffer[_samples_collected].set(sample);
  156. _sample_buffer[_samples_collected].att.set_from_ahrs();
  157. _samples_collected++;
  158. }
  159. }
  160. void CompassCalibrator::update(bool &failure) {
  161. failure = false;
  162. if(!fitting()) {
  163. return;
  164. }
  165. if(_status == COMPASS_CAL_RUNNING_STEP_ONE) {
  166. if (_fit_step >= 10) {
  167. if(is_equal(_fitness,_initial_fitness) || isnan(_fitness)) { //if true, means that fitness is diverging instead of converging
  168. set_status(COMPASS_CAL_FAILED);
  169. failure = true;
  170. }
  171. set_status(COMPASS_CAL_RUNNING_STEP_TWO);
  172. } else {
  173. if (_fit_step == 0) {
  174. calc_initial_offset();
  175. }
  176. run_sphere_fit();
  177. _fit_step++;
  178. }
  179. } else if(_status == COMPASS_CAL_RUNNING_STEP_TWO) {
  180. if (_fit_step >= 35) {
  181. if(fit_acceptable() && calculate_orientation()) {
  182. set_status(COMPASS_CAL_SUCCESS);
  183. } else {
  184. set_status(COMPASS_CAL_FAILED);
  185. failure = true;
  186. }
  187. } else if (_fit_step < 15) {
  188. run_sphere_fit();
  189. _fit_step++;
  190. } else {
  191. run_ellipsoid_fit();
  192. _fit_step++;
  193. }
  194. }
  195. }
  196. /////////////////////////////////////////////////////////////
  197. ////////////////////// PRIVATE METHODS //////////////////////
  198. /////////////////////////////////////////////////////////////
  199. bool CompassCalibrator::running() const {
  200. return _status == COMPASS_CAL_RUNNING_STEP_ONE || _status == COMPASS_CAL_RUNNING_STEP_TWO;
  201. }
  202. bool CompassCalibrator::fitting() const {
  203. return running() && _samples_collected == COMPASS_CAL_NUM_SAMPLES;
  204. }
  205. void CompassCalibrator::initialize_fit() {
  206. //initialize _fitness before starting a fit
  207. if (_samples_collected != 0) {
  208. _fitness = calc_mean_squared_residuals(_params);
  209. } else {
  210. _fitness = 1.0e30f;
  211. }
  212. _ellipsoid_lambda = 1.0f;
  213. _sphere_lambda = 1.0f;
  214. _initial_fitness = _fitness;
  215. _fit_step = 0;
  216. }
  217. void CompassCalibrator::reset_state() {
  218. _samples_collected = 0;
  219. _samples_thinned = 0;
  220. _params.radius = 200;
  221. _params.offset.zero();
  222. _params.diag = Vector3f(1.0f,1.0f,1.0f);
  223. _params.offdiag.zero();
  224. memset(_completion_mask, 0, sizeof(_completion_mask));
  225. initialize_fit();
  226. }
  227. bool CompassCalibrator::set_status(compass_cal_status_t status) {
  228. if (status != COMPASS_CAL_NOT_STARTED && _status == status) {
  229. return true;
  230. }
  231. switch(status) {
  232. case COMPASS_CAL_NOT_STARTED:
  233. reset_state();
  234. _status = COMPASS_CAL_NOT_STARTED;
  235. if(_sample_buffer != nullptr) {
  236. free(_sample_buffer);
  237. _sample_buffer = nullptr;
  238. }
  239. return true;
  240. case COMPASS_CAL_WAITING_TO_START:
  241. reset_state();
  242. _status = COMPASS_CAL_WAITING_TO_START;
  243. set_status(COMPASS_CAL_RUNNING_STEP_ONE);
  244. return true;
  245. case COMPASS_CAL_RUNNING_STEP_ONE:
  246. if(_status != COMPASS_CAL_WAITING_TO_START) {
  247. return false;
  248. }
  249. if(_attempt == 1 && (AP_HAL::millis()-_start_time_ms)*1.0e-3f < _delay_start_sec) {
  250. return false;
  251. }
  252. if (_sample_buffer == nullptr) {
  253. _sample_buffer =
  254. (CompassSample*) calloc(COMPASS_CAL_NUM_SAMPLES, sizeof(CompassSample));
  255. }
  256. if(_sample_buffer != nullptr) {
  257. initialize_fit();
  258. _status = COMPASS_CAL_RUNNING_STEP_ONE;
  259. return true;
  260. }
  261. return false;
  262. case COMPASS_CAL_RUNNING_STEP_TWO:
  263. if(_status != COMPASS_CAL_RUNNING_STEP_ONE) {
  264. return false;
  265. }
  266. thin_samples();
  267. initialize_fit();
  268. _status = COMPASS_CAL_RUNNING_STEP_TWO;
  269. return true;
  270. case COMPASS_CAL_SUCCESS:
  271. if(_status != COMPASS_CAL_RUNNING_STEP_TWO) {
  272. return false;
  273. }
  274. if(_sample_buffer != nullptr) {
  275. free(_sample_buffer);
  276. _sample_buffer = nullptr;
  277. }
  278. _status = COMPASS_CAL_SUCCESS;
  279. return true;
  280. case COMPASS_CAL_FAILED:
  281. if (_status == COMPASS_CAL_BAD_ORIENTATION) {
  282. // don't overwrite bad orientation status
  283. return false;
  284. }
  285. FALLTHROUGH;
  286. case COMPASS_CAL_BAD_ORIENTATION:
  287. if(_status == COMPASS_CAL_NOT_STARTED) {
  288. return false;
  289. }
  290. if(_retry && set_status(COMPASS_CAL_WAITING_TO_START)) {
  291. _attempt++;
  292. return true;
  293. }
  294. if(_sample_buffer != nullptr) {
  295. free(_sample_buffer);
  296. _sample_buffer = nullptr;
  297. }
  298. _status = status;
  299. return true;
  300. default:
  301. return false;
  302. };
  303. }
  304. bool CompassCalibrator::fit_acceptable() {
  305. if( !isnan(_fitness) &&
  306. _params.radius > 150 && _params.radius < 950 && //Earth's magnetic field strength range: 250-850mG
  307. fabsf(_params.offset.x) < _offset_max &&
  308. fabsf(_params.offset.y) < _offset_max &&
  309. fabsf(_params.offset.z) < _offset_max &&
  310. _params.diag.x > 0.2f && _params.diag.x < 5.0f &&
  311. _params.diag.y > 0.2f && _params.diag.y < 5.0f &&
  312. _params.diag.z > 0.2f && _params.diag.z < 5.0f &&
  313. fabsf(_params.offdiag.x) < 1.0f && //absolute of sine/cosine output cannot be greater than 1
  314. fabsf(_params.offdiag.y) < 1.0f &&
  315. fabsf(_params.offdiag.z) < 1.0f ){
  316. return _fitness <= sq(_tolerance);
  317. }
  318. return false;
  319. }
  320. void CompassCalibrator::thin_samples() {
  321. if(_sample_buffer == nullptr) {
  322. return;
  323. }
  324. _samples_thinned = 0;
  325. // shuffle the samples http://en.wikipedia.org/wiki/Fisher%E2%80%93Yates_shuffle
  326. // this is so that adjacent samples don't get sequentially eliminated
  327. for(uint16_t i=_samples_collected-1; i>=1; i--) {
  328. uint16_t j = get_random16() % (i+1);
  329. CompassSample temp = _sample_buffer[i];
  330. _sample_buffer[i] = _sample_buffer[j];
  331. _sample_buffer[j] = temp;
  332. }
  333. for(uint16_t i=0; i < _samples_collected; i++) {
  334. if(!accept_sample(_sample_buffer[i])) {
  335. _sample_buffer[i] = _sample_buffer[_samples_collected-1];
  336. _samples_collected --;
  337. _samples_thinned ++;
  338. }
  339. }
  340. update_completion_mask();
  341. }
  342. /*
  343. * The sample acceptance distance is determined as follows:
  344. * For any regular polyhedron with triangular faces, the angle theta subtended
  345. * by two closest points is defined as
  346. *
  347. * theta = arccos(cos(A)/(1-cos(A)))
  348. *
  349. * Where:
  350. * A = (4pi/F + pi)/3
  351. * and
  352. * F = 2V - 4 is the number of faces for the polyhedron in consideration,
  353. * which depends on the number of vertices V
  354. *
  355. * The above equation was proved after solving for spherical triangular excess
  356. * and related equations.
  357. */
  358. bool CompassCalibrator::accept_sample(const Vector3f& sample)
  359. {
  360. static const uint16_t faces = (2 * COMPASS_CAL_NUM_SAMPLES - 4);
  361. static const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;
  362. static const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));
  363. if(_sample_buffer == nullptr) {
  364. return false;
  365. }
  366. float min_distance = _params.radius * 2*sinf(theta/2);
  367. for (uint16_t i = 0; i<_samples_collected; i++){
  368. float distance = (sample - _sample_buffer[i].get()).length();
  369. if(distance < min_distance) {
  370. return false;
  371. }
  372. }
  373. return true;
  374. }
  375. bool CompassCalibrator::accept_sample(const CompassSample& sample) {
  376. return accept_sample(sample.get());
  377. }
  378. float CompassCalibrator::calc_residual(const Vector3f& sample, const param_t& params) const {
  379. Matrix3f softiron(
  380. params.diag.x , params.offdiag.x , params.offdiag.y,
  381. params.offdiag.x , params.diag.y , params.offdiag.z,
  382. params.offdiag.y , params.offdiag.z , params.diag.z
  383. );
  384. return params.radius - (softiron*(sample+params.offset)).length();
  385. }
  386. float CompassCalibrator::calc_mean_squared_residuals() const
  387. {
  388. return calc_mean_squared_residuals(_params);
  389. }
  390. float CompassCalibrator::calc_mean_squared_residuals(const param_t& params) const
  391. {
  392. if(_sample_buffer == nullptr || _samples_collected == 0) {
  393. return 1.0e30f;
  394. }
  395. float sum = 0.0f;
  396. for(uint16_t i=0; i < _samples_collected; i++){
  397. Vector3f sample = _sample_buffer[i].get();
  398. float resid = calc_residual(sample, params);
  399. sum += sq(resid);
  400. }
  401. sum /= _samples_collected;
  402. return sum;
  403. }
  404. void CompassCalibrator::calc_sphere_jacob(const Vector3f& sample, const param_t& params, float* ret) const{
  405. const Vector3f &offset = params.offset;
  406. const Vector3f &diag = params.diag;
  407. const Vector3f &offdiag = params.offdiag;
  408. Matrix3f softiron(
  409. diag.x , offdiag.x , offdiag.y,
  410. offdiag.x , diag.y , offdiag.z,
  411. offdiag.y , offdiag.z , diag.z
  412. );
  413. float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));
  414. float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));
  415. float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));
  416. float length = (softiron*(sample+offset)).length();
  417. // 0: partial derivative (radius wrt fitness fn) fn operated on sample
  418. ret[0] = 1.0f;
  419. // 1-3: partial derivative (offsets wrt fitness fn) fn operated on sample
  420. ret[1] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);
  421. ret[2] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);
  422. ret[3] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);
  423. }
  424. void CompassCalibrator::calc_initial_offset()
  425. {
  426. // Set initial offset to the average value of the samples
  427. _params.offset.zero();
  428. for(uint16_t k = 0; k<_samples_collected; k++) {
  429. _params.offset -= _sample_buffer[k].get();
  430. }
  431. _params.offset /= _samples_collected;
  432. }
  433. void CompassCalibrator::run_sphere_fit()
  434. {
  435. if(_sample_buffer == nullptr) {
  436. return;
  437. }
  438. const float lma_damping = 10.0f;
  439. float fitness = _fitness;
  440. float fit1, fit2;
  441. param_t fit1_params, fit2_params;
  442. fit1_params = fit2_params = _params;
  443. float JTJ[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
  444. float JTJ2[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
  445. float JTFI[COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
  446. // Gauss Newton Part common for all kind of extensions including LM
  447. for(uint16_t k = 0; k<_samples_collected; k++) {
  448. Vector3f sample = _sample_buffer[k].get();
  449. float sphere_jacob[COMPASS_CAL_NUM_SPHERE_PARAMS];
  450. calc_sphere_jacob(sample, fit1_params, sphere_jacob);
  451. for(uint8_t i = 0;i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {
  452. // compute JTJ
  453. for(uint8_t j = 0; j < COMPASS_CAL_NUM_SPHERE_PARAMS; j++) {
  454. JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j];
  455. JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j]; //a backup JTJ for LM
  456. }
  457. // compute JTFI
  458. JTFI[i] += sphere_jacob[i] * calc_residual(sample, fit1_params);
  459. }
  460. }
  461. //------------------------Levenberg-Marquardt-part-starts-here---------------------------------//
  462. //refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter
  463. for(uint8_t i = 0; i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {
  464. JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda;
  465. JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda/lma_damping;
  466. }
  467. if(!inverse(JTJ, JTJ, 4)) {
  468. return;
  469. }
  470. if(!inverse(JTJ2, JTJ2, 4)) {
  471. return;
  472. }
  473. for(uint8_t row=0; row < COMPASS_CAL_NUM_SPHERE_PARAMS; row++) {
  474. for(uint8_t col=0; col < COMPASS_CAL_NUM_SPHERE_PARAMS; col++) {
  475. fit1_params.get_sphere_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];
  476. fit2_params.get_sphere_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];
  477. }
  478. }
  479. fit1 = calc_mean_squared_residuals(fit1_params);
  480. fit2 = calc_mean_squared_residuals(fit2_params);
  481. if(fit1 > _fitness && fit2 > _fitness){
  482. _sphere_lambda *= lma_damping;
  483. } else if(fit2 < _fitness && fit2 < fit1) {
  484. _sphere_lambda /= lma_damping;
  485. fit1_params = fit2_params;
  486. fitness = fit2;
  487. } else if(fit1 < _fitness){
  488. fitness = fit1;
  489. }
  490. //--------------------Levenberg-Marquardt-part-ends-here--------------------------------//
  491. if(!isnan(fitness) && fitness < _fitness) {
  492. _fitness = fitness;
  493. _params = fit1_params;
  494. update_completion_mask();
  495. }
  496. }
  497. void CompassCalibrator::calc_ellipsoid_jacob(const Vector3f& sample, const param_t& params, float* ret) const{
  498. const Vector3f &offset = params.offset;
  499. const Vector3f &diag = params.diag;
  500. const Vector3f &offdiag = params.offdiag;
  501. Matrix3f softiron(
  502. diag.x , offdiag.x , offdiag.y,
  503. offdiag.x , diag.y , offdiag.z,
  504. offdiag.y , offdiag.z , diag.z
  505. );
  506. float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));
  507. float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));
  508. float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));
  509. float length = (softiron*(sample+offset)).length();
  510. // 0-2: partial derivative (offset wrt fitness fn) fn operated on sample
  511. ret[0] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);
  512. ret[1] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);
  513. ret[2] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);
  514. // 3-5: partial derivative (diag offset wrt fitness fn) fn operated on sample
  515. ret[3] = -1.0f * ((sample.x + offset.x) * A)/length;
  516. ret[4] = -1.0f * ((sample.y + offset.y) * B)/length;
  517. ret[5] = -1.0f * ((sample.z + offset.z) * C)/length;
  518. // 6-8: partial derivative (off-diag offset wrt fitness fn) fn operated on sample
  519. ret[6] = -1.0f * (((sample.y + offset.y) * A) + ((sample.x + offset.x) * B))/length;
  520. ret[7] = -1.0f * (((sample.z + offset.z) * A) + ((sample.x + offset.x) * C))/length;
  521. ret[8] = -1.0f * (((sample.z + offset.z) * B) + ((sample.y + offset.y) * C))/length;
  522. }
  523. void CompassCalibrator::run_ellipsoid_fit()
  524. {
  525. if(_sample_buffer == nullptr) {
  526. return;
  527. }
  528. const float lma_damping = 10.0f;
  529. float fitness = _fitness;
  530. float fit1, fit2;
  531. param_t fit1_params, fit2_params;
  532. fit1_params = fit2_params = _params;
  533. float JTJ[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
  534. float JTJ2[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
  535. float JTFI[COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
  536. // Gauss Newton Part common for all kind of extensions including LM
  537. for(uint16_t k = 0; k<_samples_collected; k++) {
  538. Vector3f sample = _sample_buffer[k].get();
  539. float ellipsoid_jacob[COMPASS_CAL_NUM_ELLIPSOID_PARAMS];
  540. calc_ellipsoid_jacob(sample, fit1_params, ellipsoid_jacob);
  541. for(uint8_t i = 0;i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {
  542. // compute JTJ
  543. for(uint8_t j = 0; j < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; j++) {
  544. JTJ [i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];
  545. JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];
  546. }
  547. // compute JTFI
  548. JTFI[i] += ellipsoid_jacob[i] * calc_residual(sample, fit1_params);
  549. }
  550. }
  551. //------------------------Levenberg-Marquardt-part-starts-here---------------------------------//
  552. //refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter
  553. for(uint8_t i = 0; i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {
  554. JTJ[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda;
  555. JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda/lma_damping;
  556. }
  557. if(!inverse(JTJ, JTJ, 9)) {
  558. return;
  559. }
  560. if(!inverse(JTJ2, JTJ2, 9)) {
  561. return;
  562. }
  563. for(uint8_t row=0; row < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; row++) {
  564. for(uint8_t col=0; col < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; col++) {
  565. fit1_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];
  566. fit2_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];
  567. }
  568. }
  569. fit1 = calc_mean_squared_residuals(fit1_params);
  570. fit2 = calc_mean_squared_residuals(fit2_params);
  571. if(fit1 > _fitness && fit2 > _fitness){
  572. _ellipsoid_lambda *= lma_damping;
  573. } else if(fit2 < _fitness && fit2 < fit1) {
  574. _ellipsoid_lambda /= lma_damping;
  575. fit1_params = fit2_params;
  576. fitness = fit2;
  577. } else if(fit1 < _fitness){
  578. fitness = fit1;
  579. }
  580. //--------------------Levenberg-part-ends-here--------------------------------//
  581. if(fitness < _fitness) {
  582. _fitness = fitness;
  583. _params = fit1_params;
  584. update_completion_mask();
  585. }
  586. }
  587. //////////////////////////////////////////////////////////
  588. //////////// CompassSample public interface //////////////
  589. //////////////////////////////////////////////////////////
  590. #define COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(__X) ((int16_t)constrain_float(roundf(__X*8.0f), INT16_MIN, INT16_MAX))
  591. #define COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(__X) (__X/8.0f)
  592. Vector3f CompassCalibrator::CompassSample::get() const {
  593. return Vector3f(COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(x),
  594. COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(y),
  595. COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(z));
  596. }
  597. void CompassCalibrator::CompassSample::set(const Vector3f &in) {
  598. x = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.x);
  599. y = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.y);
  600. z = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.z);
  601. }
  602. void CompassCalibrator::AttitudeSample::set_from_ahrs(void) {
  603. const Matrix3f &dcm = AP::ahrs().get_DCM_rotation_body_to_ned();
  604. float roll_rad, pitch_rad, yaw_rad;
  605. dcm.to_euler(&roll_rad, &pitch_rad, &yaw_rad);
  606. roll = constrain_int16(127 * (roll_rad / M_PI), -127, 127);
  607. pitch = constrain_int16(127 * (pitch_rad / M_PI_2), -127, 127);
  608. yaw = constrain_int16(127 * (yaw_rad / M_PI), -127, 127);
  609. }
  610. Matrix3f CompassCalibrator::AttitudeSample::get_rotmat(void) {
  611. float roll_rad, pitch_rad, yaw_rad;
  612. roll_rad = roll * (M_PI / 127);
  613. pitch_rad = pitch * (M_PI_2 / 127);
  614. yaw_rad = yaw * (M_PI / 127);
  615. Matrix3f dcm;
  616. dcm.from_euler(roll_rad, pitch_rad, yaw_rad);
  617. return dcm;
  618. }
  619. /*
  620. calculate the implied earth field for a compass sample and compass
  621. rotation. This is used to check for consistency between
  622. samples.
  623. If the orientation is correct then when rotated the same (or
  624. similar) earth field should be given for all samples.
  625. Note that this earth field uses an arbitrary north reference, so it
  626. may not match the true earth field.
  627. */
  628. Vector3f CompassCalibrator::calculate_earth_field(CompassSample &sample, enum Rotation r)
  629. {
  630. Vector3f v = sample.get();
  631. // convert the sample back to sensor frame
  632. v.rotate_inverse(_orientation);
  633. // rotate to body frame for this rotation
  634. v.rotate(r);
  635. // apply offsets, rotating them for the orientation we are testing
  636. Vector3f rot_offsets = _params.offset;
  637. rot_offsets.rotate_inverse(_orientation);
  638. rot_offsets.rotate(r);
  639. v += rot_offsets;
  640. // rotate the sample from body frame back to earth frame
  641. Matrix3f rot = sample.att.get_rotmat();
  642. Vector3f efield = rot * v;
  643. // earth field is the mag sample in earth frame
  644. return efield;
  645. }
  646. /*
  647. calculate compass orientation using the attitude estimate associated
  648. with each sample, and fix orientation on external compasses if
  649. the feature is enabled
  650. */
  651. bool CompassCalibrator::calculate_orientation(void)
  652. {
  653. if (!_check_orientation) {
  654. // we are not checking orientation
  655. return true;
  656. }
  657. // this function is very slow
  658. EXPECT_DELAY_MS(1000);
  659. float variance[ROTATION_MAX] {};
  660. for (enum Rotation r = ROTATION_NONE; r<ROTATION_MAX; r = (enum Rotation)(r+1)) {
  661. // calculate the average implied earth field across all samples
  662. Vector3f total_ef {};
  663. for (uint32_t i=0; i<_samples_collected; i++) {
  664. Vector3f efield = calculate_earth_field(_sample_buffer[i], r);
  665. total_ef += efield;
  666. }
  667. Vector3f avg_efield = total_ef / _samples_collected;
  668. // now calculate the square error for this rotation against the average earth field
  669. for (uint32_t i=0; i<_samples_collected; i++) {
  670. Vector3f efield = calculate_earth_field(_sample_buffer[i], r);
  671. float err = (efield - avg_efield).length_squared();
  672. // divide by number of samples collected to get the variance
  673. variance[r] += err / _samples_collected;
  674. }
  675. }
  676. // find the rotation with the lowest variance
  677. enum Rotation besti = ROTATION_NONE;
  678. float bestv = variance[0];
  679. for (enum Rotation r = ROTATION_NONE; r<ROTATION_MAX; r = (enum Rotation)(r+1)) {
  680. if (variance[r] < bestv) {
  681. bestv = variance[r];
  682. besti = r;
  683. }
  684. }
  685. // consider this a pass if the best orientation is 2x better
  686. // variance than 2nd best
  687. const float variance_threshold = 2.0;
  688. float second_best = besti==ROTATION_NONE?variance[1]:variance[0];
  689. enum Rotation besti2 = ROTATION_NONE;
  690. for (enum Rotation r = ROTATION_NONE; r<ROTATION_MAX; r = (enum Rotation)(r+1)) {
  691. if (!rotation_equal(besti, r)) {
  692. if (variance[r] < second_best) {
  693. second_best = variance[r];
  694. besti2 = r;
  695. }
  696. }
  697. }
  698. _orientation_confidence = second_best/bestv;
  699. bool pass;
  700. if (besti == _orientation) {
  701. // if the orientation matched then allow for a low threshold
  702. pass = true;
  703. } else {
  704. pass = _orientation_confidence > variance_threshold;
  705. }
  706. if (!pass) {
  707. gcs().send_text(MAV_SEVERITY_CRITICAL, "Mag(%u) bad orientation: %u/%u %.1f", _compass_idx,
  708. besti, besti2, (double)_orientation_confidence);
  709. } else if (besti == _orientation) {
  710. // no orientation change
  711. gcs().send_text(MAV_SEVERITY_INFO, "Mag(%u) good orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);
  712. } else if (!_is_external || !_fix_orientation) {
  713. gcs().send_text(MAV_SEVERITY_CRITICAL, "Mag(%u) internal bad orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);
  714. } else {
  715. gcs().send_text(MAV_SEVERITY_INFO, "Mag(%u) new orientation: %u was %u %.1f", _compass_idx, besti, _orientation, (double)_orientation_confidence);
  716. }
  717. if (!pass) {
  718. set_status(COMPASS_CAL_BAD_ORIENTATION);
  719. return false;
  720. }
  721. if (_orientation == besti) {
  722. // no orientation change
  723. return true;
  724. }
  725. if (!_is_external || !_fix_orientation) {
  726. // we won't change the orientation, but we set _orientation
  727. // for reporting purposes
  728. _orientation = besti;
  729. set_status(COMPASS_CAL_BAD_ORIENTATION);
  730. return false;
  731. }
  732. // correct the offsets for the new orientation
  733. Vector3f rot_offsets = _params.offset;
  734. rot_offsets.rotate_inverse(_orientation);
  735. rot_offsets.rotate(besti);
  736. _params.offset = rot_offsets;
  737. // rotate the samples for the new orientation
  738. for (uint32_t i=0; i<_samples_collected; i++) {
  739. Vector3f s = _sample_buffer[i].get();
  740. s.rotate_inverse(_orientation);
  741. s.rotate(besti);
  742. _sample_buffer[i].set(s);
  743. }
  744. _orientation = besti;
  745. // re-run the fit to get the diagonals and off-diagonals for the
  746. // new orientation
  747. initialize_fit();
  748. run_sphere_fit();
  749. run_ellipsoid_fit();
  750. return fit_acceptable();
  751. }