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/AP_Compass_Calibration.cpp
Views: 1798
#include <AP_HAL/AP_HAL.h>1#include <AP_Notify/AP_Notify.h>2#include <AP_GPS/AP_GPS.h>3#include <GCS_MAVLink/GCS.h>4#include <AP_AHRS/AP_AHRS.h>5#include <AP_InternalError/AP_InternalError.h>67#include "AP_Compass.h"89const extern AP_HAL::HAL& hal;1011#if COMPASS_CAL_ENABLED1213void Compass::cal_update()14{15if (hal.util->get_soft_armed()) {16return;17}1819bool running = false;2021for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {22if (_calibrator[i] == nullptr) {23continue;24}25if (_calibrator[i]->failed()) {26AP_Notify::events.compass_cal_failed = 1;27}2829if (_calibrator[i]->running()) {30running = true;31} else if (_cal_autosave && !_cal_saved[i] && _calibrator[i]->get_state().status == CompassCalibrator::Status::SUCCESS) {32_accept_calibration(uint8_t(i));33}34}3536AP_Notify::flags.compass_cal_running = running;3738if (is_calibrating()) {39_cal_has_run = true;40return;41} else if (_cal_has_run && _auto_reboot()) {42hal.scheduler->delay(1000);43hal.scheduler->reboot();44}45}4647bool Compass::_start_calibration(uint8_t i, bool retry, float delay)48{49if (!healthy(i)) {50return false;51}52if (!use_for_yaw(i)) {53return false;54}55Priority prio = Priority(i);5657#if COMPASS_MAX_INSTANCES > 158if (_priority_did_list[prio] != _priority_did_stored_list[prio]) {59GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal requires reboot after priority change");60return false;61}62#endif6364if (_calibrator[prio] == nullptr) {65_calibrator[prio] = NEW_NOTHROW CompassCalibrator();66if (_calibrator[prio] == nullptr) {67GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal object not initialised");68return false;69}70}7172if (option_set(Option::CAL_REQUIRE_GPS)) {73if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {74GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal requires GPS lock");75return false;76}77}78if (!is_calibrating()) {79AP_Notify::events.initiated_compass_cal = 1;80}8182if (_rotate_auto) {83enum Rotation r = _get_state(prio).external?(enum Rotation)_get_state(prio).orientation.get():ROTATION_NONE;84if (r < ROTATION_MAX) {85_calibrator[prio]->set_orientation(r, _get_state(prio).external, _rotate_auto>=2, _rotate_auto>=3);86}87}88_cal_saved[prio] = false;89if (i == 0 && _get_state(prio).external != 0) {90_calibrator[prio]->start(retry, delay, get_offsets_max(), i, _calibration_threshold);91} else {92// internal compasses or secondary compasses get twice the93// threshold. This is because internal compasses tend to be a94// lot noisier95_calibrator[prio]->start(retry, delay, get_offsets_max(), i, _calibration_threshold*2);96}97if (!_cal_thread_started) {98_cal_requires_reboot = true;99if (!hal.scheduler->thread_create(FUNCTOR_BIND(this, &Compass::_update_calibration_trampoline, void), "compasscal", 2048, AP_HAL::Scheduler::PRIORITY_IO, 0)) {100GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "CompassCalibrator: Cannot start compass thread.");101return false;102}103_cal_thread_started = true;104}105106// disable compass learning both for calibration and after completion107_learn.set_and_save(0);108109return true;110}111112void Compass::_update_calibration_trampoline() {113while(true) {114for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {115if (_calibrator[i] == nullptr) {116continue;117}118_calibrator[i]->update();119}120hal.scheduler->delay(1);121}122}123124bool Compass::_start_calibration_mask(uint8_t mask, bool retry, bool autosave, float delay, bool autoreboot)125{126_cal_autosave = autosave;127_compass_cal_autoreboot = autoreboot;128129bool at_least_one_started = false;130for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {131if ((1<<i) & mask) {132if (!_start_calibration(i,retry,delay)) {133_cancel_calibration_mask(mask);134return false;135}136at_least_one_started = true;137}138}139return at_least_one_started;140}141142bool Compass::start_calibration_all(bool retry, bool autosave, float delay, bool autoreboot)143{144_cal_autosave = autosave;145_compass_cal_autoreboot = autoreboot;146147bool at_least_one_started = false;148for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {149// ignore any compasses that fail to start calibrating150// start all should only calibrate compasses that are being used151if (_start_calibration(i,retry,delay)) {152at_least_one_started = true;153}154}155return at_least_one_started;156}157158void Compass::_cancel_calibration(uint8_t i)159{160AP_Notify::events.initiated_compass_cal = 0;161Priority prio = Priority(i);162if (_calibrator[prio] == nullptr) {163return;164}165if (_calibrator[prio]->running() || _calibrator[prio]->get_state().status == CompassCalibrator::Status::WAITING_TO_START) {166AP_Notify::events.compass_cal_canceled = 1;167}168_cal_saved[prio] = false;169_calibrator[prio]->stop();170}171172void Compass::_cancel_calibration_mask(uint8_t mask)173{174for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {175if ((1<<i) & mask) {176_cancel_calibration(i);177}178}179}180181void Compass::cancel_calibration_all()182{183_cancel_calibration_mask(0xFF);184}185186bool Compass::_accept_calibration(uint8_t i)187{188Priority prio = Priority(i);189190CompassCalibrator* cal = _calibrator[prio];191if (cal == nullptr) {192return false;193}194const CompassCalibrator::Report cal_report = cal->get_report();195196if (_cal_saved[prio] || cal_report.status == CompassCalibrator::Status::NOT_STARTED) {197return true;198} else if (cal_report.status == CompassCalibrator::Status::SUCCESS) {199_cal_saved[prio] = true;200201Vector3f ofs(cal_report.ofs), diag(cal_report.diag), offdiag(cal_report.offdiag);202float scale_factor = cal_report.scale_factor;203204set_and_save_offsets(i, ofs);205#if AP_COMPASS_DIAGONALS_ENABLED206set_and_save_diagonals(i,diag);207set_and_save_offdiagonals(i,offdiag);208#endif209set_and_save_scale_factor(i,scale_factor);210211if (cal_report.check_orientation && _get_state(prio).external && _rotate_auto >= 2) {212set_and_save_orientation(i, cal_report.orientation);213}214215if (!is_calibrating()) {216AP_Notify::events.compass_cal_saved = 1;217}218return true;219} else {220return false;221}222}223224bool Compass::_accept_calibration_mask(uint8_t mask)225{226bool success = true;227for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {228if (_calibrator[i] == nullptr) {229continue;230}231if ((1<<uint8_t(i)) & mask) {232if (!_accept_calibration(uint8_t(i))) {233success = false;234}235_calibrator[i]->stop();236}237}238239return success;240}241242#if HAL_GCS_ENABLED243bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link)244{245const mavlink_channel_t chan = link.get_chan();246247for (uint8_t i = 0; i < COMPASS_MAX_INSTANCES; i++) {248const Priority compass_id = (next_cal_progress_idx[chan] + 1) % COMPASS_MAX_INSTANCES;249250auto& calibrator = _calibrator[compass_id];251if (calibrator == nullptr) {252next_cal_progress_idx[chan] = compass_id;253continue;254}255const CompassCalibrator::State cal_state = calibrator->get_state();256257if (cal_state.status == CompassCalibrator::Status::WAITING_TO_START ||258cal_state.status == CompassCalibrator::Status::RUNNING_STEP_ONE ||259cal_state.status == CompassCalibrator::Status::RUNNING_STEP_TWO) {260// ensure we don't try to send with no space available261if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_PROGRESS)) {262return false;263}264265next_cal_progress_idx[chan] = compass_id;266267mavlink_msg_mag_cal_progress_send(268link.get_chan(),269uint8_t(compass_id),270_get_cal_mask(),271(uint8_t)cal_state.status, cal_state.attempt, cal_state.completion_pct, cal_state.completion_mask,2720.0f, 0.0f, 0.0f273);274} else {275next_cal_progress_idx[chan] = compass_id;276}277}278279return true;280}281282bool Compass::send_mag_cal_report(const GCS_MAVLINK& link)283{284const mavlink_channel_t chan = link.get_chan();285286for (uint8_t i = 0; i < COMPASS_MAX_INSTANCES; i++) {287const Priority compass_id = (next_cal_report_idx[chan] + 1) % COMPASS_MAX_INSTANCES;288289if (_calibrator[compass_id] == nullptr) {290next_cal_report_idx[chan] = compass_id;291continue;292}293const CompassCalibrator::Report cal_report = _calibrator[compass_id]->get_report();294switch (cal_report.status) {295case CompassCalibrator::Status::NOT_STARTED:296case CompassCalibrator::Status::WAITING_TO_START:297case CompassCalibrator::Status::RUNNING_STEP_ONE:298case CompassCalibrator::Status::RUNNING_STEP_TWO:299// calibration has not finished ergo no report300next_cal_report_idx[chan] = compass_id;301continue;302case CompassCalibrator::Status::SUCCESS:303case CompassCalibrator::Status::FAILED:304case CompassCalibrator::Status::BAD_ORIENTATION:305case CompassCalibrator::Status::BAD_RADIUS:306// ensure we don't try to send with no space available307if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_REPORT)) {308return false;309}310311next_cal_report_idx[chan] = compass_id;312313mavlink_msg_mag_cal_report_send(314link.get_chan(),315uint8_t(compass_id),316_get_cal_mask(),317(uint8_t)cal_report.status,318_cal_saved[compass_id],319cal_report.fitness,320cal_report.ofs.x, cal_report.ofs.y, cal_report.ofs.z,321cal_report.diag.x, cal_report.diag.y, cal_report.diag.z,322cal_report.offdiag.x, cal_report.offdiag.y, cal_report.offdiag.z,323cal_report.orientation_confidence,324cal_report.original_orientation,325cal_report.orientation,326cal_report.scale_factor327);328}329}330return true;331}332#endif333334bool Compass::is_calibrating() const335{336for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {337if (_calibrator[i] == nullptr) {338continue;339}340switch(_calibrator[i]->get_state().status) {341case CompassCalibrator::Status::NOT_STARTED:342case CompassCalibrator::Status::SUCCESS:343case CompassCalibrator::Status::FAILED:344case CompassCalibrator::Status::BAD_ORIENTATION:345case CompassCalibrator::Status::BAD_RADIUS:346// this backend isn't calibrating,347// but maybe the next one is:348continue;349case CompassCalibrator::Status::WAITING_TO_START:350case CompassCalibrator::Status::RUNNING_STEP_ONE:351case CompassCalibrator::Status::RUNNING_STEP_TWO:352return true;353}354}355return false;356}357358uint8_t Compass::_get_cal_mask()359{360uint8_t cal_mask = 0;361for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {362if (_calibrator[i] == nullptr) {363continue;364}365if (_calibrator[i]->get_state().status != CompassCalibrator::Status::NOT_STARTED) {366cal_mask |= 1 << uint8_t(i);367}368}369return cal_mask;370}371372/*373handle an incoming MAG_CAL command374*/375MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_int_t &packet)376{377MAV_RESULT result = MAV_RESULT_FAILED;378379switch (packet.command) {380case MAV_CMD_DO_START_MAG_CAL: {381result = MAV_RESULT_ACCEPTED;382if (hal.util->get_soft_armed()) {383GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration");384result = MAV_RESULT_FAILED;385break;386}387if (packet.param1 < 0 || packet.param1 > 255) {388result = MAV_RESULT_FAILED;389break;390}391392uint8_t mag_mask = packet.param1;393bool retry = !is_zero(packet.param2);394bool autosave = !is_zero(packet.param3);395float delay = packet.param4;396bool autoreboot = packet.x != 0;397398if (mag_mask == 0) { // 0 means all399_reset_compass_id();400if (!start_calibration_all(retry, autosave, delay, autoreboot)) {401result = MAV_RESULT_FAILED;402}403} else {404if (!_start_calibration_mask(mag_mask, retry, autosave, delay, autoreboot)) {405result = MAV_RESULT_FAILED;406}407}408409break;410}411412case MAV_CMD_DO_ACCEPT_MAG_CAL: {413result = MAV_RESULT_ACCEPTED;414if (packet.param1 < 0 || packet.param1 > 255) {415result = MAV_RESULT_FAILED;416break;417}418419uint8_t mag_mask = packet.param1;420421if (mag_mask == 0) { // 0 means all422mag_mask = 0xFF;423}424425if (!_accept_calibration_mask(mag_mask)) {426result = MAV_RESULT_FAILED;427}428break;429}430431case MAV_CMD_DO_CANCEL_MAG_CAL: {432result = MAV_RESULT_ACCEPTED;433if (packet.param1 < 0 || packet.param1 > 255) {434result = MAV_RESULT_FAILED;435break;436}437438uint8_t mag_mask = packet.param1;439440if (mag_mask == 0) { // 0 means all441cancel_calibration_all();442break;443}444445_cancel_calibration_mask(mag_mask);446break;447}448}449450return result;451}452453#endif // COMPASS_CAL_ENABLED454455#if AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED456/*457get mag field with the effects of offsets, diagonals and458off-diagonals removed459*/460bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) const461{462// get corrected field463field = get_field(instance);464465#if AP_COMPASS_DIAGONALS_ENABLED466// form elliptical correction matrix and invert it. This is467// needed to remove the effects of the elliptical correction468// when calculating new offsets469const Vector3f &diagonals = get_diagonals(instance);470if (!diagonals.is_zero()) {471const Vector3f &offdiagonals = get_offdiagonals(instance);472Matrix3f mat {473diagonals.x, offdiagonals.x, offdiagonals.y,474offdiagonals.x, diagonals.y, offdiagonals.z,475offdiagonals.y, offdiagonals.z, diagonals.z476};477if (!mat.invert()) {478return false;479}480481// remove impact of diagonals and off-diagonals482field = mat * field;483}484#endif485486// remove impact of offsets487field -= get_offsets(instance);488489return true;490}491492/*493fast compass calibration given vehicle position and yaw. This494results in zero diagonal and off-diagonal elements, so is only495suitable for vehicles where the field is close to spherical. It is496useful for large vehicles where moving the vehicle to calibrate it497is difficult.498499The offsets of the selected compasses are set to values to bring500them into consistency with the WMM tables at the given latitude and501longitude. If compass_mask is zero then all enabled compasses are502calibrated.503504This assumes that the compass is correctly scaled in milliGauss505*/506bool Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,507float lat_deg, float lon_deg, bool force_use)508{509_reset_compass_id();510if (is_zero(lat_deg) && is_zero(lon_deg)) {511Location loc;512// get AHRS position. If unavailable then try GPS location513if (!AP::ahrs().get_location(loc)) {514if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {515GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag: no position available");516return false;517}518loc = AP::gps().location();519}520lat_deg = loc.lat * 1.0e-7;521lon_deg = loc.lng * 1.0e-7;522}523524// get the magnetic field intensity and orientation525float intensity;526float declination;527float inclination;528if (!AP_Declination::get_mag_field_ef(lat_deg, lon_deg, intensity, declination, inclination)) {529GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag: WMM table error");530return false;531}532533// create a field vector and rotate to the required orientation534Vector3f field(1e3f * intensity, 0.0f, 0.0f);535Matrix3f R;536R.from_euler(0.0f, -ToRad(inclination), ToRad(declination));537field = R * field;538539Matrix3f dcm;540dcm.from_euler(AP::ahrs().get_roll(), AP::ahrs().get_pitch(), radians(yaw_deg));541542// Rotate into body frame using provided yaw543field = dcm.transposed() * field;544545for (uint8_t i=0; i<get_count(); i++) {546if (compass_mask != 0 && ((1U<<i) & compass_mask) == 0) {547// skip this compass548continue;549}550if (_use_for_yaw[Priority(i)] == 0 || (!force_use && !use_for_yaw(i))) {551continue;552}553if (!healthy(i)) {554GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag[%u]: unhealthy\n", i);555return false;556}557558Vector3f measurement;559if (!get_uncorrected_field(i, measurement)) {560GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag[%u]: bad uncorrected field", i);561return false;562}563564Vector3f offsets = field - measurement;565set_and_save_offsets(i, offsets);566#if AP_COMPASS_DIAGONALS_ENABLED567Vector3f one{1,1,1};568set_and_save_diagonals(i, one);569Vector3f zero{0,0,0};570set_and_save_offdiagonals(i, zero);571#endif572}573574return true;575}576577#endif // AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED578579580