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_Compass/CompassCalibrator.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.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 9507475extern const AP_HAL::HAL& hal;7677////////////////////////////////////////////////////////////78///////////////////// PUBLIC INTERFACE /////////////////////79////////////////////////////////////////////////////////////8081CompassCalibrator::CompassCalibrator()82{83set_status(Status::NOT_STARTED);84}8586// Request to cancel calibration87void CompassCalibrator::stop()88{89WITH_SEMAPHORE(state_sem);90_requested_status = Status::NOT_STARTED;91_status_set_requested = true;92}9394void CompassCalibrator::set_orientation(enum Rotation orientation, bool is_external, bool fix_orientation, bool always_45_deg)95{96WITH_SEMAPHORE(state_sem);97cal_settings.check_orientation = true;98cal_settings.orientation = orientation;99cal_settings.orig_orientation = orientation;100cal_settings.is_external = is_external;101cal_settings.fix_orientation = fix_orientation;102cal_settings.always_45_deg = always_45_deg;103}104105void CompassCalibrator::start(bool retry, float delay, uint16_t offset_max, uint8_t compass_idx, float tolerance)106{107if (compass_idx > COMPASS_MAX_INSTANCES) {108return;109}110111WITH_SEMAPHORE(state_sem);112// Don't do this while we are already started113if (_running()) {114return;115}116cal_settings.offset_max = offset_max;117cal_settings.attempt = 1;118cal_settings.retry = retry;119cal_settings.delay_start_sec = delay;120cal_settings.start_time_ms = AP_HAL::millis();121cal_settings.compass_idx = compass_idx;122cal_settings.tolerance = tolerance;123124// Request status change to Waiting to start125_requested_status = Status::WAITING_TO_START;126_status_set_requested = true;127}128129// Record point mag sample and associated attitude sample to intermediate struct130void CompassCalibrator::new_sample(const Vector3f& sample)131{132WITH_SEMAPHORE(sample_sem);133_last_sample.set(sample);134_last_sample.att.set_from_ahrs();135_new_sample = true;136}137138bool CompassCalibrator::failed() {139WITH_SEMAPHORE(state_sem);140switch (cal_state.status) {141case Status::FAILED:142case Status::BAD_ORIENTATION:143case Status::BAD_RADIUS:144return true;145case Status::SUCCESS:146case Status::NOT_STARTED:147case Status::WAITING_TO_START:148case Status::RUNNING_STEP_ONE:149case Status::RUNNING_STEP_TWO:150return false;151}152153// compiler guarantees we don't get here154return true;155}156157158bool CompassCalibrator::running() {159WITH_SEMAPHORE(state_sem);160return (cal_state.status == Status::RUNNING_STEP_ONE || cal_state.status == Status::RUNNING_STEP_TWO);161}162163const CompassCalibrator::Report CompassCalibrator::get_report() {164WITH_SEMAPHORE(state_sem);165return cal_report;166}167168const CompassCalibrator::State CompassCalibrator::get_state() {169WITH_SEMAPHORE(state_sem);170return cal_state;171}172/////////////////////////////////////////////////////////////173////////////////////// PRIVATE METHODS //////////////////////174/////////////////////////////////////////////////////////////175176void CompassCalibrator::update()177{178179//pickup samples from intermediate struct180pull_sample();181182{183WITH_SEMAPHORE(state_sem);184//update_settings185if (!running()) {186update_cal_settings();187}188189//update requested state190if (_status_set_requested) {191_status_set_requested = false;192set_status(_requested_status);193}194//update report and status195update_cal_status();196update_cal_report();197}198199// collect the minimum number of samples200if (!_fitting()) {201return;202}203204if (_status == Status::RUNNING_STEP_ONE) {205if (_fit_step >= 10) {206if (is_equal(_fitness, _initial_fitness) || isnan(_fitness)) { // if true, means that fitness is diverging instead of converging207set_status(Status::FAILED);208} else {209set_status(Status::RUNNING_STEP_TWO);210}211} else {212if (_fit_step == 0) {213calc_initial_offset();214}215run_sphere_fit();216_fit_step++;217}218} else if (_status == Status::RUNNING_STEP_TWO) {219if (_fit_step >= 35) {220if (fit_acceptable() && fix_radius() && calculate_orientation()) {221set_status(Status::SUCCESS);222} else {223set_status(Status::FAILED);224}225} else if (_fit_step < 15) {226run_sphere_fit();227_fit_step++;228} else {229run_ellipsoid_fit();230_fit_step++;231}232}233}234235void CompassCalibrator::pull_sample()236{237CompassSample mag_sample;238{239WITH_SEMAPHORE(sample_sem);240if (!_new_sample) {241return;242}243if (_status == Status::WAITING_TO_START) {244set_status(Status::RUNNING_STEP_ONE);245}246_new_sample = false;247mag_sample = _last_sample;248}249if (_running() && _samples_collected < COMPASS_CAL_NUM_SAMPLES && accept_sample(mag_sample.get())) {250update_completion_mask(mag_sample.get());251_sample_buffer[_samples_collected] = mag_sample;252_samples_collected++;253}254}255256257void CompassCalibrator::update_cal_settings()258{259_tolerance = cal_settings.tolerance;260_check_orientation = cal_settings.check_orientation;261_orientation = cal_settings.orientation;262_orig_orientation = cal_settings.orig_orientation;263_is_external = cal_settings.is_external;264_fix_orientation = cal_settings.fix_orientation;265_offset_max = cal_settings.offset_max;266_attempt = cal_settings.attempt;267_retry = cal_settings.retry;268_delay_start_sec = cal_settings.delay_start_sec;269_start_time_ms = cal_settings.start_time_ms;270_compass_idx = cal_settings.compass_idx;271_always_45_deg = cal_settings.always_45_deg;272}273274// update completion mask based on latest sample275// used to ensure we have collected samples in all directions276void CompassCalibrator::update_completion_mask(const Vector3f& v)277{278Matrix3f softiron {279_params.diag.x, _params.offdiag.x, _params.offdiag.y,280_params.offdiag.x, _params.diag.y, _params.offdiag.z,281_params.offdiag.y, _params.offdiag.z, _params.diag.z282};283Vector3f corrected = softiron * (v + _params.offset);284int section = AP_GeodesicGrid::section(corrected, true);285if (section < 0) {286return;287}288_completion_mask[section / 8] |= 1 << (section % 8);289}290291// reset and update the completion mask using all samples in the sample buffer292void CompassCalibrator::update_completion_mask()293{294memset(_completion_mask, 0, sizeof(_completion_mask));295for (int i = 0; i < _samples_collected; i++) {296update_completion_mask(_sample_buffer[i].get());297}298}299300void CompassCalibrator::update_cal_status()301{302cal_state.status = _status;303cal_state.attempt = _attempt;304memcpy(cal_state.completion_mask, _completion_mask, sizeof(completion_mask_t));305cal_state.completion_pct = 0.0f;306// first sampling step is 1/3rd of the progress bar307// never return more than 99% unless _status is Status::SUCCESS308switch (_status) {309case Status::NOT_STARTED:310case Status::WAITING_TO_START:311cal_state.completion_pct = 0.0f;312break;313case Status::RUNNING_STEP_ONE:314cal_state.completion_pct = 33.3f * _samples_collected/COMPASS_CAL_NUM_SAMPLES;315break;316case Status::RUNNING_STEP_TWO:317cal_state.completion_pct = 33.3f + 65.7f*((float)(_samples_collected-_samples_thinned)/(COMPASS_CAL_NUM_SAMPLES-_samples_thinned));318break;319case Status::SUCCESS:320cal_state.completion_pct = 100.0f;321break;322case Status::FAILED:323case Status::BAD_ORIENTATION:324case Status::BAD_RADIUS:325cal_state.completion_pct = 0.0f;326break;327};328}329330331void CompassCalibrator::update_cal_report()332{333cal_report.status = _status;334cal_report.fitness = sqrtf(_fitness);335cal_report.ofs = _params.offset;336cal_report.diag = _params.diag;337cal_report.offdiag = _params.offdiag;338cal_report.scale_factor = _params.scale_factor;339cal_report.orientation_confidence = _orientation_confidence;340cal_report.original_orientation = _orig_orientation;341cal_report.orientation = _orientation_solution;342cal_report.check_orientation = _check_orientation;343}344345// running method for use in thread346bool CompassCalibrator::_running() const347{348return _status == Status::RUNNING_STEP_ONE || _status == Status::RUNNING_STEP_TWO;349}350351// fitting method for use in thread352bool CompassCalibrator::_fitting() const353{354return _running() && (_samples_collected == COMPASS_CAL_NUM_SAMPLES);355}356357// initialize fitness before starting a fit358void CompassCalibrator::initialize_fit()359{360if (_samples_collected != 0) {361_fitness = calc_mean_squared_residuals(_params);362} else {363_fitness = 1.0e30f;364}365_initial_fitness = _fitness;366_sphere_lambda = 1.0f;367_ellipsoid_lambda = 1.0f;368_fit_step = 0;369}370371void CompassCalibrator::reset_state()372{373_samples_collected = 0;374_samples_thinned = 0;375_params.radius = 200;376_params.offset.zero();377_params.diag = Vector3f(1.0f,1.0f,1.0f);378_params.offdiag.zero();379_params.scale_factor = 0;380381memset(_completion_mask, 0, sizeof(_completion_mask));382initialize_fit();383}384385bool CompassCalibrator::set_status(CompassCalibrator::Status status)386{387if (status != Status::NOT_STARTED && _status == status) {388return true;389}390391switch (status) {392case Status::NOT_STARTED:393reset_state();394_status = Status::NOT_STARTED;395if (_sample_buffer != nullptr) {396free(_sample_buffer);397_sample_buffer = nullptr;398}399return true;400401case Status::WAITING_TO_START:402reset_state();403_status = Status::WAITING_TO_START;404set_status(Status::RUNNING_STEP_ONE);405return true;406407case Status::RUNNING_STEP_ONE:408if (_status != Status::WAITING_TO_START) {409return false;410}411412// on first attempt delay start if requested by caller413if (_attempt == 1 && (AP_HAL::millis()-_start_time_ms)*1.0e-3f < _delay_start_sec) {414return false;415}416417if (_sample_buffer == nullptr) {418_sample_buffer = (CompassSample*)calloc(COMPASS_CAL_NUM_SAMPLES, sizeof(CompassSample));419}420if (_sample_buffer != nullptr) {421initialize_fit();422_status = Status::RUNNING_STEP_ONE;423return true;424}425return false;426427case Status::RUNNING_STEP_TWO:428if (_status != Status::RUNNING_STEP_ONE) {429return false;430}431thin_samples();432initialize_fit();433_status = Status::RUNNING_STEP_TWO;434return true;435436case Status::SUCCESS:437if (_status != Status::RUNNING_STEP_TWO) {438return false;439}440441if (_sample_buffer != nullptr) {442free(_sample_buffer);443_sample_buffer = nullptr;444}445446_status = Status::SUCCESS;447return true;448449case Status::FAILED:450if (_status == Status::BAD_ORIENTATION ||451_status == Status::BAD_RADIUS) {452// don't overwrite bad orientation status453return false;454}455FALLTHROUGH;456457case Status::BAD_ORIENTATION:458case Status::BAD_RADIUS:459if (_status == Status::NOT_STARTED) {460return false;461}462463if (_retry && set_status(Status::WAITING_TO_START)) {464_attempt++;465return true;466}467468if (_sample_buffer != nullptr) {469free(_sample_buffer);470_sample_buffer = nullptr;471}472473_status = status;474return true;475};476477// compiler guarantees we don't get here478return false;479}480481bool CompassCalibrator::fit_acceptable() const482{483if (!isnan(_fitness) &&484_params.radius > FIELD_RADIUS_MIN && _params.radius < FIELD_RADIUS_MAX &&485fabsf(_params.offset.x) < _offset_max &&486fabsf(_params.offset.y) < _offset_max &&487fabsf(_params.offset.z) < _offset_max &&488_params.diag.x > 0.2f && _params.diag.x < 5.0f &&489_params.diag.y > 0.2f && _params.diag.y < 5.0f &&490_params.diag.z > 0.2f && _params.diag.z < 5.0f &&491fabsf(_params.offdiag.x) < 1.0f && //absolute of sine/cosine output cannot be greater than 1492fabsf(_params.offdiag.y) < 1.0f &&493fabsf(_params.offdiag.z) < 1.0f ) {494return _fitness <= sq(_tolerance);495}496return false;497}498499void CompassCalibrator::thin_samples()500{501if (_sample_buffer == nullptr) {502return;503}504505_samples_thinned = 0;506// shuffle the samples http://en.wikipedia.org/wiki/Fisher%E2%80%93Yates_shuffle507// this is so that adjacent samples don't get sequentially eliminated508for (uint16_t i=_samples_collected-1; i>=1; i--) {509uint16_t j = get_random16() % (i+1);510CompassSample temp = _sample_buffer[i];511_sample_buffer[i] = _sample_buffer[j];512_sample_buffer[j] = temp;513}514515// remove any samples that are close together516for (uint16_t i=0; i < _samples_collected; i++) {517if (!accept_sample(_sample_buffer[i], i)) {518_sample_buffer[i] = _sample_buffer[_samples_collected-1];519_samples_collected--;520_samples_thinned++;521}522}523524update_completion_mask();525}526527/*528* The sample acceptance distance is determined as follows:529* For any regular polyhedron with triangular faces, the angle theta subtended530* by two closest points is defined as531*532* theta = arccos(cos(A)/(1-cos(A)))533*534* Where:535* A = (4pi/F + pi)/3536* and537* F = 2V - 4 is the number of faces for the polyhedron in consideration,538* which depends on the number of vertices V539*540* The above equation was proved after solving for spherical triangular excess541* and related equations.542*/543bool CompassCalibrator::accept_sample(const Vector3f& sample, uint16_t skip_index)544{545static const uint16_t faces = (2 * COMPASS_CAL_NUM_SAMPLES - 4);546static const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f;547static const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a)));548549if (_sample_buffer == nullptr) {550return false;551}552553float min_distance = _params.radius * 2*sinf(theta/2);554555for (uint16_t i = 0; i<_samples_collected; i++) {556if (i != skip_index) {557float distance = (sample - _sample_buffer[i].get()).length();558if (distance < min_distance) {559return false;560}561}562}563return true;564}565566bool CompassCalibrator::accept_sample(const CompassSample& sample, uint16_t skip_index)567{568return accept_sample(sample.get(), skip_index);569}570571float CompassCalibrator::calc_residual(const Vector3f& sample, const param_t& params) const572{573Matrix3f softiron(574params.diag.x , params.offdiag.x , params.offdiag.y,575params.offdiag.x , params.diag.y , params.offdiag.z,576params.offdiag.y , params.offdiag.z , params.diag.z577);578return params.radius - (softiron*(sample+params.offset)).length();579}580581// calc the fitness given a set of parameters (offsets, diagonals, off diagonals)582float CompassCalibrator::calc_mean_squared_residuals(const param_t& params) const583{584if (_sample_buffer == nullptr || _samples_collected == 0) {585return 1.0e30f;586}587float sum = 0.0f;588for (uint16_t i=0; i < _samples_collected; i++) {589Vector3f sample = _sample_buffer[i].get();590float resid = calc_residual(sample, params);591sum += sq(resid);592}593sum /= _samples_collected;594return sum;595}596597// calculate initial offsets by simply taking the average values of the samples598void CompassCalibrator::calc_initial_offset()599{600// Set initial offset to the average value of the samples601_params.offset.zero();602for (uint16_t k = 0; k < _samples_collected; k++) {603_params.offset -= _sample_buffer[k].get();604}605_params.offset /= _samples_collected;606}607608void CompassCalibrator::calc_sphere_jacob(const Vector3f& sample, const param_t& params, float* ret) const609{610const Vector3f &offset = params.offset;611const Vector3f &diag = params.diag;612const Vector3f &offdiag = params.offdiag;613Matrix3f softiron(614diag.x , offdiag.x , offdiag.y,615offdiag.x , diag.y , offdiag.z,616offdiag.y , offdiag.z , diag.z617);618619float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));620float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));621float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));622float length = (softiron*(sample+offset)).length();623624// 0: partial derivative (radius wrt fitness fn) fn operated on sample625ret[0] = 1.0f;626// 1-3: partial derivative (offsets wrt fitness fn) fn operated on sample627ret[1] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);628ret[2] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);629ret[3] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);630}631632// run sphere fit to calculate diagonals and offdiagonals633void CompassCalibrator::run_sphere_fit()634{635if (_sample_buffer == nullptr) {636return;637}638639const float lma_damping = 10.0f;640641// take backup of fitness and parameters so we can determine later if this fit has improved the calibration642float fitness = _fitness;643float fit1, fit2;644param_t fit1_params, fit2_params;645fit1_params = fit2_params = _params;646647float JTJ[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };648float JTJ2[COMPASS_CAL_NUM_SPHERE_PARAMS*COMPASS_CAL_NUM_SPHERE_PARAMS] = { };649float JTFI[COMPASS_CAL_NUM_SPHERE_PARAMS] = { };650651// Gauss Newton Part common for all kind of extensions including LM652for (uint16_t k = 0; k<_samples_collected; k++) {653Vector3f sample = _sample_buffer[k].get();654655float sphere_jacob[COMPASS_CAL_NUM_SPHERE_PARAMS];656657calc_sphere_jacob(sample, fit1_params, sphere_jacob);658659for (uint8_t i = 0;i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {660// compute JTJ661for (uint8_t j = 0; j < COMPASS_CAL_NUM_SPHERE_PARAMS; j++) {662JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j];663JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+j] += sphere_jacob[i] * sphere_jacob[j]; //a backup JTJ for LM664}665// compute JTFI666JTFI[i] += sphere_jacob[i] * calc_residual(sample, fit1_params);667}668}669670//------------------------Levenberg-Marquardt-part-starts-here---------------------------------//671// refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter672for (uint8_t i = 0; i < COMPASS_CAL_NUM_SPHERE_PARAMS; i++) {673JTJ[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda;674JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda/lma_damping;675}676677if (!mat_inverse(JTJ, JTJ, 4)) {678return;679}680681if (!mat_inverse(JTJ2, JTJ2, 4)) {682return;683}684685// extract radius, offset, diagonals and offdiagonal parameters686for (uint8_t row=0; row < COMPASS_CAL_NUM_SPHERE_PARAMS; row++) {687for (uint8_t col=0; col < COMPASS_CAL_NUM_SPHERE_PARAMS; col++) {688fit1_params.get_sphere_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];689fit2_params.get_sphere_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_SPHERE_PARAMS+col];690}691}692693// calculate fitness of two possible sets of parameters694fit1 = calc_mean_squared_residuals(fit1_params);695fit2 = calc_mean_squared_residuals(fit2_params);696697// decide which of the two sets of parameters is best and store in fit1_params698if (fit1 > _fitness && fit2 > _fitness) {699// if neither set of parameters provided better results, increase lambda700_sphere_lambda *= lma_damping;701} else if (fit2 < _fitness && fit2 < fit1) {702// if fit2 was better we will use it. decrease lambda703_sphere_lambda /= lma_damping;704fit1_params = fit2_params;705fitness = fit2;706} else if (fit1 < _fitness) {707fitness = fit1;708}709//--------------------Levenberg-Marquardt-part-ends-here--------------------------------//710711// store new parameters and update fitness712if (!isnan(fitness) && fitness < _fitness) {713_fitness = fitness;714_params = fit1_params;715update_completion_mask();716}717}718719void CompassCalibrator::calc_ellipsoid_jacob(const Vector3f& sample, const param_t& params, float* ret) const720{721const Vector3f &offset = params.offset;722const Vector3f &diag = params.diag;723const Vector3f &offdiag = params.offdiag;724Matrix3f softiron(725diag.x , offdiag.x , offdiag.y,726offdiag.x , diag.y , offdiag.z,727offdiag.y , offdiag.z , diag.z728);729730float A = (diag.x * (sample.x + offset.x)) + (offdiag.x * (sample.y + offset.y)) + (offdiag.y * (sample.z + offset.z));731float B = (offdiag.x * (sample.x + offset.x)) + (diag.y * (sample.y + offset.y)) + (offdiag.z * (sample.z + offset.z));732float C = (offdiag.y * (sample.x + offset.x)) + (offdiag.z * (sample.y + offset.y)) + (diag.z * (sample.z + offset.z));733float length = (softiron*(sample+offset)).length();734735// 0-2: partial derivative (offset wrt fitness fn) fn operated on sample736ret[0] = -1.0f * (((diag.x * A) + (offdiag.x * B) + (offdiag.y * C))/length);737ret[1] = -1.0f * (((offdiag.x * A) + (diag.y * B) + (offdiag.z * C))/length);738ret[2] = -1.0f * (((offdiag.y * A) + (offdiag.z * B) + (diag.z * C))/length);739// 3-5: partial derivative (diag offset wrt fitness fn) fn operated on sample740ret[3] = -1.0f * ((sample.x + offset.x) * A)/length;741ret[4] = -1.0f * ((sample.y + offset.y) * B)/length;742ret[5] = -1.0f * ((sample.z + offset.z) * C)/length;743// 6-8: partial derivative (off-diag offset wrt fitness fn) fn operated on sample744ret[6] = -1.0f * (((sample.y + offset.y) * A) + ((sample.x + offset.x) * B))/length;745ret[7] = -1.0f * (((sample.z + offset.z) * A) + ((sample.x + offset.x) * C))/length;746ret[8] = -1.0f * (((sample.z + offset.z) * B) + ((sample.y + offset.y) * C))/length;747}748749void CompassCalibrator::run_ellipsoid_fit()750{751if (_sample_buffer == nullptr) {752return;753}754755const float lma_damping = 10.0f;756757// take backup of fitness and parameters so we can determine later if this fit has improved the calibration758float fitness = _fitness;759float fit1, fit2;760param_t fit1_params, fit2_params;761fit1_params = fit2_params = _params;762763float JTJ[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };764float JTJ2[COMPASS_CAL_NUM_ELLIPSOID_PARAMS*COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };765float JTFI[COMPASS_CAL_NUM_ELLIPSOID_PARAMS] = { };766767// Gauss Newton Part common for all kind of extensions including LM768for (uint16_t k = 0; k<_samples_collected; k++) {769Vector3f sample = _sample_buffer[k].get();770771float ellipsoid_jacob[COMPASS_CAL_NUM_ELLIPSOID_PARAMS];772773calc_ellipsoid_jacob(sample, fit1_params, ellipsoid_jacob);774775for (uint8_t i = 0;i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {776// compute JTJ777for (uint8_t j = 0; j < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; j++) {778JTJ [i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];779JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+j] += ellipsoid_jacob[i] * ellipsoid_jacob[j];780}781// compute JTFI782JTFI[i] += ellipsoid_jacob[i] * calc_residual(sample, fit1_params);783}784}785786//------------------------Levenberg-Marquardt-part-starts-here---------------------------------//787//refer: http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm#Choice_of_damping_parameter788for (uint8_t i = 0; i < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; i++) {789JTJ[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda;790JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda/lma_damping;791}792793if (!mat_inverse(JTJ, JTJ, 9)) {794return;795}796797if (!mat_inverse(JTJ2, JTJ2, 9)) {798return;799}800801// extract radius, offset, diagonals and offdiagonal parameters802for (uint8_t row=0; row < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; row++) {803for (uint8_t col=0; col < COMPASS_CAL_NUM_ELLIPSOID_PARAMS; col++) {804fit1_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];805fit2_params.get_ellipsoid_params()[row] -= JTFI[col] * JTJ2[row*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+col];806}807}808809// calculate fitness of two possible sets of parameters810fit1 = calc_mean_squared_residuals(fit1_params);811fit2 = calc_mean_squared_residuals(fit2_params);812813// decide which of the two sets of parameters is best and store in fit1_params814if (fit1 > _fitness && fit2 > _fitness) {815// if neither set of parameters provided better results, increase lambda816_ellipsoid_lambda *= lma_damping;817} else if (fit2 < _fitness && fit2 < fit1) {818// if fit2 was better we will use it. decrease lambda819_ellipsoid_lambda /= lma_damping;820fit1_params = fit2_params;821fitness = fit2;822} else if (fit1 < _fitness) {823fitness = fit1;824}825//--------------------Levenberg-part-ends-here--------------------------------//826827// store new parameters and update fitness828if (fitness < _fitness) {829_fitness = fitness;830_params = fit1_params;831update_completion_mask();832}833}834835836//////////////////////////////////////////////////////////837//////////// CompassSample public interface //////////////838//////////////////////////////////////////////////////////839840#define COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(__X) ((int16_t)constrain_float(roundf(__X*8.0f), INT16_MIN, INT16_MAX))841#define COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(__X) (__X/8.0f)842843Vector3f CompassCalibrator::CompassSample::get() const844{845return Vector3f(COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(x),846COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(y),847COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(z));848}849850void CompassCalibrator::CompassSample::set(const Vector3f &in)851{852x = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.x);853y = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.y);854z = COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(in.z);855}856857void CompassCalibrator::AttitudeSample::set_from_ahrs(void)858{859const Matrix3f &dcm = AP::ahrs().get_DCM_rotation_body_to_ned();860float roll_rad, pitch_rad, yaw_rad;861dcm.to_euler(&roll_rad, &pitch_rad, &yaw_rad);862roll = constrain_int16(127 * (roll_rad / M_PI), -127, 127);863pitch = constrain_int16(127 * (pitch_rad / M_PI_2), -127, 127);864yaw = constrain_int16(127 * (yaw_rad / M_PI), -127, 127);865}866867Matrix3f CompassCalibrator::AttitudeSample::get_rotmat(void) const868{869float roll_rad, pitch_rad, yaw_rad;870roll_rad = roll * (M_PI / 127);871pitch_rad = pitch * (M_PI_2 / 127);872yaw_rad = yaw * (M_PI / 127);873Matrix3f dcm;874dcm.from_euler(roll_rad, pitch_rad, yaw_rad);875return dcm;876}877878/*879calculate the implied earth field for a compass sample and compass880rotation. This is used to check for consistency between881samples.882883If the orientation is correct then when rotated the same (or884similar) earth field should be given for all samples.885886Note that this earth field uses an arbitrary north reference, so it887may not match the true earth field.888*/889Vector3f CompassCalibrator::calculate_earth_field(CompassSample &sample, enum Rotation r)890{891Vector3f v = sample.get();892893// convert the sample back to sensor frame894v.rotate_inverse(_orientation);895896// rotate to body frame for this rotation897v.rotate(r);898899// apply offsets, rotating them for the orientation we are testing900Vector3f rot_offsets = _params.offset;901rot_offsets.rotate_inverse(_orientation);902903rot_offsets.rotate(r);904905v += rot_offsets;906907// rotate the sample from body frame back to earth frame908Matrix3f rot = sample.att.get_rotmat();909910Vector3f efield = rot * v;911912// earth field is the mag sample in earth frame913return efield;914}915916/*917calculate compass orientation using the attitude estimate associated918with each sample, and fix orientation on external compasses if919the feature is enabled920*/921bool CompassCalibrator::calculate_orientation(void)922{923if (!_check_orientation) {924// we are not checking orientation925return true;926}927928// this function is very slow929EXPECT_DELAY_MS(1000);930931// Skip 4 rotations, see: auto_rotation_index()932float variance[ROTATION_MAX-4] {};933934_orientation_solution = _orientation;935936for (uint8_t n=0; n < ARRAY_SIZE(variance); n++) {937Rotation r = auto_rotation_index(n);938939// calculate the average implied earth field across all samples940Vector3f total_ef {};941for (uint32_t i=0; i<_samples_collected; i++) {942Vector3f efield = calculate_earth_field(_sample_buffer[i], r);943total_ef += efield;944}945Vector3f avg_efield = total_ef / _samples_collected;946947// now calculate the square error for this rotation against the average earth field948for (uint32_t i=0; i<_samples_collected; i++) {949Vector3f efield = calculate_earth_field(_sample_buffer[i], r);950float err = (efield - avg_efield).length_squared();951// divide by number of samples collected to get the variance952variance[n] += err / _samples_collected;953}954}955956// find the rotation with the lowest variance957enum Rotation besti = ROTATION_NONE;958float bestv = variance[0];959enum Rotation besti_90 = ROTATION_NONE;960float bestv_90 = variance[0];961for (uint8_t n=0; n < ARRAY_SIZE(variance); n++) {962Rotation r = auto_rotation_index(n);963if (variance[n] < bestv) {964bestv = variance[n];965besti = r;966}967if (right_angle_rotation(r) && variance[n] < bestv_90) {968bestv_90 = variance[n];969besti_90 = r;970}971}972973974float second_best = besti==ROTATION_NONE?variance[1]:variance[0];975enum Rotation besti2 = besti==ROTATION_NONE?ROTATION_YAW_45:ROTATION_NONE;976float second_best_90 = besti_90==ROTATION_NONE?variance[2]:variance[0];977enum Rotation besti2_90 = besti_90==ROTATION_NONE?ROTATION_YAW_90:ROTATION_NONE;978for (uint8_t n=0; n < ARRAY_SIZE(variance); n++) {979Rotation r = auto_rotation_index(n);980if (besti != r) {981if (variance[n] < second_best) {982second_best = variance[n];983besti2 = r;984}985}986if (right_angle_rotation(r) && (besti_90 != r) && (variance[n] < second_best_90)) {987second_best_90 = variance[n];988besti2_90 = r;989}990}991992_orientation_confidence = second_best/bestv;993994bool pass;995if (besti == _orientation) {996// if the orientation matched then allow for a low threshold997pass = true;998} else {999if (_orientation_confidence > 4.0) {1000// very confident, always pass1001pass = true;10021003} else if (_always_45_deg && (_orientation_confidence > 2.0)) {1004// use same tolerance for all rotations1005pass = true;10061007} else {1008// just consider 90's1009_orientation_confidence = second_best_90 / bestv_90;1010pass = _orientation_confidence > 2.0;1011besti = besti_90;1012besti2 = besti2_90;1013}1014}1015if (!pass) {1016GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Mag(%u) bad orientation: %u/%u %.1f", _compass_idx,1017besti, besti2, (double)_orientation_confidence);1018(void)besti2;1019} else if (besti == _orientation) {1020// no orientation change1021GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mag(%u) good orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);1022} else if (!_is_external || !_fix_orientation) {1023GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Mag(%u) internal bad orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);1024} else {1025GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mag(%u) new orientation: %u was %u %.1f", _compass_idx, besti, _orientation, (double)_orientation_confidence);1026}10271028if (!pass) {1029set_status(Status::BAD_ORIENTATION);1030return false;1031}10321033if (_orientation == besti) {1034// no orientation change1035return true;1036}10371038if (!_is_external || !_fix_orientation) {1039// we won't change the orientation, but we set _orientation1040// for reporting purposes1041_orientation = besti;1042_orientation_solution = besti;1043set_status(Status::BAD_ORIENTATION);1044return false;1045}10461047// correct the offsets for the new orientation1048Vector3f rot_offsets = _params.offset;1049rot_offsets.rotate_inverse(_orientation);1050rot_offsets.rotate(besti);1051_params.offset = rot_offsets;10521053// rotate the samples for the new orientation1054for (uint32_t i=0; i<_samples_collected; i++) {1055Vector3f s = _sample_buffer[i].get();1056s.rotate_inverse(_orientation);1057s.rotate(besti);1058_sample_buffer[i].set(s);1059}10601061_orientation = besti;1062_orientation_solution = besti;10631064// re-run the fit to get the diagonals and off-diagonals for the1065// new orientation1066initialize_fit();1067run_sphere_fit();1068run_ellipsoid_fit();10691070return fit_acceptable();1071}10721073/*1074fix radius of the fit to compensate for sensor scale factor errors1075return false if radius is outside acceptable range1076*/1077bool CompassCalibrator::fix_radius(void)1078{1079Location loc;1080if (!AP::ahrs().get_location(loc) && !AP::ahrs().get_origin(loc)) {1081GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "MagCal: No location, fix_radius skipped");1082// we don't have a position, leave scale factor as 0. This1083// will disable use of WMM in the EKF. Users can manually set1084// scale factor after calibration if it is known1085_params.scale_factor = 0;1086return true;1087}1088float intensity;1089float declination;1090float inclination;1091AP_Declination::get_mag_field_ef(loc.lat * 1e-7f, loc.lng * 1e-7f, intensity, declination, inclination);10921093float expected_radius = intensity * 1000; // mGauss1094float correction = expected_radius / _params.radius;10951096if (correction > COMPASS_MAX_SCALE_FACTOR || correction < COMPASS_MIN_SCALE_FACTOR) {1097// don't allow more than 30% scale factor correction1098GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag(%u) bad radius %.0f expected %.0f",1099_compass_idx,1100_params.radius,1101expected_radius);1102set_status(Status::BAD_RADIUS);1103return false;1104}11051106_params.scale_factor = correction;11071108return true;1109}11101111// convert index to rotation, this allows to skip some rotations1112Rotation CompassCalibrator::auto_rotation_index(uint8_t n) const1113{1114if (n < ROTATION_PITCH_180_YAW_90) {1115return (Rotation)n;1116}1117// ROTATION_PITCH_180_YAW_90 (26) is the same as ROTATION_ROLL_180_YAW_90 (10)1118// ROTATION_PITCH_180_YAW_270 (27) is the same as ROTATION_ROLL_180_YAW_270 (14)1119n += 2;1120if (n < ROTATION_ROLL_90_PITCH_68_YAW_293) {1121return (Rotation)n;1122}1123// ROTATION_ROLL_90_PITCH_68_YAW_293 is for solo leg compass, not expecting to see this in other vehicles1124n += 1;1125if (n < ROTATION_PITCH_7) {1126return (Rotation)n;1127}1128// ROTATION_PITCH_7 is too close to ROTATION_NONE to tell the difference in compass cal1129n += 1;1130if (n < ROTATION_MAX) {1131return (Rotation)n;1132}1133INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);1134return ROTATION_NONE;1135};11361137bool CompassCalibrator::right_angle_rotation(Rotation r) const1138{1139switch (r) {1140case ROTATION_NONE:1141case ROTATION_YAW_90:1142case ROTATION_YAW_180:1143case ROTATION_YAW_270:1144case ROTATION_ROLL_180:1145case ROTATION_ROLL_180_YAW_90:1146case ROTATION_PITCH_180:1147case ROTATION_ROLL_180_YAW_270:1148case ROTATION_ROLL_90:1149case ROTATION_ROLL_90_YAW_90:1150case ROTATION_ROLL_270:1151case ROTATION_ROLL_270_YAW_90:1152case ROTATION_PITCH_90:1153case ROTATION_PITCH_270:1154case ROTATION_PITCH_180_YAW_90:1155case ROTATION_PITCH_180_YAW_270:1156case ROTATION_ROLL_90_PITCH_90:1157case ROTATION_ROLL_180_PITCH_90:1158case ROTATION_ROLL_270_PITCH_90:1159case ROTATION_ROLL_90_PITCH_180:1160case ROTATION_ROLL_270_PITCH_180:1161case ROTATION_ROLL_90_PITCH_270:1162case ROTATION_ROLL_180_PITCH_270:1163case ROTATION_ROLL_270_PITCH_270:1164case ROTATION_ROLL_90_PITCH_180_YAW_90:1165case ROTATION_ROLL_90_YAW_270:1166return true;11671168default:1169return false;1170}1171}11721173#endif // COMPASS_CAL_ENABLED117411751176