APM:Libraries
CompassCalibrator.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14 */
15 
16 /*
17  * The intention of a magnetometer in a compass application is to measure
18  * Earth's magnetic field. Measurements other than those of Earth's magnetic
19  * field are considered errors. This algorithm computes a set of correction
20  * parameters that null out errors from various sources:
21  *
22  * - Sensor bias error
23  * - "Hard iron" error caused by materials fixed to the vehicle body that
24  * produce static magnetic fields.
25  * - Sensor scale-factor error
26  * - Sensor cross-axis sensitivity
27  * - "Soft iron" error caused by materials fixed to the vehicle body that
28  * distort magnetic fields.
29  *
30  * This is done by taking a set of samples that are assumed to be the product
31  * of rotation in earth's magnetic field and fitting an offset ellipsoid to
32  * them, determining the correction to be applied to adjust the samples into an
33  * origin-centered sphere.
34  *
35  * The state machine of this library is described entirely by the
36  * compass_cal_status_t enum, and all state transitions are managed by the
37  * set_status function. Normally, the library is in the NOT_STARTED state. When
38  * the start function is called, the state transitions to WAITING_TO_START,
39  * until two conditions are met: the delay as elapsed, and the memory for the
40  * sample buffer has been successfully allocated.
41  * Once these conditions are met, the state transitions to RUNNING_STEP_ONE, and
42  * samples are collected via calls to the new_sample function. These samples are
43  * accepted or rejected based on distance to the nearest sample. The samples are
44  * assumed to cover the surface of a sphere, and the radius of that sphere is
45  * initialized to a conservative value. Based on a circle-packing pattern, the
46  * minimum distance is set such that some percentage of the surface of that
47  * sphere must be covered by samples.
48  *
49  * Once the sample buffer is full, a sphere fitting algorithm is run, which
50  * computes a new sphere radius. The sample buffer is thinned of samples which
51  * no longer meet the acceptance criteria, and the state transitions to
52  * RUNNING_STEP_TWO. Samples continue to be collected until the buffer is full
53  * again, the full ellipsoid fit is run, and the state transitions to either
54  * SUCCESS or FAILED.
55  *
56  * The fitting algorithm used is Levenberg-Marquardt. See also:
57  * http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm
58  */
59 
60 #include "CompassCalibrator.h"
61 #include <AP_HAL/AP_HAL.h>
63 
64 extern const AP_HAL::HAL& hal;
65 
69 
72 _sample_buffer(nullptr)
73 {
74  clear();
75 }
76 
79 }
80 
81 void CompassCalibrator::start(bool retry, float delay, uint16_t offset_max) {
82  if(running()) {
83  return;
84  }
85  _offset_max = offset_max;
86  _attempt = 1;
87  _retry = retry;
91 }
92 
93 void CompassCalibrator::get_calibration(Vector3f &offsets, Vector3f &diagonals, Vector3f &offdiagonals) {
95  return;
96  }
97 
98  offsets = _params.offset;
99  diagonals = _params.diag;
100  offdiagonals = _params.offdiag;
101 }
102 
104  // first sampling step is 1/3rd of the progress bar
105  // never return more than 99% unless _status is COMPASS_CAL_SUCCESS
106  switch(_status) {
109  return 0.0f;
114  case COMPASS_CAL_SUCCESS:
115  return 100.0f;
116  case COMPASS_CAL_FAILED:
117  default:
118  return 0.0f;
119  };
120 }
121 
123 {
124  Matrix3f softiron{
128  };
129  Vector3f corrected = softiron * (v + _params.offset);
130  int section = AP_GeodesicGrid::section(corrected, true);
131  if (section < 0) {
132  return;
133  }
134  _completion_mask[section / 8] |= 1 << (section % 8);
135 }
136 
138 {
139  memset(_completion_mask, 0, sizeof(_completion_mask));
140  for (int i = 0; i < _samples_collected; i++) {
142  }
143 }
144 
146 {
147  return _completion_mask;
148 }
149 
151  uint32_t tnow = AP_HAL::millis();
152  if(running() && tnow - _last_sample_ms > 1000) {
153  _retry = false;
155  return true;
156  }
157  return false;
158 }
159 
162 
165  }
166 
168  update_completion_mask(sample);
171  }
172 }
173 
174 void CompassCalibrator::update(bool &failure) {
175  failure = false;
176 
177  if(!fitting()) {
178  return;
179  }
180 
182  if (_fit_step >= 10) {
183  if(is_equal(_fitness,_initial_fitness) || isnan(_fitness)) { //if true, means that fitness is diverging instead of converging
185  failure = true;
186  }
188  } else {
189  if (_fit_step == 0) {
191  }
192  run_sphere_fit();
193  _fit_step++;
194  }
195  } else if(_status == COMPASS_CAL_RUNNING_STEP_TWO) {
196  if (_fit_step >= 35) {
197  if(fit_acceptable()) {
199  } else {
201  failure = true;
202  }
203  } else if (_fit_step < 15) {
204  run_sphere_fit();
205  _fit_step++;
206  } else {
208  _fit_step++;
209  }
210  }
211 }
212 
218 }
219 
222 }
223 
225  //initialize _fitness before starting a fit
226  if (_samples_collected != 0) {
228  } else {
229  _fitness = 1.0e30f;
230  }
231  _ellipsoid_lambda = 1.0f;
232  _sphere_lambda = 1.0f;
234  _fit_step = 0;
235 }
236 
238  _samples_collected = 0;
239  _samples_thinned = 0;
240  _params.radius = 200;
241  _params.offset.zero();
242  _params.diag = Vector3f(1.0f,1.0f,1.0f);
243  _params.offdiag.zero();
244 
245  memset(_completion_mask, 0, sizeof(_completion_mask));
246  initialize_fit();
247 }
248 
250  if (status != COMPASS_CAL_NOT_STARTED && _status == status) {
251  return true;
252  }
253 
254  switch(status) {
256  reset_state();
258 
259  if(_sample_buffer != nullptr) {
261  _sample_buffer = nullptr;
262  }
263  return true;
264 
266  reset_state();
268 
270  return true;
271 
274  return false;
275  }
276 
277  if(_attempt == 1 && (AP_HAL::millis()-_start_time_ms)*1.0e-3f < _delay_start_sec) {
278  return false;
279  }
280 
281  if (_sample_buffer == nullptr) {
284  }
285 
286  if(_sample_buffer != nullptr) {
287  initialize_fit();
289  return true;
290  }
291 
292  return false;
293 
296  return false;
297  }
298  thin_samples();
299  initialize_fit();
301  return true;
302 
303  case COMPASS_CAL_SUCCESS:
305  return false;
306  }
307 
308  if(_sample_buffer != nullptr) {
310  _sample_buffer = nullptr;
311  }
312 
314  return true;
315 
316  case COMPASS_CAL_FAILED:
318  return false;
319  }
320 
322  _attempt++;
323  return true;
324  }
325 
326  if(_sample_buffer != nullptr) {
328  _sample_buffer = nullptr;
329  }
330 
332  return true;
333 
334  default:
335  return false;
336  };
337 }
338 
340  if( !isnan(_fitness) &&
341  _params.radius > 150 && _params.radius < 950 && //Earth's magnetic field strength range: 250-850mG
342  fabsf(_params.offset.x) < _offset_max &&
343  fabsf(_params.offset.y) < _offset_max &&
344  fabsf(_params.offset.z) < _offset_max &&
345  _params.diag.x > 0.2f && _params.diag.x < 5.0f &&
346  _params.diag.y > 0.2f && _params.diag.y < 5.0f &&
347  _params.diag.z > 0.2f && _params.diag.z < 5.0f &&
348  fabsf(_params.offdiag.x) < 1.0f && //absolute of sine/cosine output cannot be greater than 1
349  fabsf(_params.offdiag.y) < 1.0f &&
350  fabsf(_params.offdiag.z) < 1.0f ){
351 
352  return _fitness <= sq(_tolerance);
353  }
354  return false;
355 }
356 
358  if(_sample_buffer == nullptr) {
359  return;
360  }
361 
362  _samples_thinned = 0;
363  // shuffle the samples http://en.wikipedia.org/wiki/Fisher%E2%80%93Yates_shuffle
364  // this is so that adjacent samples don't get sequentially eliminated
365  for(uint16_t i=_samples_collected-1; i>=1; i--) {
366  uint16_t j = get_random16() % (i+1);
367  CompassSample temp = _sample_buffer[i];
369  _sample_buffer[j] = temp;
370  }
371 
372  for(uint16_t i=0; i < _samples_collected; i++) {
373  if(!accept_sample(_sample_buffer[i])) {
374  _sample_buffer[i] = _sample_buffer[_samples_collected-1];
375  _samples_collected --;
376  _samples_thinned ++;
377  }
378  }
379 
381 }
382 
383 /*
384  * The sample acceptance distance is determined as follows:
385  * For any regular polyhedron with triangular faces, the angle theta subtended
386  * by two closest points is defined as
387  *
388  * theta = arccos(cos(A)/(1-cos(A)))
389  *
390  * Where:
391  * A = (4pi/F + pi)/3
392  * and
393  * F = 2V - 4 is the number of faces for the polyhedron in consideration,
394  * which depends on the number of vertices V
395  *
396  * The above equation was proved after solving for spherical triangular excess
397  * and related equations.
398  */
400 {
401  static const uint16_t faces = (2 * COMPASS_CAL_NUM_SAMPLES - 4);
402  static const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;
403  static const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));
404 
405  if(_sample_buffer == nullptr) {
406  return false;
407  }
408 
409  float min_distance = _params.radius * 2*sinf(theta/2);
410 
411  for (uint16_t i = 0; i<_samples_collected; i++){
412  float distance = (sample - _sample_buffer[i].get()).length();
413  if(distance < min_distance) {
414  return false;
415  }
416  }
417  return true;
418 }
419 
421  return accept_sample(sample.get());
422 }
423 
424 float CompassCalibrator::calc_residual(const Vector3f& sample, const param_t& params) const {
425  Matrix3f softiron(
426  params.diag.x , params.offdiag.x , params.offdiag.y,
427  params.offdiag.x , params.diag.y , params.offdiag.z,
428  params.offdiag.y , params.offdiag.z , params.diag.z
429  );
430  return params.radius - (softiron*(sample+params.offset)).length();
431 }
432 
434 {
436 }
437 
439 {
440  if(_sample_buffer == nullptr || _samples_collected == 0) {
441  return 1.0e30f;
442  }
443  float sum = 0.0f;
444  for(uint16_t i=0; i < _samples_collected; i++){
445  Vector3f sample = _sample_buffer[i].get();
446  float resid = calc_residual(sample, params);
447  sum += sq(resid);
448  }
449  sum /= _samples_collected;
450  return sum;
451 }
452 
453 void CompassCalibrator::calc_sphere_jacob(const Vector3f& sample, const param_t& params, float* ret) const{
454  const Vector3f &offset = params.offset;
455  const Vector3f &diag = params.diag;
456  const Vector3f &offdiag = params.offdiag;
457  Matrix3f softiron(
458  diag.x , offdiag.x , offdiag.y,
459  offdiag.x , diag.y , offdiag.z,
460  offdiag.y , offdiag.z , diag.z
461  );
462 
463  float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));
464  float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));
465  float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));
466  float length = (softiron*(sample+offset)).length();
467 
468  // 0: partial derivative (radius wrt fitness fn) fn operated on sample
469  ret[0] = 1.0f;
470  // 1-3: partial derivative (offsets wrt fitness fn) fn operated on sample
471  ret[1] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);
472  ret[2] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);
473  ret[3] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);
474 }
475 
477 {
478  // Set initial offset to the average value of the samples
479  _params.offset.zero();
480  for(uint16_t k = 0; k<_samples_collected; k++) {
482  }
484 }
485 
487 {
488  if(_sample_buffer == nullptr) {
489  return;
490  }
491 
492  const float lma_damping = 10.0f;
493 
494  float fitness = _fitness;
495  float fit1, fit2;
496  param_t fit1_params, fit2_params;
497  fit1_params = fit2_params = _params;
498 
501  float JTFI[COMPASS_CAL_NUM_SPHERE_PARAMS] = { };
502 
503  // Gauss Newton Part common for all kind of extensions including LM
504  for(uint16_t k = 0; k<_samples_collected; k++) {
505  Vector3f sample = _sample_buffer[k].get();
506 
507  float sphere_jacob[COMPASS_CAL_NUM_SPHERE_PARAMS];
508 
509  calc_sphere_jacob(sample, fit1_params, sphere_jacob);
510 
511  for(uint8_t i = 0;i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {
512  // compute JTJ
513  for(uint8_t j = 0; j < COMPASS_CAL_NUM_SPHERE_PARAMS; j++) {
514  JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j];
515  JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j]; //a backup JTJ for LM
516  }
517  // compute JTFI
518  JTFI[i] += sphere_jacob[i] * calc_residual(sample, fit1_params);
519  }
520  }
521 
522 
523  //------------------------Levenberg-Marquardt-part-starts-here---------------------------------//
524  //refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter
525  for(uint8_t i = 0; i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {
526  JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda;
527  JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda/lma_damping;
528  }
529 
530  if(!inverse(JTJ, JTJ, 4)) {
531  return;
532  }
533 
534  if(!inverse(JTJ2, JTJ2, 4)) {
535  return;
536  }
537 
538  for(uint8_t row=0; row < COMPASS_CAL_NUM_SPHERE_PARAMS; row++) {
539  for(uint8_t col=0; col < COMPASS_CAL_NUM_SPHERE_PARAMS; col++) {
540  fit1_params.get_sphere_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];
541  fit2_params.get_sphere_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];
542  }
543  }
544 
545  fit1 = calc_mean_squared_residuals(fit1_params);
546  fit2 = calc_mean_squared_residuals(fit2_params);
547 
548  if(fit1 > _fitness && fit2 > _fitness){
549  _sphere_lambda *= lma_damping;
550  } else if(fit2 < _fitness && fit2 < fit1) {
551  _sphere_lambda /= lma_damping;
552  fit1_params = fit2_params;
553  fitness = fit2;
554  } else if(fit1 < _fitness){
555  fitness = fit1;
556  }
557  //--------------------Levenberg-Marquardt-part-ends-here--------------------------------//
558 
559  if(!isnan(fitness) && fitness < _fitness) {
560  _fitness = fitness;
561  _params = fit1_params;
563  }
564 }
565 
566 
567 
568 void CompassCalibrator::calc_ellipsoid_jacob(const Vector3f& sample, const param_t& params, float* ret) const{
569  const Vector3f &offset = params.offset;
570  const Vector3f &diag = params.diag;
571  const Vector3f &offdiag = params.offdiag;
572  Matrix3f softiron(
573  diag.x , offdiag.x , offdiag.y,
574  offdiag.x , diag.y , offdiag.z,
575  offdiag.y , offdiag.z , diag.z
576  );
577 
578  float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));
579  float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));
580  float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));
581  float length = (softiron*(sample+offset)).length();
582 
583  // 0-2: partial derivative (offset wrt fitness fn) fn operated on sample
584  ret[0] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);
585  ret[1] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);
586  ret[2] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);
587  // 3-5: partial derivative (diag offset wrt fitness fn) fn operated on sample
588  ret[3] = -1.0f * ((sample.x + offset.x) * A)/length;
589  ret[4] = -1.0f * ((sample.y + offset.y) * B)/length;
590  ret[5] = -1.0f * ((sample.z + offset.z) * C)/length;
591  // 6-8: partial derivative (off-diag offset wrt fitness fn) fn operated on sample
592  ret[6] = -1.0f * (((sample.y + offset.y) * A) + ((sample.x + offset.x) * B))/length;
593  ret[7] = -1.0f * (((sample.z + offset.z) * A) + ((sample.x + offset.x) * C))/length;
594  ret[8] = -1.0f * (((sample.z + offset.z) * B) + ((sample.y + offset.y) * C))/length;
595 }
596 
598 {
599  if(_sample_buffer == nullptr) {
600  return;
601  }
602 
603  const float lma_damping = 10.0f;
604 
605 
606  float fitness = _fitness;
607  float fit1, fit2;
608  param_t fit1_params, fit2_params;
609  fit1_params = fit2_params = _params;
610 
611 
614  float JTFI[COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };
615 
616  // Gauss Newton Part common for all kind of extensions including LM
617  for(uint16_t k = 0; k<_samples_collected; k++) {
618  Vector3f sample = _sample_buffer[k].get();
619 
620  float ellipsoid_jacob[COMPASS_CAL_NUM_ELLIPSOID_PARAMS];
621 
622  calc_ellipsoid_jacob(sample, fit1_params, ellipsoid_jacob);
623 
624  for(uint8_t i = 0;i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {
625  // compute JTJ
626  for(uint8_t j = 0; j < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; j++) {
627  JTJ [i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];
628  JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];
629  }
630  // compute JTFI
631  JTFI[i] += ellipsoid_jacob[i] * calc_residual(sample, fit1_params);
632  }
633  }
634 
635 
636 
637  //------------------------Levenberg-Marquardt-part-starts-here---------------------------------//
638  //refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter
639  for(uint8_t i = 0; i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {
640  JTJ[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda;
641  JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda/lma_damping;
642  }
643 
644  if(!inverse(JTJ, JTJ, 9)) {
645  return;
646  }
647 
648  if(!inverse(JTJ2, JTJ2, 9)) {
649  return;
650  }
651 
652  for(uint8_t row=0; row < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; row++) {
653  for(uint8_t col=0; col < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; col++) {
654  fit1_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];
655  fit2_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];
656  }
657  }
658 
659  fit1 = calc_mean_squared_residuals(fit1_params);
660  fit2 = calc_mean_squared_residuals(fit2_params);
661 
662  if(fit1 > _fitness && fit2 > _fitness){
663  _ellipsoid_lambda *= lma_damping;
664  } else if(fit2 < _fitness && fit2 < fit1) {
665  _ellipsoid_lambda /= lma_damping;
666  fit1_params = fit2_params;
667  fitness = fit2;
668  } else if(fit1 < _fitness){
669  fitness = fit1;
670  }
671  //--------------------Levenberg-part-ends-here--------------------------------//
672 
673  if(fitness < _fitness) {
674  _fitness = fitness;
675  _params = fit1_params;
677  }
678 }
679 
680 
684 
685 #define COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(__X) ((int16_t)constrain_float(roundf(__X*8.0f), INT16_MIN, INT16_MAX))
686 #define COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(__X) (__X/8.0f)
687 
692 }
693 
698 }
float get_completion_percent() const
void start(bool retry, float delay, uint16_t offset_max)
void new_sample(const Vector3f &sample)
Vector3< float > Vector3f
Definition: vector3.h:246
enum compass_cal_status_t _status
float calc_residual(const Vector3f &sample, const param_t &params) const
#define COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(__X)
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void calc_ellipsoid_jacob(const Vector3f &sample, const param_t &params, float *ret) const
uint8_t completion_mask_t[10]
#define COMPASS_CAL_NUM_ELLIPSOID_PARAMS
completion_mask_t _completion_mask
ptrdiff_t offset
Definition: AP_Param.h:149
completion_mask_t & get_completion_mask()
float distance
Definition: location.cpp:94
void delay(uint32_t ms)
Definition: system.cpp:91
void calc_sphere_jacob(const Vector3f &sample, const param_t &params, float *ret) const
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
uint16_t get_random16(void)
Definition: AP_Math.cpp:212
compass_cal_status_t
void update(bool &failure)
class param_t _params
#define x(i)
void get_calibration(Vector3f &offsets, Vector3f &diagonals, Vector3f &offdiagonals)
#define f(i)
#define COMPASS_CAL_NUM_SPHERE_PARAMS
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
bool set_status(compass_cal_status_t status)
bool accept_sample(const Vector3f &sample)
T z
Definition: vector3.h:67
#define COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(__X)
float v
Definition: Printf.cpp:15
#define COMPASS_CAL_NUM_SAMPLES
void free(void *ptr)
Definition: malloc.c:81
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
static int section(const Vector3f &v, bool inclusive=false)
#define COMPASS_CAL_DEFAULT_TOLERANCE
bool inverse(float x[], float y[], uint16_t dim)
Definition: matrix_alg.cpp:433
float sq(const T val)
Definition: AP_Math.h:170
#define M_PI
Definition: definitions.h:10
float calc_mean_squared_residuals() const
CompassSample * _sample_buffer
void zero()
Definition: vector3.h:182
T x
Definition: vector3.h:67