123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466 |
- #include "AccelCalibrator.h"
- #include <stdio.h>
- #include <AP_HAL/AP_HAL.h>
- const extern AP_HAL::HAL& hal;
- AccelCalibrator::AccelCalibrator() :
- _conf_tolerance(ACCEL_CAL_TOLERANCE),
- _sample_buffer(nullptr)
- {
- clear();
- }
- void AccelCalibrator::start(enum accel_cal_fit_type_t fit_type, uint8_t num_samples, float sample_time) {
- start(fit_type, num_samples, sample_time, Vector3f(0,0,0), Vector3f(1,1,1), Vector3f(0,0,0));
- }
- void AccelCalibrator::start(enum accel_cal_fit_type_t fit_type, uint8_t num_samples, float sample_time, Vector3f offset, Vector3f diag, Vector3f offdiag) {
- if (_status == ACCEL_CAL_FAILED || _status == ACCEL_CAL_SUCCESS) {
- clear();
- }
- if (_status != ACCEL_CAL_NOT_STARTED) {
- return;
- }
- _conf_num_samples = num_samples;
- _conf_sample_time = sample_time;
- _conf_fit_type = fit_type;
- const uint16_t faces = 2*_conf_num_samples-4;
- const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;
- const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));
- _min_sample_dist = GRAVITY_MSS * 2*sinf(theta/2);
- _param.s.offset = offset;
- _param.s.diag = diag;
- _param.s.offdiag = offdiag;
- switch (_conf_fit_type) {
- case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:
- if (_conf_num_samples < 6) {
- set_status(ACCEL_CAL_FAILED);
- return;
- }
- break;
- case ACCEL_CAL_ELLIPSOID:
- if (_conf_num_samples < 8) {
- set_status(ACCEL_CAL_FAILED);
- return;
- }
- break;
- }
- set_status(ACCEL_CAL_WAITING_FOR_ORIENTATION);
- }
- void AccelCalibrator::clear() {
- set_status(ACCEL_CAL_NOT_STARTED);
- }
- bool AccelCalibrator::running() {
- return _status == ACCEL_CAL_WAITING_FOR_ORIENTATION || _status == ACCEL_CAL_COLLECTING_SAMPLE;
- }
- void AccelCalibrator::collect_sample() {
- set_status(ACCEL_CAL_COLLECTING_SAMPLE);
- }
- void AccelCalibrator::new_sample(const Vector3f& delta_velocity, float dt) {
- if (_status != ACCEL_CAL_COLLECTING_SAMPLE) {
- return;
- }
- if (_samples_collected >= _conf_num_samples) {
- set_status(ACCEL_CAL_FAILED);
- return;
- }
- _sample_buffer[_samples_collected].delta_velocity += delta_velocity;
- _sample_buffer[_samples_collected].delta_time += dt;
- _last_samp_frag_collected_ms = AP_HAL::millis();
- if (_sample_buffer[_samples_collected].delta_time > _conf_sample_time) {
- Vector3f sample = _sample_buffer[_samples_collected].delta_velocity/_sample_buffer[_samples_collected].delta_time;
- if (!accept_sample(sample)) {
- set_status(ACCEL_CAL_FAILED);
- return;
- }
- _samples_collected++;
- if (_samples_collected >= _conf_num_samples) {
- run_fit(MAX_ITERATIONS, _fitness);
- if (_fitness < _conf_tolerance && accept_result()) {
- set_status(ACCEL_CAL_SUCCESS);
- } else {
- set_status(ACCEL_CAL_FAILED);
- }
- } else {
- set_status(ACCEL_CAL_WAITING_FOR_ORIENTATION);
- }
- }
- }
- bool AccelCalibrator::accept_result() const {
- if (fabsf(_param.s.offset.x) > GRAVITY_MSS ||
- fabsf(_param.s.offset.y) > GRAVITY_MSS ||
- fabsf(_param.s.offset.z) > GRAVITY_MSS ||
- _param.s.diag.x < 0.8f || _param.s.diag.x > 1.2f ||
- _param.s.diag.y < 0.8f || _param.s.diag.y > 1.2f ||
- _param.s.diag.z < 0.8f || _param.s.diag.z > 1.2f) {
- return false;
- } else {
- return true;
- }
- }
- bool AccelCalibrator::get_sample(uint8_t i, Vector3f& s) const {
- if (i >= _samples_collected) {
- return false;
- }
- s = _sample_buffer[i].delta_velocity / _sample_buffer[i].delta_time;
- return true;
- }
- bool AccelCalibrator::get_sample_corrected(uint8_t i, Vector3f& s) const {
- if (_status != ACCEL_CAL_SUCCESS || !get_sample(i,s)) {
- return false;
- }
- Matrix3f M (
- _param.s.diag.x , _param.s.offdiag.x , _param.s.offdiag.y,
- _param.s.offdiag.x , _param.s.diag.y , _param.s.offdiag.z,
- _param.s.offdiag.y , _param.s.offdiag.z , _param.s.diag.z
- );
- s = M*(s+_param.s.offset);
- return true;
- }
- void AccelCalibrator::check_for_timeout() {
- const uint32_t timeout = _conf_sample_time*2*1000 + 500;
- if (_status == ACCEL_CAL_COLLECTING_SAMPLE && AP_HAL::millis() - _last_samp_frag_collected_ms > timeout) {
- set_status(ACCEL_CAL_FAILED);
- }
- }
- void AccelCalibrator::get_calibration(Vector3f& offset) const {
- offset = -_param.s.offset;
- }
- void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag) const {
- offset = -_param.s.offset;
- diag = _param.s.diag;
- }
- void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag, Vector3f& offdiag) const {
- offset = -_param.s.offset;
- diag = _param.s.diag;
- offdiag = _param.s.offdiag;
- }
- bool AccelCalibrator::accept_sample(const Vector3f& sample)
- {
- if (_sample_buffer == nullptr) {
- return false;
- }
- for(uint8_t i=0; i < _samples_collected; i++) {
- Vector3f other_sample;
- get_sample(i, other_sample);
- if ((other_sample - sample).length() < _min_sample_dist){
- return false;
- }
- }
- return true;
- }
- void AccelCalibrator::set_status(enum accel_cal_status_t status) {
- switch (status) {
- case ACCEL_CAL_NOT_STARTED:
-
- _status = ACCEL_CAL_NOT_STARTED;
- _samples_collected = 0;
- if (_sample_buffer != nullptr) {
- free(_sample_buffer);
- _sample_buffer = nullptr;
- }
- break;
- case ACCEL_CAL_WAITING_FOR_ORIENTATION:
-
- if (!running()) {
- _samples_collected = 0;
- if (_sample_buffer == nullptr) {
- _sample_buffer = (struct AccelSample*)calloc(_conf_num_samples,sizeof(struct AccelSample));
- if (_sample_buffer == nullptr) {
- set_status(ACCEL_CAL_FAILED);
- break;
- }
- }
- }
- if (_samples_collected >= _conf_num_samples) {
- break;
- }
- _status = ACCEL_CAL_WAITING_FOR_ORIENTATION;
- break;
- case ACCEL_CAL_COLLECTING_SAMPLE:
-
-
- if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) {
- break;
- }
- _last_samp_frag_collected_ms = AP_HAL::millis();
- _status = ACCEL_CAL_COLLECTING_SAMPLE;
- break;
- case ACCEL_CAL_SUCCESS:
-
-
- if (_status != ACCEL_CAL_COLLECTING_SAMPLE) {
- break;
- }
- _status = ACCEL_CAL_SUCCESS;
- break;
- case ACCEL_CAL_FAILED:
-
-
- if (_status == ACCEL_CAL_NOT_STARTED) {
- break;
- }
- _status = ACCEL_CAL_FAILED;
- break;
- };
- }
- void AccelCalibrator::run_fit(uint8_t max_iterations, float& fitness)
- {
- if (_sample_buffer == nullptr) {
- return;
- }
- fitness = calc_mean_squared_residuals(_param.s);
- float min_fitness = fitness;
- union param_u fit_param = _param;
- uint8_t num_iterations = 0;
- while(num_iterations < max_iterations) {
- float JTJ[ACCEL_CAL_MAX_NUM_PARAMS*ACCEL_CAL_MAX_NUM_PARAMS] {};
- VectorP JTFI;
- for(uint16_t k = 0; k<_samples_collected; k++) {
- Vector3f sample;
- get_sample(k, sample);
- VectorN<float,ACCEL_CAL_MAX_NUM_PARAMS> jacob;
- calc_jacob(sample, fit_param.s, jacob);
- for(uint8_t i = 0; i < get_num_params(); i++) {
-
- for(uint8_t j = 0; j < get_num_params(); j++) {
- JTJ[i*get_num_params()+j] += jacob[i] * jacob[j];
- }
-
- JTFI[i] += jacob[i] * calc_residual(sample, fit_param.s);
- }
- }
- if (!inverse(JTJ, JTJ, get_num_params())) {
- return;
- }
- for(uint8_t row=0; row < get_num_params(); row++) {
- for(uint8_t col=0; col < get_num_params(); col++) {
- fit_param.a[row] -= JTFI[col] * JTJ[row*get_num_params()+col];
- }
- }
- fitness = calc_mean_squared_residuals(fit_param.s);
- if (isnan(fitness) || isinf(fitness)) {
- return;
- }
- if (fitness < min_fitness) {
- min_fitness = fitness;
- _param = fit_param;
- }
- num_iterations++;
- }
- }
- float AccelCalibrator::calc_residual(const Vector3f& sample, const struct param_t& params) const {
- Matrix3f M (
- params.diag.x , params.offdiag.x , params.offdiag.y,
- params.offdiag.x , params.diag.y , params.offdiag.z,
- params.offdiag.y , params.offdiag.z , params.diag.z
- );
- return GRAVITY_MSS - (M*(sample+params.offset)).length();
- }
- float AccelCalibrator::calc_mean_squared_residuals() const
- {
- return calc_mean_squared_residuals(_param.s);
- }
- float AccelCalibrator::calc_mean_squared_residuals(const struct param_t& params) const
- {
- if (_sample_buffer == nullptr || _samples_collected == 0) {
- return 1.0e30f;
- }
- float sum = 0.0f;
- for(uint16_t i=0; i < _samples_collected; i++){
- Vector3f sample;
- get_sample(i, sample);
- float resid = calc_residual(sample, params);
- sum += sq(resid);
- }
- sum /= _samples_collected;
- return sum;
- }
- void AccelCalibrator::calc_jacob(const Vector3f& sample, const struct param_t& params, VectorP &ret) const {
- switch (_conf_fit_type) {
- case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:
- case ACCEL_CAL_ELLIPSOID: {
- const Vector3f &offset = params.offset;
- const Vector3f &diag = params.diag;
- const Vector3f &offdiag = params.offdiag;
- Matrix3f M(
- diag.x , offdiag.x , offdiag.y,
- offdiag.x , diag.y , offdiag.z,
- offdiag.y , offdiag.z , diag.z
- );
- float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));
- float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));
- float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));
- float length = (M*(sample+offset)).length();
-
- ret[0] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);
- ret[1] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);
- ret[2] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);
-
- ret[3] = -1.0f * ((sample.x + offset.x) * A)/length;
- ret[4] = -1.0f * ((sample.y + offset.y) * B)/length;
- ret[5] = -1.0f * ((sample.z + offset.z) * C)/length;
-
- ret[6] = -1.0f * (((sample.y + offset.y) * A) + ((sample.x + offset.x) * B))/length;
- ret[7] = -1.0f * (((sample.z + offset.z) * A) + ((sample.x + offset.x) * C))/length;
- ret[8] = -1.0f * (((sample.z + offset.z) * B) + ((sample.y + offset.y) * C))/length;
- return;
- }
- };
- }
- uint8_t AccelCalibrator::get_num_params() const {
- switch (_conf_fit_type) {
- case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:
- return 6;
- case ACCEL_CAL_ELLIPSOID:
- return 9;
- default:
- return 6;
- }
- }
|