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_Backend.cpp
Views: 1798
#include "AP_Compass_config.h"12#if AP_COMPASS_ENABLED34#include <AP_HAL/AP_HAL.h>56#include "AP_Compass.h"7#include "AP_Compass_Backend.h"89#include <AP_BattMonitor/AP_BattMonitor.h>10#include <AP_Vehicle/AP_Vehicle_Type.h>11#include <AP_BoardConfig/AP_BoardConfig.h>1213extern const AP_HAL::HAL& hal;1415AP_Compass_Backend::AP_Compass_Backend()16: _compass(AP::compass())17{18}1920void AP_Compass_Backend::rotate_field(Vector3f &mag, uint8_t instance)21{22Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];23if (MAG_BOARD_ORIENTATION != ROTATION_NONE) {24mag.rotate(MAG_BOARD_ORIENTATION);25}26mag.rotate(state.rotation);2728#ifdef HAL_HEATER_MAG_OFFSET29/*30apply compass compensations for boards that have a heater which31interferes with an internal compass. This needs to be applied32before the board orientation so it is independent of33AHRS_ORIENTATION34*/35if (!is_external(instance)) {36const uint32_t dev_id = uint32_t(_compass._state[Compass::StateIndex(instance)].dev_id);37static const struct offset {38uint32_t dev_id;39Vector3f ofs;40} offsets[] = HAL_HEATER_MAG_OFFSET;41const auto *bc = AP::boardConfig();42if (bc) {43for (const auto &o : offsets) {44if (o.dev_id == dev_id) {45mag += o.ofs * bc->get_heater_duty_cycle() * 0.01;46}47}48}49}50#endif5152if (!state.external) {53mag.rotate(_compass._board_orientation);54} else {55// add user selectable orientation56mag.rotate((enum Rotation)state.orientation.get());57}58}5960void AP_Compass_Backend::publish_raw_field(const Vector3f &mag, uint8_t instance)61{62// note that we do not set last_update_usec here as otherwise the63// EKF and DCM would end up consuming compass data at the full64// sensor rate. We want them to consume only the filtered fields65#if COMPASS_CAL_ENABLED66auto& cal = _compass._calibrator[_compass._get_priority(Compass::StateIndex(instance))];67if (cal != nullptr) {68Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];69state.last_update_ms = AP_HAL::millis();70cal->new_sample(mag);71}72#endif73}7475void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)76{77Compass::mag_state &state = _compass._state[Compass::StateIndex(i)];7879const Vector3f &offsets = state.offset.get();80#if AP_COMPASS_DIAGONALS_ENABLED81const Vector3f &diagonals = state.diagonals.get();82const Vector3f &offdiagonals = state.offdiagonals.get();83#endif8485// add in the basic offsets86mag += offsets;8788// add in scale factor, use a wide sanity check. The calibrator89// uses a narrower check.90if (_compass.have_scale_factor(i)) {91mag *= state.scale_factor;92}9394#if AP_COMPASS_DIAGONALS_ENABLED95// apply elliptical correction96if (!diagonals.is_zero()) {97Matrix3f mat(98diagonals.x, offdiagonals.x, offdiagonals.y,99offdiagonals.x, diagonals.y, offdiagonals.z,100offdiagonals.y, offdiagonals.z, diagonals.z101);102103mag = mat * mag;104}105#endif106107#if COMPASS_MOT_ENABLED108const Vector3f &mot = state.motor_compensation.get();109/*110calculate motor-power based compensation111note that _motor_offset[] is kept even if compensation is not112being applied so it can be logged correctly113*/114state.motor_offset.zero();115if (_compass._per_motor.enabled() && i == 0) {116// per-motor correction is only valid for first compass117_compass._per_motor.compensate(state.motor_offset);118} else if (_compass._motor_comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {119state.motor_offset = mot * _compass._thr;120} else if (_compass._motor_comp_type == AP_COMPASS_MOT_COMP_CURRENT) {121AP_BattMonitor &battery = AP::battery();122float current;123if (battery.current_amps(current)) {124state.motor_offset = mot * current;125}126}127128/*129we apply the motor offsets after we apply the elliptical130correction. This is needed to match the way that the motor131compensation values are calculated, as they are calculated based132on final field outputs, not on the raw outputs133*/134mag += state.motor_offset;135#endif // COMPASS_MOT_ENABLED136}137138void AP_Compass_Backend::accumulate_sample(Vector3f &field, uint8_t instance,139uint32_t max_samples)140{141/* rotate raw_field from sensor frame to body frame */142rotate_field(field, instance);143144/* publish raw_field (uncorrected point sample) for calibration use */145publish_raw_field(field, instance);146147/* correct raw_field for known errors */148correct_field(field, instance);149150if (!field_ok(field)) {151return;152}153154WITH_SEMAPHORE(_sem);155156Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];157state.accum += field;158state.accum_count++;159if (max_samples && state.accum_count >= max_samples) {160state.accum_count /= 2;161state.accum /= 2;162}163}164165void AP_Compass_Backend::drain_accumulated_samples(uint8_t instance,166const Vector3f *scaling)167{168WITH_SEMAPHORE(_sem);169170Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];171172if (state.accum_count == 0) {173return;174}175176if (scaling) {177state.accum *= *scaling;178}179state.accum /= state.accum_count;180181publish_filtered_field(state.accum, instance);182183state.accum.zero();184state.accum_count = 0;185}186187/*188copy latest data to the frontend from a backend189*/190void AP_Compass_Backend::publish_filtered_field(const Vector3f &mag, uint8_t instance)191{192Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];193194state.field = mag;195196state.last_update_ms = AP_HAL::millis();197state.last_update_usec = AP_HAL::micros();198}199200void AP_Compass_Backend::set_last_update_usec(uint32_t last_update, uint8_t instance)201{202Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];203state.last_update_usec = last_update;204}205206/*207register a new backend with frontend, returning instance which208should be used in publish_field()209*/210bool AP_Compass_Backend::register_compass(int32_t dev_id, uint8_t& instance) const211{212return _compass.register_compass(dev_id, instance);213}214215216/*217set dev_id for an instance218*/219void AP_Compass_Backend::set_dev_id(uint8_t instance, uint32_t dev_id)220{221_compass._state[Compass::StateIndex(instance)].dev_id.set_and_notify(dev_id);222_compass._state[Compass::StateIndex(instance)].detected_dev_id = dev_id;223}224225/*226save dev_id, used by SITL227*/228void AP_Compass_Backend::save_dev_id(uint8_t instance)229{230_compass._state[Compass::StateIndex(instance)].dev_id.save();231}232233/*234set external for an instance235*/236void AP_Compass_Backend::set_external(uint8_t instance, bool external)237{238if (_compass._state[Compass::StateIndex(instance)].external != 2) {239_compass._state[Compass::StateIndex(instance)].external.set_and_notify(external);240}241}242243bool AP_Compass_Backend::is_external(uint8_t instance)244{245return _compass._state[Compass::StateIndex(instance)].external;246}247248// set rotation of an instance249void AP_Compass_Backend::set_rotation(uint8_t instance, enum Rotation rotation)250{251_compass._state[Compass::StateIndex(instance)].rotation = rotation;252}253254static constexpr float FILTER_KOEF = 0.1f;255256/* Check that the compass value is valid by using a mean filter. If257* the value is further than filter_range from mean value, it is258* rejected.259*/260bool AP_Compass_Backend::field_ok(const Vector3f &field)261{262263264if (field.is_inf() || field.is_nan()) {265return false;266}267268const float range = (float)_compass.get_filter_range();269if (range <= 0) {270return true;271}272273const float length = field.length();274275if (is_zero(_mean_field_length)) {276_mean_field_length = length;277return true;278}279280bool ret = true;281const float d = fabsf(_mean_field_length - length) / (_mean_field_length + length); // diff divide by mean value in percent ( with the *200.0f on later line)282float koeff = FILTER_KOEF;283284if (d * 200.0f > range) { // check the difference from mean value outside allowed range285// printf("\nCompass field length error: mean %f got %f\n", (double)_mean_field_length, (double)length );286ret = false;287koeff /= (d * 10.0f); // 2.5 and more, so one bad sample never change mean more than 4%288_error_count++;289}290_mean_field_length = _mean_field_length * (1 - koeff) + length * koeff; // complimentary filter 1/k291292return ret;293}294295296enum Rotation AP_Compass_Backend::get_board_orientation(void) const297{298return _compass._board_orientation;299}300301#endif // AP_COMPASS_ENABLED302303304