Path: blob/master/libraries/AP_Compass/AP_Compass_Backend.cpp
9374 views
#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>1213AP_Compass_Backend::AP_Compass_Backend()14: _compass(AP::compass())15{16}1718void AP_Compass_Backend::rotate_field(Vector3f &mag)19{20Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];21if (MAG_BOARD_ORIENTATION != ROTATION_NONE) {22mag.rotate(MAG_BOARD_ORIENTATION);23}24mag.rotate(state.rotation);2526#ifdef HAL_HEATER_MAG_OFFSET27/*28apply compass compensations for boards that have a heater which29interferes with an internal compass. This needs to be applied30before the board orientation so it is independent of31AHRS_ORIENTATION32*/33if (!is_external()) {34const uint32_t dev_id = uint32_t(_compass._state[Compass::StateIndex(instance)].dev_id);35static const struct offset {36uint32_t dev_id;37Vector3f ofs;38} offsets[] = HAL_HEATER_MAG_OFFSET;39const auto *bc = AP::boardConfig();40if (bc) {41for (const auto &o : offsets) {42if (o.dev_id == dev_id) {43mag += o.ofs * bc->get_heater_duty_cycle() * 0.01;44}45}46}47}48#endif4950if (!state.external) {51mag.rotate(_compass._board_orientation);52} else {53// add user selectable orientation54mag.rotate((enum Rotation)state.orientation.get());55}56}5758void AP_Compass_Backend::publish_raw_field(const Vector3f &mag)59{60// note that we do not set last_update_usec here as otherwise the61// EKF and DCM would end up consuming compass data at the full62// sensor rate. We want them to consume only the filtered fields63#if COMPASS_CAL_ENABLED64auto& cal = _compass._calibrator[_compass._get_priority(Compass::StateIndex(instance))];65if (cal != nullptr) {66Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];67state.last_update_ms = AP_HAL::millis();68cal->new_sample(mag);69}70#endif71}7273void AP_Compass_Backend::correct_field(Vector3f &mag)74{75Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];7677const Vector3f &offsets = state.offset.get();78#if AP_COMPASS_DIAGONALS_ENABLED79const Vector3f &diagonals = state.diagonals.get();80const Vector3f &offdiagonals = state.offdiagonals.get();81#endif8283// add in the basic offsets84mag += offsets;8586// add in scale factor, use a wide sanity check. The calibrator87// uses a narrower check.88if (_compass.have_scale_factor(instance)) {89mag *= state.scale_factor;90}9192#if AP_COMPASS_DIAGONALS_ENABLED93// apply elliptical correction94if (!diagonals.is_zero()) {95Matrix3f mat(96diagonals.x, offdiagonals.x, offdiagonals.y,97offdiagonals.x, diagonals.y, offdiagonals.z,98offdiagonals.y, offdiagonals.z, diagonals.z99);100101mag = mat * mag;102}103#endif104105#if COMPASS_MOT_ENABLED106const Vector3f &mot = state.motor_compensation.get();107/*108calculate motor-power based compensation109note that _motor_offset[] is kept even if compensation is not110being applied so it can be logged correctly111*/112state.motor_offset.zero();113if (_compass._per_motor.enabled() && instance == 0) {114// per-motor correction is only valid for first compass115_compass._per_motor.compensate(state.motor_offset);116} else if (_compass._motor_comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {117state.motor_offset = mot * _compass._thr;118} else if (_compass._motor_comp_type == AP_COMPASS_MOT_COMP_CURRENT) {119AP_BattMonitor &battery = AP::battery();120float current;121if (battery.current_amps(current)) {122state.motor_offset = mot * current;123}124}125126/*127we apply the motor offsets after we apply the elliptical128correction. This is needed to match the way that the motor129compensation values are calculated, as they are calculated based130on final field outputs, not on the raw outputs131*/132mag += state.motor_offset;133#endif // COMPASS_MOT_ENABLED134}135136void AP_Compass_Backend::accumulate_sample(Vector3f &field,137uint32_t max_samples)138{139/* rotate raw_field from sensor frame to body frame */140rotate_field(field);141142/* publish raw_field (uncorrected point sample) for calibration use */143publish_raw_field(field);144145/* correct raw_field for known errors */146correct_field(field);147148if (!field_ok(field)) {149return;150}151152WITH_SEMAPHORE(_sem);153154Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];155state.accum += field;156state.accum_count++;157if (max_samples && state.accum_count >= max_samples) {158state.accum_count /= 2;159state.accum /= 2;160}161}162163void AP_Compass_Backend::drain_accumulated_samples(const Vector3f *scaling)164{165WITH_SEMAPHORE(_sem);166167Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];168169if (state.accum_count == 0) {170return;171}172173if (scaling) {174state.accum *= *scaling;175}176state.accum /= state.accum_count;177178publish_filtered_field(state.accum);179180state.accum.zero();181state.accum_count = 0;182}183184/*185copy latest data to the frontend from a backend186*/187void AP_Compass_Backend::publish_filtered_field(const Vector3f &mag)188{189Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];190191state.field = mag;192193state.last_update_ms = AP_HAL::millis();194state.last_update_usec = AP_HAL::micros();195}196197void AP_Compass_Backend::set_last_update_usec(uint32_t last_update)198{199Compass::mag_state &state = _compass._state[Compass::StateIndex(instance)];200state.last_update_usec = last_update;201}202203/*204register a new backend with frontend, returning instance which205should be used in publish_field()206*/207bool AP_Compass_Backend::register_compass(int32_t dev_id)208{209if (!_compass.register_compass(dev_id, instance)) {210return false;211}212set_dev_id(dev_id);213return true;214}215216/*217set dev_id for an instance218*/219void AP_Compass_Backend::set_dev_id(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()229{230_compass._state[Compass::StateIndex(instance)].dev_id.save();231}232233/*234set external for an instance235*/236void AP_Compass_Backend::set_external(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()244{245return _compass._state[Compass::StateIndex(instance)].external;246}247248// set rotation of an instance249void AP_Compass_Backend::set_rotation(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