Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_AccelCal/AccelCalibrator.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.5This program is distributed in the hope that it will be useful,6but WITHOUT ANY WARRANTY; without even the implied warranty of7MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the8GNU General Public License for more details.9You should have received a copy of the GNU General Public License10along with this program. If not, see <http://www.gnu.org/licenses/>.11*/1213// Authored by Jonathan Challinger, 3D Robotics Inc.1415#include "AccelCalibrator.h"16#include <stdio.h>17#include <AP_HAL/AP_HAL.h>1819const extern AP_HAL::HAL& hal;20/*21* TODO22* - time out when not receiving samples23*/2425////////////////////////////////////////////////////////////26///////////////////// PUBLIC INTERFACE /////////////////////27////////////////////////////////////////////////////////////2829AccelCalibrator::AccelCalibrator() :30_conf_tolerance(ACCEL_CAL_TOLERANCE),31_sample_buffer(nullptr)32{33clear();34}35/*36Select options, initialise variables and initiate accel calibration37Options:38Fit Type: Will assume that if accelerometer static samples around all possible orientation39are spread in space will cover a surface of AXIS_ALIGNED_ELLIPSOID or any general40ELLIPSOID as chosen4142Num Samples: Number of samples user should will be gathering, please note that with type of surface43chosen the minimum number of samples required will vary, for instance in the case of AXIS44ALIGNED ELLIPSOID atleast 6 distinct samples are required while for generic ELLIPSOIDAL fit45which will include calculation of offdiagonal parameters too requires atleast 8 parameters46to form a distinct ELLIPSOID4748Sample Time: Time over which the samples will be gathered and averaged to add to a single sample for least49square regression5051offset,diag,offdiag: initial parameter values for LSQ calculation52*/53void AccelCalibrator::start(enum accel_cal_fit_type_t fit_type, uint8_t num_samples, float sample_time) {54start(fit_type, num_samples, sample_time, Vector3f(0,0,0), Vector3f(1,1,1), Vector3f(0,0,0));55}5657void AccelCalibrator::start(enum accel_cal_fit_type_t fit_type, uint8_t num_samples, float sample_time, Vector3f offset, Vector3f diag, Vector3f offdiag) {58if (_status == ACCEL_CAL_FAILED || _status == ACCEL_CAL_SUCCESS) {59clear();60}61if (_status != ACCEL_CAL_NOT_STARTED) {62return;63}6465_conf_num_samples = num_samples;66_conf_sample_time = sample_time;67_conf_fit_type = fit_type;6869const uint16_t faces = 2*_conf_num_samples-4;70const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;71const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));72_min_sample_dist = GRAVITY_MSS * 2*sinf(theta/2);7374_param.s.offset = offset;75_param.s.diag = diag;76_param.s.offdiag = offdiag;7778switch (_conf_fit_type) {79case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:80if (_conf_num_samples < 6) {81set_status(ACCEL_CAL_FAILED);82return;83}84break;85case ACCEL_CAL_ELLIPSOID:86if (_conf_num_samples < 8) {87set_status(ACCEL_CAL_FAILED);88return;89}90break;91}9293set_status(ACCEL_CAL_WAITING_FOR_ORIENTATION);94}959697// set Accel calibrator status to make itself ready for future accel cals98void AccelCalibrator::clear() {99set_status(ACCEL_CAL_NOT_STARTED);100}101102// returns true if accel calibrator is running103bool AccelCalibrator::running() {104return _status == ACCEL_CAL_WAITING_FOR_ORIENTATION || _status == ACCEL_CAL_COLLECTING_SAMPLE;105}106107// set Accel calibrator to start collecting samples in the next cycle108void AccelCalibrator::collect_sample() {109set_status(ACCEL_CAL_COLLECTING_SAMPLE);110}111112// collect and avg sample to be passed onto LSQ estimator after all requisite orientations are done113void AccelCalibrator::new_sample(const Vector3f& delta_velocity, float dt) {114if (_status != ACCEL_CAL_COLLECTING_SAMPLE) {115return;116}117118if (_samples_collected >= _conf_num_samples) {119set_status(ACCEL_CAL_FAILED);120return;121}122123_sample_buffer[_samples_collected].delta_velocity += delta_velocity;124_sample_buffer[_samples_collected].delta_time += dt;125126_last_samp_frag_collected_ms = AP_HAL::millis();127128if (_sample_buffer[_samples_collected].delta_time > _conf_sample_time) {129Vector3f sample = _sample_buffer[_samples_collected].delta_velocity/_sample_buffer[_samples_collected].delta_time;130if (!accept_sample(sample)) {131set_status(ACCEL_CAL_FAILED);132return;133}134135_samples_collected++;136137if (_samples_collected >= _conf_num_samples) {138run_fit(MAX_ITERATIONS, _fitness);139140if (_fitness < _conf_tolerance && accept_result()) {141set_status(ACCEL_CAL_SUCCESS);142} else {143set_status(ACCEL_CAL_FAILED);144}145} else {146set_status(ACCEL_CAL_WAITING_FOR_ORIENTATION);147}148}149}150151// determines if the result is acceptable152bool AccelCalibrator::accept_result() const {153if (fabsf(_param.s.offset.x) > GRAVITY_MSS ||154fabsf(_param.s.offset.y) > GRAVITY_MSS ||155fabsf(_param.s.offset.z) > GRAVITY_MSS ||156_param.s.diag.x < 0.8f || _param.s.diag.x > 1.2f ||157_param.s.diag.y < 0.8f || _param.s.diag.y > 1.2f ||158_param.s.diag.z < 0.8f || _param.s.diag.z > 1.2f) {159return false;160} else {161return true;162}163}164165// interface for LSq estimator to read sample buffer sent after conversion from delta velocity166// to averaged acc over time167bool AccelCalibrator::get_sample(uint8_t i, Vector3f& s) const {168if (i >= _samples_collected) {169return false;170}171s = _sample_buffer[i].delta_velocity / _sample_buffer[i].delta_time;172return true;173}174175// returns true and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure176// returns false if no correct parameter exists to be applied along with existing sample without corrections177bool AccelCalibrator::get_sample_corrected(uint8_t i, Vector3f& s) const {178if (_status != ACCEL_CAL_SUCCESS || !get_sample(i,s)) {179return false;180}181182Matrix3f M (183_param.s.diag.x , _param.s.offdiag.x , _param.s.offdiag.y,184_param.s.offdiag.x , _param.s.diag.y , _param.s.offdiag.z,185_param.s.offdiag.y , _param.s.offdiag.z , _param.s.diag.z186);187188s = M*(s+_param.s.offset);189190return true;191}192193// checks if no new sample has been received for considerable amount of time194void AccelCalibrator::check_for_timeout() {195const uint32_t timeout = _conf_sample_time*2*1000 + 500;196if (_status == ACCEL_CAL_COLLECTING_SAMPLE && AP_HAL::millis() - _last_samp_frag_collected_ms > timeout) {197set_status(ACCEL_CAL_FAILED);198}199}200201// returns spherical fit parameters202void AccelCalibrator::get_calibration(Vector3f& offset) const {203offset = -_param.s.offset;204}205206// returns axis aligned ellipsoidal fit parameters207void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag) const {208offset = -_param.s.offset;209diag = _param.s.diag;210}211212// returns generic ellipsoidal fit parameters213void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag, Vector3f& offdiag) const {214offset = -_param.s.offset;215diag = _param.s.diag;216offdiag = _param.s.offdiag;217}218219/////////////////////////////////////////////////////////////220////////////////////// PRIVATE METHODS //////////////////////221/////////////////////////////////////////////////////////////222223/*224The sample acceptance distance is determined as follows:225For any regular polyhedron with triangular faces, the angle theta subtended226by two closest points is defined as227228theta = arccos(cos(A)/(1-cos(A)))229230Where:231A = (4pi/F + pi)/3232and233F = 2V - 4 is the number of faces for the polyhedron in consideration,234which depends on the number of vertices V235236The above equation was proved after solving for spherical triangular excess237and related equations.238*/239bool AccelCalibrator::accept_sample(const Vector3f& sample)240{241if (_sample_buffer == nullptr) {242return false;243}244245for(uint8_t i=0; i < _samples_collected; i++) {246Vector3f other_sample;247get_sample(i, other_sample);248249if ((other_sample - sample).length() < _min_sample_dist){250return false;251}252}253return true;254}255256// sets status of calibrator and takes appropriate actions257void AccelCalibrator::set_status(enum accel_cal_status_t status) {258switch (status) {259case ACCEL_CAL_NOT_STARTED:260//Calibrator not started261_status = ACCEL_CAL_NOT_STARTED;262263_samples_collected = 0;264if (_sample_buffer != nullptr) {265free(_sample_buffer);266_sample_buffer = nullptr;267}268269break;270271case ACCEL_CAL_WAITING_FOR_ORIENTATION:272//Callibrator has been started and is waiting for user to ack after orientation setting273if (!running()) {274_samples_collected = 0;275if (_sample_buffer == nullptr) {276_sample_buffer = (struct AccelSample*)calloc(_conf_num_samples,sizeof(struct AccelSample));277if (_sample_buffer == nullptr) {278set_status(ACCEL_CAL_FAILED);279break;280}281}282}283if (_samples_collected >= _conf_num_samples) {284break;285}286_status = ACCEL_CAL_WAITING_FOR_ORIENTATION;287break;288289case ACCEL_CAL_COLLECTING_SAMPLE:290// Calibrator is waiting on collecting samples from accelerometer for amount of291// time as requested by user/GCS292if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) {293break;294}295_last_samp_frag_collected_ms = AP_HAL::millis();296_status = ACCEL_CAL_COLLECTING_SAMPLE;297break;298299case ACCEL_CAL_SUCCESS:300// Calibrator has successfully fitted the samples to user requested surface model301// and has passed tolerance test302if (_status != ACCEL_CAL_COLLECTING_SAMPLE) {303break;304}305306_status = ACCEL_CAL_SUCCESS;307break;308309case ACCEL_CAL_FAILED:310// Calibration has failed with reasons that can range from311// bad sample data leading to failure in tolerance test to lack of distinct samples312if (_status == ACCEL_CAL_NOT_STARTED) {313break;314}315316_status = ACCEL_CAL_FAILED;317break;318};319}320321/*322Run Gauss Newton fitting algorithm over the sample space and come up with offsets, diagonal/scale factors323and crosstalk/offdiagonal parameters324*/325void AccelCalibrator::run_fit(uint8_t max_iterations, float& fitness)326{327if (_sample_buffer == nullptr) {328return;329}330fitness = calc_mean_squared_residuals(_param.s);331float min_fitness = fitness;332union param_u fit_param = _param;333uint8_t num_iterations = 0;334335while(num_iterations < max_iterations) {336float JTJ[ACCEL_CAL_MAX_NUM_PARAMS*ACCEL_CAL_MAX_NUM_PARAMS] {};337VectorP JTFI;338339for(uint16_t k = 0; k<_samples_collected; k++) {340Vector3f sample;341get_sample(k, sample);342343VectorN<float,ACCEL_CAL_MAX_NUM_PARAMS> jacob;344345calc_jacob(sample, fit_param.s, jacob);346347for(uint8_t i = 0; i < get_num_params(); i++) {348// compute JTJ349for(uint8_t j = 0; j < get_num_params(); j++) {350JTJ[i*get_num_params()+j] += jacob[i] * jacob[j];351}352// compute JTFI353JTFI[i] += jacob[i] * calc_residual(sample, fit_param.s);354}355}356357if (!mat_inverse(JTJ, JTJ, get_num_params())) {358return;359}360361for(uint8_t row=0; row < get_num_params(); row++) {362for(uint8_t col=0; col < get_num_params(); col++) {363fit_param.a[row] -= JTFI[col] * JTJ[row*get_num_params()+col];364}365}366367fitness = calc_mean_squared_residuals(fit_param.s);368369if (isnan(fitness) || isinf(fitness)) {370return;371}372373if (fitness < min_fitness) {374min_fitness = fitness;375_param = fit_param;376}377378num_iterations++;379}380}381382// calculates residual from samples(corrected using supplied parameter) to gravity383// used to create Fitness column matrix384float AccelCalibrator::calc_residual(const Vector3f& sample, const struct param_t& params) const {385Matrix3f M (386params.diag.x , params.offdiag.x , params.offdiag.y,387params.offdiag.x , params.diag.y , params.offdiag.z,388params.offdiag.y , params.offdiag.z , params.diag.z389);390return GRAVITY_MSS - (M*(sample+params.offset)).length();391}392393// calculated the total mean squared fitness of all the collected samples using parameters394// supplied395float AccelCalibrator::calc_mean_squared_residuals(const struct param_t& params) const396{397if (_sample_buffer == nullptr || _samples_collected == 0) {398return 1.0e30f;399}400float sum = 0.0f;401for(uint16_t i=0; i < _samples_collected; i++){402Vector3f sample;403get_sample(i, sample);404float resid = calc_residual(sample, params);405sum += sq(resid);406}407sum /= _samples_collected;408return sum;409}410411// calculate jacobian, a matrix that defines relation to variation in fitness with variation in each of the parameters412// this is used in LSq estimator to adjust variation in parameter to be used for next iteration of LSq413void AccelCalibrator::calc_jacob(const Vector3f& sample, const struct param_t& params, VectorP &ret) const {414switch (_conf_fit_type) {415case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:416case ACCEL_CAL_ELLIPSOID: {417const Vector3f &offset = params.offset;418const Vector3f &diag = params.diag;419const Vector3f &offdiag = params.offdiag;420Matrix3f M(421diag.x , offdiag.x , offdiag.y,422offdiag.x , diag.y , offdiag.z,423offdiag.y , offdiag.z , diag.z424);425426float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));427float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));428float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));429float length = (M*(sample+offset)).length();430431// 0-2: offsets432ret[0] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);433ret[1] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);434ret[2] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);435// 3-5: diagonals436ret[3] = -1.0f * ((sample.x + offset.x) * A)/length;437ret[4] = -1.0f * ((sample.y + offset.y) * B)/length;438ret[5] = -1.0f * ((sample.z + offset.z) * C)/length;439// 6-8: off-diagonals440ret[6] = -1.0f * (((sample.y + offset.y) * A) + ((sample.x + offset.x) * B))/length;441ret[7] = -1.0f * (((sample.z + offset.z) * A) + ((sample.x + offset.x) * C))/length;442ret[8] = -1.0f * (((sample.z + offset.z) * B) + ((sample.y + offset.y) * C))/length;443return;444}445}446}447448// returns number of parameters are required for selected Fit type449uint8_t AccelCalibrator::get_num_params() const {450switch (_conf_fit_type) {451case ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID:452return 6;453case ACCEL_CAL_ELLIPSOID:454return 9;455default:456return 6;457}458}459460461