Path: blob/master/libraries/AP_Compass/CompassCalibrator.cpp
9362 views
/*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.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/*16* The intention of a magnetometer in a compass application is to measure17* Earth's magnetic field. Measurements other than those of Earth's magnetic18* field are considered errors. This algorithm computes a set of correction19* parameters that null out errors from various sources:20*21* - Sensor bias error22* - "Hard iron" error caused by materials fixed to the vehicle body that23* produce static magnetic fields.24* - Sensor scale-factor error25* - Sensor cross-axis sensitivity26* - "Soft iron" error caused by materials fixed to the vehicle body that27* distort magnetic fields.28*29* This is done by taking a set of samples that are assumed to be the product30* of rotation in earth's magnetic field and fitting an offset ellipsoid to31* them, determining the correction to be applied to adjust the samples into an32* origin-centered sphere.33*34* The state machine of this library is described entirely by the35* CompassCalibrator::Status enum, and all state transitions are managed by the36* set_status function. Normally, the library is in the NOT_STARTED state. When37* the start function is called, the state transitions to WAITING_TO_START,38* until two conditions are met: the delay as elapsed, and the memory for the39* sample buffer has been successfully allocated.40* Once these conditions are met, the state transitions to RUNNING_STEP_ONE, and41* samples are collected via calls to the new_sample function. These samples are42* accepted or rejected based on distance to the nearest sample. The samples are43* assumed to cover the surface of a sphere, and the radius of that sphere is44* initialized to a conservative value. Based on a circle-packing pattern, the45* minimum distance is set such that some percentage of the surface of that46* sphere must be covered by samples.47*48* Once the sample buffer is full, a sphere fitting algorithm is run, which49* computes a new sphere radius. The sample buffer is thinned of samples which50* no longer meet the acceptance criteria, and the state transitions to51* RUNNING_STEP_TWO. Samples continue to be collected until the buffer is full52* again, the full ellipsoid fit is run, and the state transitions to either53* SUCCESS or FAILED.54*55* The fitting algorithm used is Levenberg-Marquardt. See also:56* http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm57*/5859#include "AP_Compass_config.h"6061#if COMPASS_CAL_ENABLED6263#include "AP_Compass.h"64#include "CompassCalibrator.h"65#include <AP_HAL/AP_HAL.h>66#include <AP_Math/AP_GeodesicGrid.h>67#include <AP_AHRS/AP_AHRS.h>68#include <AP_GPS/AP_GPS.h>69#include <GCS_MAVLink/GCS.h>70#include <AP_InternalError/AP_InternalError.h>7172#define FIELD_RADIUS_MIN 15073#define FIELD_RADIUS_MAX 9507475////////////////////////////////////////////////////////////76///////////////////// PUBLIC INTERFACE /////////////////////77////////////////////////////////////////////////////////////7879CompassCalibrator::CompassCalibrator()80{81set_status(Status::NOT_STARTED);82}8384// Request to cancel calibration85void CompassCalibrator::stop()86{87WITH_SEMAPHORE(state_sem);88_requested_status = Status::NOT_STARTED;89_status_set_requested = true;90}9192void CompassCalibrator::set_orientation(enum Rotation orientation, bool is_external, bool fix_orientation, bool always_45_deg)93{94WITH_SEMAPHORE(state_sem);95cal_settings.check_orientation = true;96cal_settings.orientation = orientation;97cal_settings.orig_orientation = orientation;98cal_settings.is_external = is_external;99cal_settings.fix_orientation = fix_orientation;100cal_settings.always_45_deg = always_45_deg;101}102103void CompassCalibrator::start(bool retry, float delay, uint16_t offset_max, uint8_t compass_idx, float tolerance)104{105if (compass_idx > COMPASS_MAX_INSTANCES) {106return;107}108109WITH_SEMAPHORE(state_sem);110// Don't do this while we are already started111if (_running()) {112return;113}114cal_settings.offset_max = offset_max;115cal_settings.attempt = 1;116cal_settings.retry = retry;117cal_settings.delay_start_sec = delay;118cal_settings.start_time_ms = AP_HAL::millis();119cal_settings.compass_idx = compass_idx;120cal_settings.tolerance = tolerance;121122// Request status change to Waiting to start123_requested_status = Status::WAITING_TO_START;124_status_set_requested = true;125}126127// Record point mag sample and associated attitude sample to intermediate struct128void CompassCalibrator::new_sample(const Vector3f& sample)129{130WITH_SEMAPHORE(sample_sem);131_last_sample.set(sample);132_last_sample.att.set_from_ahrs();133_new_sample = true;134}135136bool CompassCalibrator::failed() {137WITH_SEMAPHORE(state_sem);138switch (cal_state.status) {139case Status::FAILED:140case Status::BAD_ORIENTATION:141case Status::BAD_RADIUS:142return true;143case Status::SUCCESS:144case Status::NOT_STARTED:145case Status::WAITING_TO_START:146case Status::RUNNING_STEP_ONE:147case Status::RUNNING_STEP_TWO:148return false;149}150151// compiler guarantees we don't get here152return true;153}154155156bool CompassCalibrator::running() {157WITH_SEMAPHORE(state_sem);158return (cal_state.status == Status::RUNNING_STEP_ONE || cal_state.status == Status::RUNNING_STEP_TWO);159}160161const CompassCalibrator::Report CompassCalibrator::get_report() {162WITH_SEMAPHORE(state_sem);163return cal_report;164}165166const CompassCalibrator::State CompassCalibrator::get_state() {167WITH_SEMAPHORE(state_sem);168return cal_state;169}170/////////////////////////////////////////////////////////////171////////////////////// PRIVATE METHODS //////////////////////172/////////////////////////////////////////////////////////////173174void CompassCalibrator::update()175{176177//pickup samples from intermediate struct178pull_sample();179180{181WITH_SEMAPHORE(state_sem);182//update_settings183if (!running()) {184update_cal_settings();185}186187//update requested state188if (_status_set_requested) {189_status_set_requested = false;190set_status(_requested_status);191}192//update report and status193update_cal_status();194update_cal_report();195}196197// collect the minimum number of samples198if (!_fitting()) {199return;200}201202if (_status == Status::RUNNING_STEP_ONE) {203if (_fit_step >= 10) {204if (is_equal(_fitness, _initial_fitness) || isnan(_fitness)) { // if true, means that fitness is diverging instead of converging205set_status(Status::FAILED);206} else {207set_status(Status::RUNNING_STEP_TWO);208}209} else {210if (_fit_step == 0) {211calc_initial_offset();212}213run_sphere_fit();214_fit_step++;215}216} else if (_status == Status::RUNNING_STEP_TWO) {217if (_fit_step >= 35) {218if (fit_acceptable() && fix_radius() && calculate_orientation()) {219set_status(Status::SUCCESS);220} else {221set_status(Status::FAILED);222}223} else if (_fit_step < 15) {224run_sphere_fit();225_fit_step++;226} else {227run_ellipsoid_fit();228_fit_step++;229}230}231}232233void CompassCalibrator::pull_sample()234{235CompassSample mag_sample;236{237WITH_SEMAPHORE(sample_sem);238if (!_new_sample) {239return;240}241if (_status == Status::WAITING_TO_START) {242set_status(Status::RUNNING_STEP_ONE);243}244_new_sample = false;245mag_sample = _last_sample;246}247if (_running() && _samples_collected < COMPASS_CAL_NUM_SAMPLES && accept_sample(mag_sample.get())) {248update_completion_mask(mag_sample.get());249_sample_buffer[_samples_collected] = mag_sample;250_samples_collected++;251}252}253254255void CompassCalibrator::update_cal_settings()256{257_tolerance = cal_settings.tolerance;258_check_orientation = cal_settings.check_orientation;259_orientation = cal_settings.orientation;260_orig_orientation = cal_settings.orig_orientation;261_is_external = cal_settings.is_external;262_fix_orientation = cal_settings.fix_orientation;263_offset_max = cal_settings.offset_max;264_attempt = cal_settings.attempt;265_retry = cal_settings.retry;266_delay_start_sec = cal_settings.delay_start_sec;267_start_time_ms = cal_settings.start_time_ms;268_compass_idx = cal_settings.compass_idx;269_always_45_deg = cal_settings.always_45_deg;270}271272// update completion mask based on latest sample273// used to ensure we have collected samples in all directions274void CompassCalibrator::update_completion_mask(const Vector3f& v)275{276Matrix3f softiron {277_params.diag.x, _params.offdiag.x, _params.offdiag.y,278_params.offdiag.x, _params.diag.y, _params.offdiag.z,279_params.offdiag.y, _params.offdiag.z, _params.diag.z280};281Vector3f corrected = softiron * (v + _params.offset);282int section = AP_GeodesicGrid::section(corrected, true);283if (section < 0) {284return;285}286_completion_mask[section / 8] |= 1 << (section % 8);287}288289// reset and update the completion mask using all samples in the sample buffer290void CompassCalibrator::update_completion_mask()291{292memset(_completion_mask, 0, sizeof(_completion_mask));293for (int i = 0; i < _samples_collected; i++) {294update_completion_mask(_sample_buffer[i].get());295}296}297298void CompassCalibrator::update_cal_status()299{300cal_state.status = _status;301cal_state.attempt = _attempt;302memcpy(cal_state.completion_mask, _completion_mask, sizeof(completion_mask_t));303cal_state.completion_pct = 0.0f;304// first sampling step is 1/3rd of the progress bar305// never return more than 99% unless _status is Status::SUCCESS306switch (_status) {307case Status::NOT_STARTED:308case Status::WAITING_TO_START:309cal_state.completion_pct = 0.0f;310break;311case Status::RUNNING_STEP_ONE:312cal_state.completion_pct = 33.3f * _samples_collected/COMPASS_CAL_NUM_SAMPLES;313break;314case Status::RUNNING_STEP_TWO:315cal_state.completion_pct = 33.3f + 65.7f*((float)(_samples_collected-_samples_thinned)/(COMPASS_CAL_NUM_SAMPLES-_samples_thinned));316break;317case Status::SUCCESS:318cal_state.completion_pct = 100.0f;319break;320case Status::FAILED:321case Status::BAD_ORIENTATION:322case Status::BAD_RADIUS:323cal_state.completion_pct = 0.0f;324break;325};326}327328329void CompassCalibrator::update_cal_report()330{331cal_report.status = _status;332cal_report.fitness = sqrtf(_fitness);333cal_report.ofs = _params.offset;334cal_report.diag = _params.diag;335cal_report.offdiag = _params.offdiag;336cal_report.scale_factor = _params.scale_factor;337cal_report.orientation_confidence = _orientation_confidence;338cal_report.original_orientation = _orig_orientation;339cal_report.orientation = _orientation_solution;340cal_report.check_orientation = _check_orientation;341}342343// running method for use in thread344bool CompassCalibrator::_running() const345{346return _status == Status::RUNNING_STEP_ONE || _status == Status::RUNNING_STEP_TWO;347}348349// fitting method for use in thread350bool CompassCalibrator::_fitting() const351{352return _running() && (_samples_collected == COMPASS_CAL_NUM_SAMPLES);353}354355// initialize fitness before starting a fit356void CompassCalibrator::initialize_fit()357{358if (_samples_collected != 0) {359_fitness = calc_mean_squared_residuals(_params);360} else {361_fitness = 1.0e30f;362}363_initial_fitness = _fitness;364_sphere_lambda = 1.0f;365_ellipsoid_lambda = 1.0f;366_fit_step = 0;367}368369void CompassCalibrator::reset_state()370{371_samples_collected = 0;372_samples_thinned = 0;373_params.radius = 200;374_params.offset.zero();375_params.diag = Vector3f(1.0f,1.0f,1.0f);376_params.offdiag.zero();377_params.scale_factor = 0;378379memset(_completion_mask, 0, sizeof(_completion_mask));380initialize_fit();381}382383bool CompassCalibrator::set_status(CompassCalibrator::Status status)384{385if (status != Status::NOT_STARTED && _status == status) {386return true;387}388389switch (status) {390case Status::NOT_STARTED:391reset_state();392_status = Status::NOT_STARTED;393if (_sample_buffer != nullptr) {394free(_sample_buffer);395_sample_buffer = nullptr;396}397return true;398399case Status::WAITING_TO_START:400reset_state();401_status = Status::WAITING_TO_START;402set_status(Status::RUNNING_STEP_ONE);403return true;404405case Status::RUNNING_STEP_ONE:406if (_status != Status::WAITING_TO_START) {407return false;408}409410// on first attempt delay start if requested by caller411if (_attempt == 1 && (AP_HAL::millis()-_start_time_ms)*1.0e-3f < _delay_start_sec) {412return false;413}414415if (_sample_buffer == nullptr) {416_sample_buffer = (CompassSample*)calloc(COMPASS_CAL_NUM_SAMPLES, sizeof(CompassSample));417}418if (_sample_buffer != nullptr) {419initialize_fit();420_status = Status::RUNNING_STEP_ONE;421return true;422}423return false;424425case Status::RUNNING_STEP_TWO:426if (_status != Status::RUNNING_STEP_ONE) {427return false;428}429thin_samples();430initialize_fit();431_status = Status::RUNNING_STEP_TWO;432return true;433434case Status::SUCCESS:435if (_status != Status::RUNNING_STEP_TWO) {436return false;437}438439if (_sample_buffer != nullptr) {440free(_sample_buffer);441_sample_buffer = nullptr;442}443444_status = Status::SUCCESS;445return true;446447case Status::FAILED:448if (_status == Status::BAD_ORIENTATION ||449_status == Status::BAD_RADIUS) {450// don't overwrite bad orientation status451return false;452}453FALLTHROUGH;454455case Status::BAD_ORIENTATION:456case Status::BAD_RADIUS:457if (_status == Status::NOT_STARTED) {458return false;459}460461if (_retry && set_status(Status::WAITING_TO_START)) {462_attempt++;463return true;464}465466if (_sample_buffer != nullptr) {467free(_sample_buffer);468_sample_buffer = nullptr;469}470471_status = status;472return true;473};474475// compiler guarantees we don't get here476return false;477}478479bool CompassCalibrator::fit_acceptable() const480{481if (!isnan(_fitness) &&482_params.radius > FIELD_RADIUS_MIN && _params.radius < FIELD_RADIUS_MAX &&483fabsf(_params.offset.x) < _offset_max &&484fabsf(_params.offset.y) < _offset_max &&485fabsf(_params.offset.z) < _offset_max &&486_params.diag.x > 0.2f && _params.diag.x < 5.0f &&487_params.diag.y > 0.2f && _params.diag.y < 5.0f &&488_params.diag.z > 0.2f && _params.diag.z < 5.0f &&489fabsf(_params.offdiag.x) < 1.0f && //absolute of sine/cosine output cannot be greater than 1490fabsf(_params.offdiag.y) < 1.0f &&491fabsf(_params.offdiag.z) < 1.0f ) {492return _fitness <= sq(_tolerance);493}494return false;495}496497void CompassCalibrator::thin_samples()498{499if (_sample_buffer == nullptr) {500return;501}502503_samples_thinned = 0;504// shuffle the samples http://en.wikipedia.org/wiki/Fisher%E2%80%93Yates_shuffle505// this is so that adjacent samples don't get sequentially eliminated506for (uint16_t i=_samples_collected-1; i>=1; i--) {507uint16_t j = get_random16() % (i+1);508CompassSample temp = _sample_buffer[i];509_sample_buffer[i] = _sample_buffer[j];510_sample_buffer[j] = temp;511}512513// remove any samples that are close together514for (uint16_t i=0; i < _samples_collected; i++) {515if (!accept_sample(_sample_buffer[i], i)) {516_sample_buffer[i] = _sample_buffer[_samples_collected-1];517_samples_collected--;518_samples_thinned++;519}520}521522update_completion_mask();523}524525/*526* The sample acceptance distance is determined as follows:527* For any regular polyhedron with triangular faces, the angle theta subtended528* by two closest points is defined as529*530* theta = arccos(cos(A)/(1-cos(A)))531*532* Where:533* A = (4pi/F + pi)/3534* and535* F = 2V - 4 is the number of faces for the polyhedron in consideration,536* which depends on the number of vertices V537*538* The above equation was proved after solving for spherical triangular excess539* and related equations.540*/541bool CompassCalibrator::accept_sample(const Vector3f& sample, uint16_t skip_index)542{543static const uint16_t faces = (2 * COMPASS_CAL_NUM_SAMPLES - 4);544static const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;545static const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));546547if (_sample_buffer == nullptr) {548return false;549}550551float min_distance = _params.radius * 2*sinf(theta/2);552553for (uint16_t i = 0; i<_samples_collected; i++) {554if (i != skip_index) {555float distance = (sample - _sample_buffer[i].get()).length();556if (distance < min_distance) {557return false;558}559}560}561return true;562}563564bool CompassCalibrator::accept_sample(const CompassSample& sample, uint16_t skip_index)565{566return accept_sample(sample.get(), skip_index);567}568569float CompassCalibrator::calc_residual(const Vector3f& sample, const param_t& params) const570{571Matrix3f softiron(572params.diag.x , params.offdiag.x , params.offdiag.y,573params.offdiag.x , params.diag.y , params.offdiag.z,574params.offdiag.y , params.offdiag.z , params.diag.z575);576return params.radius - (softiron*(sample+params.offset)).length();577}578579// calc the fitness given a set of parameters (offsets, diagonals, off diagonals)580float CompassCalibrator::calc_mean_squared_residuals(const param_t& params) const581{582if (_sample_buffer == nullptr || _samples_collected == 0) {583return 1.0e30f;584}585float sum = 0.0f;586for (uint16_t i=0; i < _samples_collected; i++) {587Vector3f sample = _sample_buffer[i].get();588float resid = calc_residual(sample, params);589sum += sq(resid);590}591sum /= _samples_collected;592return sum;593}594595// calculate initial offsets by simply taking the average values of the samples596void CompassCalibrator::calc_initial_offset()597{598// Set initial offset to the average value of the samples599_params.offset.zero();600for (uint16_t k = 0; k < _samples_collected; k++) {601_params.offset -= _sample_buffer[k].get();602}603_params.offset /= _samples_collected;604}605606void CompassCalibrator::calc_sphere_jacob(const Vector3f& sample, const param_t& params, float* ret) const607{608const Vector3f &offset = params.offset;609const Vector3f &diag = params.diag;610const Vector3f &offdiag = params.offdiag;611Matrix3f softiron(612diag.x , offdiag.x , offdiag.y,613offdiag.x , diag.y , offdiag.z,614offdiag.y , offdiag.z , diag.z615);616617float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));618float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));619float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));620float length = (softiron*(sample+offset)).length();621622// 0: partial derivative (radius wrt fitness fn) fn operated on sample623ret[0] = 1.0f;624// 1-3: partial derivative (offsets wrt fitness fn) fn operated on sample625ret[1] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);626ret[2] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);627ret[3] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);628}629630// run sphere fit to calculate diagonals and offdiagonals631void CompassCalibrator::run_sphere_fit()632{633if (_sample_buffer == nullptr) {634return;635}636637const float lma_damping = 10.0f;638639// take backup of fitness and parameters so we can determine later if this fit has improved the calibration640float fitness = _fitness;641float fit1, fit2;642param_t fit1_params, fit2_params;643fit1_params = fit2_params = _params;644645float JTJ[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };646float JTJ2[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };647float JTFI[COMPASS_CAL_NUM_SPHERE_PARAMS] = { };648649// Gauss Newton Part common for all kind of extensions including LM650for (uint16_t k = 0; k<_samples_collected; k++) {651Vector3f sample = _sample_buffer[k].get();652653float sphere_jacob[COMPASS_CAL_NUM_SPHERE_PARAMS];654655calc_sphere_jacob(sample, fit1_params, sphere_jacob);656657for (uint8_t i = 0;i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {658// compute JTJ659for (uint8_t j = 0; j < COMPASS_CAL_NUM_SPHERE_PARAMS; j++) {660JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j];661JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j]; //a backup JTJ for LM662}663// compute JTFI664JTFI[i] += sphere_jacob[i] * calc_residual(sample, fit1_params);665}666}667668//------------------------Levenberg-Marquardt-part-starts-here---------------------------------//669// refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter670for (uint8_t i = 0; i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {671JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda;672JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda/lma_damping;673}674675if (!mat_inverse(JTJ, JTJ, 4)) {676return;677}678679if (!mat_inverse(JTJ2, JTJ2, 4)) {680return;681}682683// extract radius, offset, diagonals and offdiagonal parameters684for (uint8_t row=0; row < COMPASS_CAL_NUM_SPHERE_PARAMS; row++) {685for (uint8_t col=0; col < COMPASS_CAL_NUM_SPHERE_PARAMS; col++) {686fit1_params.get_sphere_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];687fit2_params.get_sphere_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];688}689}690691// calculate fitness of two possible sets of parameters692fit1 = calc_mean_squared_residuals(fit1_params);693fit2 = calc_mean_squared_residuals(fit2_params);694695// decide which of the two sets of parameters is best and store in fit1_params696if (fit1 > _fitness && fit2 > _fitness) {697// if neither set of parameters provided better results, increase lambda698_sphere_lambda *= lma_damping;699} else if (fit2 < _fitness && fit2 < fit1) {700// if fit2 was better we will use it. decrease lambda701_sphere_lambda /= lma_damping;702fit1_params = fit2_params;703fitness = fit2;704} else if (fit1 < _fitness) {705fitness = fit1;706}707//--------------------Levenberg-Marquardt-part-ends-here--------------------------------//708709// store new parameters and update fitness710if (!isnan(fitness) && fitness < _fitness) {711_fitness = fitness;712_params = fit1_params;713update_completion_mask();714}715}716717void CompassCalibrator::calc_ellipsoid_jacob(const Vector3f& sample, const param_t& params, float* ret) const718{719const Vector3f &offset = params.offset;720const Vector3f &diag = params.diag;721const Vector3f &offdiag = params.offdiag;722Matrix3f softiron(723diag.x , offdiag.x , offdiag.y,724offdiag.x , diag.y , offdiag.z,725offdiag.y , offdiag.z , diag.z726);727728float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));729float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));730float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));731float length = (softiron*(sample+offset)).length();732733// 0-2: partial derivative (offset wrt fitness fn) fn operated on sample734ret[0] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);735ret[1] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);736ret[2] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);737// 3-5: partial derivative (diag offset wrt fitness fn) fn operated on sample738ret[3] = -1.0f * ((sample.x + offset.x) * A)/length;739ret[4] = -1.0f * ((sample.y + offset.y) * B)/length;740ret[5] = -1.0f * ((sample.z + offset.z) * C)/length;741// 6-8: partial derivative (off-diag offset wrt fitness fn) fn operated on sample742ret[6] = -1.0f * (((sample.y + offset.y) * A) + ((sample.x + offset.x) * B))/length;743ret[7] = -1.0f * (((sample.z + offset.z) * A) + ((sample.x + offset.x) * C))/length;744ret[8] = -1.0f * (((sample.z + offset.z) * B) + ((sample.y + offset.y) * C))/length;745}746747void CompassCalibrator::run_ellipsoid_fit()748{749if (_sample_buffer == nullptr) {750return;751}752753const float lma_damping = 10.0f;754755// take backup of fitness and parameters so we can determine later if this fit has improved the calibration756float fitness = _fitness;757float fit1, fit2;758param_t fit1_params, fit2_params;759fit1_params = fit2_params = _params;760761float JTJ[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };762float JTJ2[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };763float JTFI[COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };764765// Gauss Newton Part common for all kind of extensions including LM766for (uint16_t k = 0; k<_samples_collected; k++) {767Vector3f sample = _sample_buffer[k].get();768769float ellipsoid_jacob[COMPASS_CAL_NUM_ELLIPSOID_PARAMS];770771calc_ellipsoid_jacob(sample, fit1_params, ellipsoid_jacob);772773for (uint8_t i = 0;i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {774// compute JTJ775for (uint8_t j = 0; j < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; j++) {776JTJ [i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];777JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];778}779// compute JTFI780JTFI[i] += ellipsoid_jacob[i] * calc_residual(sample, fit1_params);781}782}783784//------------------------Levenberg-Marquardt-part-starts-here---------------------------------//785//refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter786for (uint8_t i = 0; i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {787JTJ[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda;788JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda/lma_damping;789}790791if (!mat_inverse(JTJ, JTJ, 9)) {792return;793}794795if (!mat_inverse(JTJ2, JTJ2, 9)) {796return;797}798799// extract radius, offset, diagonals and offdiagonal parameters800for (uint8_t row=0; row < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; row++) {801for (uint8_t col=0; col < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; col++) {802fit1_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];803fit2_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];804}805}806807// calculate fitness of two possible sets of parameters808fit1 = calc_mean_squared_residuals(fit1_params);809fit2 = calc_mean_squared_residuals(fit2_params);810811// decide which of the two sets of parameters is best and store in fit1_params812if (fit1 > _fitness && fit2 > _fitness) {813// if neither set of parameters provided better results, increase lambda814_ellipsoid_lambda *= lma_damping;815} else if (fit2 < _fitness && fit2 < fit1) {816// if fit2 was better we will use it. decrease lambda817_ellipsoid_lambda /= lma_damping;818fit1_params = fit2_params;819fitness = fit2;820} else if (fit1 < _fitness) {821fitness = fit1;822}823//--------------------Levenberg-part-ends-here--------------------------------//824825// store new parameters and update fitness826if (fitness < _fitness) {827_fitness = fitness;828_params = fit1_params;829update_completion_mask();830}831}832833834//////////////////////////////////////////////////////////835//////////// CompassSample public interface //////////////836//////////////////////////////////////////////////////////837838#define COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(__X) ((int16_t)constrain_float(roundf(__X*8.0f), INT16_MIN, INT16_MAX))839#define COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(__X) (__X/8.0f)840841Vector3f CompassCalibrator::CompassSample::get() const842{843return Vector3f(COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(x),844COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(y),845COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(z));846}847848void CompassCalibrator::CompassSample::set(const Vector3f &in)849{850x = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.x);851y = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.y);852z = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.z);853}854855void CompassCalibrator::AttitudeSample::set_from_ahrs(void)856{857const Matrix3f &dcm = AP::ahrs().get_DCM_rotation_body_to_ned();858float roll_rad, pitch_rad, yaw_rad;859dcm.to_euler(&roll_rad, &pitch_rad, &yaw_rad);860roll = constrain_int16(127 * (roll_rad / M_PI), -INT8_MAX, INT8_MAX);861pitch = constrain_int16(127 * (pitch_rad / M_PI_2), -INT8_MAX, INT8_MAX);862yaw = constrain_int16(127 * (yaw_rad / M_PI), -INT8_MAX, INT8_MAX);863}864865Matrix3f CompassCalibrator::AttitudeSample::get_rotmat(void) const866{867float roll_rad, pitch_rad, yaw_rad;868roll_rad = roll * (M_PI / 127);869pitch_rad = pitch * (M_PI_2 / 127);870yaw_rad = yaw * (M_PI / 127);871Matrix3f dcm;872dcm.from_euler(roll_rad, pitch_rad, yaw_rad);873return dcm;874}875876/*877calculate the implied earth field for a compass sample and compass878rotation. This is used to check for consistency between879samples.880881If the orientation is correct then when rotated the same (or882similar) earth field should be given for all samples.883884Note that this earth field uses an arbitrary north reference, so it885may not match the true earth field.886*/887Vector3f CompassCalibrator::calculate_earth_field(CompassSample &sample, enum Rotation r)888{889Vector3f v = sample.get();890891// convert the sample back to sensor frame892v.rotate_inverse(_orientation);893894// rotate to body frame for this rotation895v.rotate(r);896897// apply offsets, rotating them for the orientation we are testing898Vector3f rot_offsets = _params.offset;899rot_offsets.rotate_inverse(_orientation);900901rot_offsets.rotate(r);902903v += rot_offsets;904905// rotate the sample from body frame back to earth frame906Matrix3f rot = sample.att.get_rotmat();907908Vector3f efield = rot * v;909910// earth field is the mag sample in earth frame911return efield;912}913914/*915calculate compass orientation using the attitude estimate associated916with each sample, and fix orientation on external compasses if917the feature is enabled918*/919bool CompassCalibrator::calculate_orientation(void)920{921if (!_check_orientation) {922// we are not checking orientation923return true;924}925926// this function is very slow927EXPECT_DELAY_MS(1000);928929// Skip 4 rotations, see: auto_rotation_index()930float variance[ROTATION_MAX-4] {};931932_orientation_solution = _orientation;933934for (uint8_t n=0; n < ARRAY_SIZE(variance); n++) {935Rotation r = auto_rotation_index(n);936937// calculate the average implied earth field across all samples938Vector3f total_ef {};939for (uint32_t i=0; i<_samples_collected; i++) {940Vector3f efield = calculate_earth_field(_sample_buffer[i], r);941total_ef += efield;942}943Vector3f avg_efield = total_ef / _samples_collected;944945// now calculate the square error for this rotation against the average earth field946for (uint32_t i=0; i<_samples_collected; i++) {947Vector3f efield = calculate_earth_field(_sample_buffer[i], r);948float err = (efield - avg_efield).length_squared();949// divide by number of samples collected to get the variance950variance[n] += err / _samples_collected;951}952}953954// find the rotation with the lowest variance955enum Rotation besti = ROTATION_NONE;956float bestv = variance[0];957enum Rotation besti_90 = ROTATION_NONE;958float bestv_90 = variance[0];959for (uint8_t n=0; n < ARRAY_SIZE(variance); n++) {960Rotation r = auto_rotation_index(n);961if (variance[n] < bestv) {962bestv = variance[n];963besti = r;964}965if (right_angle_rotation(r) && variance[n] < bestv_90) {966bestv_90 = variance[n];967besti_90 = r;968}969}970971972float second_best = besti==ROTATION_NONE?variance[1]:variance[0];973enum Rotation besti2 = besti==ROTATION_NONE?ROTATION_YAW_45:ROTATION_NONE;974float second_best_90 = besti_90==ROTATION_NONE?variance[2]:variance[0];975enum Rotation besti2_90 = besti_90==ROTATION_NONE?ROTATION_YAW_90:ROTATION_NONE;976for (uint8_t n=0; n < ARRAY_SIZE(variance); n++) {977Rotation r = auto_rotation_index(n);978if (besti != r) {979if (variance[n] < second_best) {980second_best = variance[n];981besti2 = r;982}983}984if (right_angle_rotation(r) && (besti_90 != r) && (variance[n] < second_best_90)) {985second_best_90 = variance[n];986besti2_90 = r;987}988}989990_orientation_confidence = second_best/bestv;991992bool pass;993if (besti == _orientation) {994// if the orientation matched then allow for a low threshold995pass = true;996} else {997if (_orientation_confidence > 4.0) {998// very confident, always pass999pass = true;10001001} else if (_always_45_deg && (_orientation_confidence > 2.0)) {1002// use same tolerance for all rotations1003pass = true;10041005} else {1006// just consider 90's1007_orientation_confidence = second_best_90 / bestv_90;1008pass = _orientation_confidence > 2.0;1009besti = besti_90;1010besti2 = besti2_90;1011}1012}1013if (!pass) {1014GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Mag(%u) bad orientation: %u/%u %.1f", _compass_idx,1015besti, besti2, (double)_orientation_confidence);1016(void)besti2;1017} else if (besti == _orientation) {1018// no orientation change1019GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mag(%u) good orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);1020} else if (!_is_external || !_fix_orientation) {1021GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Mag(%u) internal bad orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);1022} else {1023GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mag(%u) new orientation: %u was %u %.1f", _compass_idx, besti, _orientation, (double)_orientation_confidence);1024}10251026if (!pass) {1027set_status(Status::BAD_ORIENTATION);1028return false;1029}10301031if (_orientation == besti) {1032// no orientation change1033return true;1034}10351036if (!_is_external || !_fix_orientation) {1037// we won't change the orientation, but we set _orientation1038// for reporting purposes1039_orientation = besti;1040_orientation_solution = besti;1041set_status(Status::BAD_ORIENTATION);1042return false;1043}10441045// correct the offsets for the new orientation1046Vector3f rot_offsets = _params.offset;1047rot_offsets.rotate_inverse(_orientation);1048rot_offsets.rotate(besti);1049_params.offset = rot_offsets;10501051// rotate the samples for the new orientation1052for (uint32_t i=0; i<_samples_collected; i++) {1053Vector3f s = _sample_buffer[i].get();1054s.rotate_inverse(_orientation);1055s.rotate(besti);1056_sample_buffer[i].set(s);1057}10581059_orientation = besti;1060_orientation_solution = besti;10611062// re-run the fit to get the diagonals and off-diagonals for the1063// new orientation1064initialize_fit();1065run_sphere_fit();1066run_ellipsoid_fit();10671068return fit_acceptable();1069}10701071/*1072fix radius of the fit to compensate for sensor scale factor errors1073return false if radius is outside acceptable range1074*/1075bool CompassCalibrator::fix_radius(void)1076{1077Location loc;1078if (!AP::ahrs().get_location(loc) && !AP::ahrs().get_origin(loc)) {1079GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "MagCal: No location, fix_radius skipped");1080// we don't have a position, leave scale factor as 0. This1081// will disable use of WMM in the EKF. Users can manually set1082// scale factor after calibration if it is known1083_params.scale_factor = 0;1084return true;1085}1086float intensity;1087float declination;1088float inclination;1089AP_Declination::get_mag_field_ef(loc.lat * 1e-7f, loc.lng * 1e-7f, intensity, declination, inclination);10901091float expected_radius = intensity * 1000; // mGauss1092float correction = expected_radius / _params.radius;10931094if (correction > COMPASS_MAX_SCALE_FACTOR || correction < COMPASS_MIN_SCALE_FACTOR) {1095// don't allow more than 30% scale factor correction1096GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag(%u) bad radius %.0f expected %.0f",1097_compass_idx,1098_params.radius,1099expected_radius);1100set_status(Status::BAD_RADIUS);1101return false;1102}11031104_params.scale_factor = correction;11051106return true;1107}11081109// convert index to rotation, this allows to skip some rotations1110Rotation CompassCalibrator::auto_rotation_index(uint8_t n) const1111{1112if (n < ROTATION_PITCH_180_YAW_90) {1113return (Rotation)n;1114}1115// ROTATION_PITCH_180_YAW_90 (26) is the same as ROTATION_ROLL_180_YAW_90 (10)1116// ROTATION_PITCH_180_YAW_270 (27) is the same as ROTATION_ROLL_180_YAW_270 (14)1117n += 2;1118if (n < ROTATION_ROLL_90_PITCH_68_YAW_293) {1119return (Rotation)n;1120}1121// ROTATION_ROLL_90_PITCH_68_YAW_293 is for solo leg compass, not expecting to see this in other vehicles1122n += 1;1123if (n < ROTATION_PITCH_7) {1124return (Rotation)n;1125}1126// ROTATION_PITCH_7 is too close to ROTATION_NONE to tell the difference in compass cal1127n += 1;1128if (n < ROTATION_MAX) {1129return (Rotation)n;1130}1131INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);1132return ROTATION_NONE;1133};11341135bool CompassCalibrator::right_angle_rotation(Rotation r) const1136{1137switch (r) {1138case ROTATION_NONE:1139case ROTATION_YAW_90:1140case ROTATION_YAW_180:1141case ROTATION_YAW_270:1142case ROTATION_ROLL_180:1143case ROTATION_ROLL_180_YAW_90:1144case ROTATION_PITCH_180:1145case ROTATION_ROLL_180_YAW_270:1146case ROTATION_ROLL_90:1147case ROTATION_ROLL_90_YAW_90:1148case ROTATION_ROLL_270:1149case ROTATION_ROLL_270_YAW_90:1150case ROTATION_PITCH_90:1151case ROTATION_PITCH_270:1152case ROTATION_PITCH_180_YAW_90:1153case ROTATION_PITCH_180_YAW_270:1154case ROTATION_ROLL_90_PITCH_90:1155case ROTATION_ROLL_180_PITCH_90:1156case ROTATION_ROLL_270_PITCH_90:1157case ROTATION_ROLL_90_PITCH_180:1158case ROTATION_ROLL_270_PITCH_180:1159case ROTATION_ROLL_90_PITCH_270:1160case ROTATION_ROLL_180_PITCH_270:1161case ROTATION_ROLL_270_PITCH_270:1162case ROTATION_ROLL_90_PITCH_180_YAW_90:1163case ROTATION_ROLL_90_YAW_270:1164return true;11651166default:1167return false;1168}1169}11701171#endif // COMPASS_CAL_ENABLED117211731174