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