Path: blob/master/libraries/AP_Compass/AP_Compass.h
9532 views
#pragma once12#include "AP_Compass_config.h"34#include <inttypes.h>56#include <AP_Common/AP_Common.h>7#include <AP_Declination/AP_Declination.h>8#include <AP_HAL/AP_HAL.h>9#include <AP_Math/AP_Math.h>10#include <AP_Param/AP_Param.h>11#include <GCS_MAVLink/GCS_MAVLink.h>12#include <AP_MSP/msp.h>13#include <AP_ExternalAHRS/AP_ExternalAHRS.h>1415#include "AP_Compass_Backend.h"16#include "Compass_PerMotor.h"17#include <AP_Common/TSIndex.h>1819// motor compensation types (for use with motor_comp_enabled)20#define AP_COMPASS_MOT_COMP_DISABLED 0x0021#define AP_COMPASS_MOT_COMP_THROTTLE 0x0122#define AP_COMPASS_MOT_COMP_CURRENT 0x0223#define AP_COMPASS_MOT_COMP_PER_MOTOR 0x032425#ifndef MAG_BOARD_ORIENTATION26#define MAG_BOARD_ORIENTATION ROTATION_NONE27#endif2829#ifndef COMPASS_MOT_ENABLED30#define COMPASS_MOT_ENABLED 131#endif32#ifndef COMPASS_LEARN_ENABLED33#define COMPASS_LEARN_ENABLED AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED34#endif3536// define default compass calibration fitness and consistency checks37#define AP_COMPASS_CALIBRATION_FITNESS_DEFAULT 16.0f38#define AP_COMPASS_MAX_XYZ_ANG_DIFF radians(90.0f)39#define AP_COMPASS_MAX_XY_ANG_DIFF radians(60.0f)40#define AP_COMPASS_MAX_XY_LENGTH_DIFF 200.0f4142/**43maximum number of compass instances available on this platform. If more44than 1 then redundant sensors may be available45*/46#ifndef HAL_BUILD_AP_PERIPH47#ifndef HAL_COMPASS_MAX_SENSORS48#define HAL_COMPASS_MAX_SENSORS 349#endif50#if HAL_COMPASS_MAX_SENSORS > 151#define COMPASS_MAX_UNREG_DEV 552#else53#define COMPASS_MAX_UNREG_DEV 054#endif55#else56#ifndef HAL_COMPASS_MAX_SENSORS57#define HAL_COMPASS_MAX_SENSORS 158#endif59#define COMPASS_MAX_UNREG_DEV 060#endif6162#define COMPASS_MAX_INSTANCES HAL_COMPASS_MAX_SENSORS63#define COMPASS_MAX_BACKEND HAL_COMPASS_MAX_SENSORS6465#define MAX_CONNECTED_MAGS (COMPASS_MAX_UNREG_DEV+COMPASS_MAX_INSTANCES)6667#include "CompassCalibrator.h"6869class CompassLearn;7071class Compass72{73friend class AP_Compass_Backend;74friend class AP_Compass_DroneCAN;75public:76Compass();7778/* Do not allow copies */79CLASS_NO_COPY(Compass);8081// get singleton instance82static Compass *get_singleton() {83return _singleton;84}8586friend class CompassLearn;8788/// Initialize the compass device.89///90/// @returns True if the compass was initialized OK, false if it was not91/// found or is not functioning.92///93__INITFUNC__ void init();9495/// Read the compass and update the mag_ variables.96///97bool read();9899// available returns true if the compass is both enabled and has100// been initialised101bool available() const { return _enabled && init_done; }102103/// Calculate the tilt-compensated heading_ variables.104///105/// @param dcm_matrix The current orientation rotation matrix106///107/// @returns heading in radians108///109float calculate_heading(const Matrix3f &dcm_matrix) const {110return calculate_heading(dcm_matrix, _first_usable);111}112float calculate_heading(const Matrix3f &dcm_matrix, uint8_t i) const;113114/// Sets offset x/y/z values.115///116/// @param i compass instance117/// @param offsets Offsets to the raw mag_ values in milligauss.118///119void set_offsets(uint8_t i, const Vector3f &offsets);120121/// Sets and saves the compass offset x/y/z values.122///123/// @param i compass instance124/// @param offsets Offsets to the raw mag_ values in milligauss.125///126void set_and_save_offsets(uint8_t i, const Vector3f &offsets);127#if AP_COMPASS_DIAGONALS_ENABLED128void set_and_save_diagonals(uint8_t i, const Vector3f &diagonals);129void set_and_save_offdiagonals(uint8_t i, const Vector3f &diagonals);130#endif131void set_and_save_scale_factor(uint8_t i, float scale_factor);132void set_and_save_orientation(uint8_t i, Rotation orientation);133134/// Saves the current offset x/y/z values for one or all compasses135///136/// @param i compass instance137///138/// This should be invoked periodically to save the offset values maintained by139/// ::learn_offsets.140///141void save_offsets(uint8_t i);142void save_offsets(void);143144// return the number of compass instances145uint8_t get_count(void) const { return _compass_count; }146147// return the number of enabled sensors148uint8_t get_num_enabled(void) const;149150/// Return the current field as a Vector3f in milligauss151const Vector3f &get_field(uint8_t i) const { return _get_state(Priority(i)).field; }152const Vector3f &get_field(void) const { return get_field(_first_usable); }153154/// Return true if we have set a scale factor for a compass155bool have_scale_factor(uint8_t i) const;156157#if COMPASS_MOT_ENABLED158// per-motor calibration access159void per_motor_calibration_start(void) {160_per_motor.calibration_start();161}162void per_motor_calibration_update(void) {163_per_motor.calibration_update();164}165void per_motor_calibration_end(void) {166_per_motor.calibration_end();167}168#endif169170#if COMPASS_CAL_ENABLED171// compass calibrator interface172void cal_update();173174// start_calibration_all will only return false if there are no175// compasses to calibrate.176bool start_calibration_all(bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot = false);177178void cancel_calibration_all();179180bool compass_cal_requires_reboot() const { return _cal_requires_reboot; }181bool is_calibrating() const;182183#if HAL_MAVLINK_BINDINGS_ENABLED184/*185handle an incoming MAG_CAL command186*/187MAV_RESULT handle_mag_cal_command(const mavlink_command_int_t &packet);188189bool send_mag_cal_progress(const class GCS_MAVLINK& link);190bool send_mag_cal_report(const class GCS_MAVLINK& link);191#endif // HAL_MAVLINK_BINDINGS_ENABLED192#endif // COMPASS_CAL_ENABLED193194// indicate which bit in LOG_BITMASK indicates we should log compass readings195void set_log_bit(uint32_t log_bit) { _log_bit = log_bit; }196197// check if the compasses are pointing in the same direction198bool consistent() const;199200/// Return the health of a compass201bool healthy(uint8_t i) const;202bool healthy(void) const { return healthy(_first_usable); }203uint8_t get_healthy_mask() const;204205/// Returns the current offset values206///207/// @returns The current compass offsets in milligauss.208///209const Vector3f &get_offsets(uint8_t i) const { return _get_state(Priority(i)).offset; }210const Vector3f &get_offsets(void) const { return get_offsets(_first_usable); }211212#if AP_COMPASS_DIAGONALS_ENABLED213const Vector3f &get_diagonals(uint8_t i) const { return _get_state(Priority(i)).diagonals; }214const Vector3f &get_diagonals(void) const { return get_diagonals(_first_usable); }215216const Vector3f &get_offdiagonals(uint8_t i) const { return _get_state(Priority(i)).offdiagonals; }217const Vector3f &get_offdiagonals(void) const { return get_offdiagonals(_first_usable); }218#endif // AP_COMPASS_DIAGONALS_ENABLED219220// learn offsets accessor221bool learn_offsets_enabled() const { return _learn == LearnType::INFLIGHT; }222223/// return true if the compass should be used for yaw calculations224bool use_for_yaw(uint8_t i) const;225bool use_for_yaw(void) const;226227/// Sets the local magnetic field declination.228///229/// @param radians Local field declination.230/// @param save_to_eeprom true to save to eeprom (false saves only to memory)231///232void set_declination(float radians, bool save_to_eeprom = true);233float get_declination() const;234235bool auto_declination_enabled() const { return _auto_declination != 0; }236237// set overall board orientation238void set_board_orientation(enum Rotation orientation) {239_board_orientation = orientation;240}241242// get overall board orientation243enum Rotation get_board_orientation(void) const {244return _board_orientation;245}246247/// Set the motor compensation type248///249/// @param comp_type 0 = disabled, 1 = enabled use throttle, 2 = enabled use current250///251void motor_compensation_type(const uint8_t comp_type);252253/// get the motor compensation value.254uint8_t get_motor_compensation_type() const {255return _motor_comp_type;256}257258/// Set the motor compensation factor x/y/z values.259///260/// @param i instance of compass261/// @param offsets Offsets multiplied by the throttle value and added to the raw mag_ values.262///263void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor);264265/// get motor compensation factors as a vector266const Vector3f& get_motor_compensation(uint8_t i) const { return _get_state(Priority(i)).motor_compensation; }267const Vector3f& get_motor_compensation(void) const { return get_motor_compensation(_first_usable); }268269/// Saves the current motor compensation x/y/z values.270///271/// This should be invoked periodically to save the offset values calculated by the motor compensation auto learning272///273void save_motor_compensation();274275/// Returns the current motor compensation offset values276///277/// @returns The current compass offsets in milligauss.278///279const Vector3f &get_motor_offsets(uint8_t i) const { return _get_state(Priority(i)).motor_offset; }280const Vector3f &get_motor_offsets(void) const { return get_motor_offsets(_first_usable); }281282/// Set the throttle as a percentage from 0.0 to 1.0283/// @param thr_pct throttle expressed as a percentage from 0 to 1.0284void set_throttle(float thr_pct) {285if (_motor_comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {286_thr = thr_pct;287}288}289290#if COMPASS_MOT_ENABLED291/// Set the battery voltage for per-motor compensation292void set_voltage(float voltage) {293_per_motor.set_voltage(voltage);294}295#endif296297/// Returns True if the compasses have been configured (i.e. offsets saved)298///299/// @returns True if compass has been configured300///301bool configured(uint8_t i);302bool configured(char *failure_msg, uint8_t failure_msg_len);303304// return last update time in microseconds305uint32_t last_update_usec(void) const { return last_update_usec(_first_usable); }306uint32_t last_update_usec(uint8_t i) const { return _get_state(Priority(i)).last_update_usec; }307308uint32_t last_update_ms(void) const { return last_update_ms(_first_usable); }309uint32_t last_update_ms(uint8_t i) const { return _get_state(Priority(i)).last_update_ms; }310311static const struct AP_Param::GroupInfo var_info[];312313enum class LearnType {314NONE = 0,315// INTERNAL = 1,316COPY_FROM_EKF = 2,317INFLIGHT = 3,318};319320// return the chosen learning type321LearnType get_learn_type(void) const {322return (LearnType)_learn.get();323}324325// set the learning type326void set_learn_type(LearnType type, bool save) {327if (save) {328_learn.set_and_save(type);329} else {330_learn.set(type);331}332}333334// return maximum allowed compass offsets335uint16_t get_offsets_max(void) const {336return (uint16_t)_offset_max.get();337}338339uint8_t get_filter_range() const { return uint8_t(_filter_range.get()); }340341#if AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED342/*343fast compass calibration given vehicle position and yaw344*/345bool mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,346float lat_deg, float lon_deg,347bool force_use=false);348#endif349350#if AP_COMPASS_MSP_ENABLED351void handle_msp(const MSP::msp_compass_data_message_t &pkt);352#endif353354#if AP_COMPASS_EXTERNALAHRS_ENABLED355void handle_external(const AP_ExternalAHRS::mag_data_message_t &pkt);356#endif357358// force save of current calibration as valid359void force_save_calibration(void);360361// get the first compass marked for use by COMPASSx_USE362uint8_t get_first_usable(void) const { return _first_usable; }363364private:365static Compass *_singleton;366367// Use Priority and StateIndex typesafe index types368// to distinguish between two different type of indexing369// We use StateIndex for access by Backend370// and Priority for access by Frontend371DECLARE_TYPESAFE_INDEX(Priority, uint8_t);372DECLARE_TYPESAFE_INDEX(StateIndex, uint8_t);373374/// Register a new compas driver, allocating an instance number375///376/// @param dev_id Dev ID of compass to register against377///378/// @return instance number saved against the dev id or first available empty instance number379bool register_compass(int32_t dev_id, uint8_t& instance) WARN_IF_UNUSED;380381// load backend drivers382__INITFUNC__ void _probe_external_i2c_compasses(void);383__INITFUNC__ void _detect_backends(void);384__INITFUNC__ void probe_i2c_spi_compasses(void);385#if AP_COMPASS_DRONECAN_ENABLED386void probe_dronecan_compasses(void);387#endif388389#if COMPASS_CAL_ENABLED390// compass cal391void _update_calibration_trampoline();392bool _accept_calibration(uint8_t i);393bool _accept_calibration_mask(uint8_t mask);394void _cancel_calibration(uint8_t i);395void _cancel_calibration_mask(uint8_t mask);396uint8_t _get_cal_mask();397bool _start_calibration(uint8_t i, bool retry=false, float delay_sec=0.0f);398bool _start_calibration_mask(uint8_t mask, bool retry=false, bool autosave=false, float delay_sec=0.0f, bool autoreboot=false);399bool _auto_reboot() const { return _compass_cal_autoreboot; }400#if HAL_MAVLINK_BINDINGS_ENABLED401Priority next_cal_progress_idx[MAVLINK_COMM_NUM_BUFFERS];402Priority next_cal_report_idx[MAVLINK_COMM_NUM_BUFFERS];403#endif404#endif // COMPASS_CAL_ENABLED405406// see if we already have probed a i2c sensor by bus number and address407bool _i2c_sensor_is_registered(uint8_t bus_num, uint8_t address) const;408409#if AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED410/*411get mag field with the effects of offsets, diagonals and412off-diagonals removed413*/414bool get_uncorrected_field(uint8_t instance, Vector3f &field) const;415#endif416417#if COMPASS_CAL_ENABLED418//keep track of which calibrators have been saved419RestrictIDTypeArray<bool, COMPASS_MAX_INSTANCES, Priority> _cal_saved;420bool _cal_autosave;421422//autoreboot after compass calibration423bool _compass_cal_autoreboot;424bool _cal_requires_reboot;425bool _cal_has_run;426#endif // COMPASS_CAL_ENABLED427428// enum of drivers for COMPASS_DISBLMSK429enum DriverType {430#if AP_COMPASS_HMC5843_ENABLED431DRIVER_HMC5843 =0,432#endif433#if AP_COMPASS_LSM303D_ENABLED434DRIVER_LSM303D =1,435#endif436#if AP_COMPASS_AK8963_ENABLED437DRIVER_AK8963 =2,438#endif439#if AP_COMPASS_BMM150_ENABLED440DRIVER_BMM150 =3,441#endif442#if AP_COMPASS_LSM9DS1_ENABLED443DRIVER_LSM9DS1 =4,444#endif445#if AP_COMPASS_LIS3MDL_ENABLED446DRIVER_LIS3MDL =5,447#endif448#if AP_COMPASS_AK09916_ENABLED449DRIVER_AK09916 =6,450#endif451#if AP_COMPASS_IST8310_ENABLED452DRIVER_IST8310 =7,453#endif454#if AP_COMPASS_ICM20948_ENABLED455DRIVER_ICM20948 =8,456#endif457#if AP_COMPASS_MMC3416_ENABLED458DRIVER_MMC3416 =9,459#endif460#if AP_COMPASS_DRONECAN_ENABLED461DRIVER_UAVCAN =11,462#endif463#if AP_COMPASS_QMC5883L_ENABLED464DRIVER_QMC5883L =12,465#endif466#if AP_COMPASS_SITL_ENABLED467DRIVER_SITL =13,468#endif469#if AP_COMPASS_MAG3110_ENABLED470DRIVER_MAG3110 =14,471#endif472#if AP_COMPASS_IST8308_ENABLED473DRIVER_IST8308 =15,474#endif475#if AP_COMPASS_RM3100_ENABLED476DRIVER_RM3100 =16,477#endif478#if AP_COMPASS_MSP_ENABLED479DRIVER_MSP =17,480#endif481#if AP_COMPASS_EXTERNALAHRS_ENABLED482DRIVER_EXTERNALAHRS =18,483#endif484#if AP_COMPASS_MMC5XX3_ENABLED485DRIVER_MMC5XX3 =19,486#endif487#if AP_COMPASS_QMC5883P_ENABLED488DRIVER_QMC5883P =20,489#endif490#if AP_COMPASS_BMM350_ENABLED491DRIVER_BMM350 =21,492#endif493#if AP_COMPASS_IIS2MDC_ENABLED494DRIVER_IIS2MDC =22,495#endif496#if AP_COMPASS_LIS2MDL_ENABLED497DRIVER_LIS2MDL =23,498#endif499500};501502bool _driver_enabled(enum DriverType driver_type);503void add_backend(DriverType driver_type, AP_Compass_Backend *backend);504505// helper probe functions506void probe_ak09916_via_icm20948(uint8_t i2c_bus, uint8_t ak09916_addr, uint8_t icm20948_addr, bool external, Rotation rotation);507void probe_ak09916_via_icm20948(uint8_t ins_instance, Rotation rotation);508void probe_ak8963_via_mpu9250(uint8_t imu_instance, Rotation rotation);509510using probe_i2c_dev_probefn_t = AP_Compass_Backend* (*)(AP_HAL::OwnPtr<AP_HAL::Device>, bool, Rotation);511void probe_i2c_dev(DriverType driver_type, probe_i2c_dev_probefn_t probefn, uint8_t i2c_bus, uint8_t i2c_addr, bool external, Rotation rotation);512513using probe_spi_dev_probefn_t = AP_Compass_Backend* (*)(AP_HAL::OwnPtr<AP_HAL::Device>, bool, Rotation);514void probe_spi_dev(DriverType driver_type, probe_spi_dev_probefn_t probefn, const char *name, bool external, Rotation rotation);515// short-lived method which expects a probe function that doesn't516// offer the ability to specify an external rotation517using probe_spi_dev_noexternal_probefn_t = AP_Compass_Backend* (*)(AP_HAL::OwnPtr<AP_HAL::Device>, Rotation);518void probe_spi_dev(DriverType driver_type, probe_spi_dev_noexternal_probefn_t probefn, const char *name, Rotation rotation);519520// backend objects521AP_Compass_Backend *_backends[COMPASS_MAX_BACKEND];522uint8_t _backend_count;523524// whether to enable the compass drivers at all525AP_Int8 _enabled;526527// number of registered compasses.528uint8_t _compass_count;529530// number of unregistered compasses.531uint8_t _unreg_compass_count;532533// settable parameters534AP_Enum<LearnType> _learn;535536// board orientation from AHRS537enum Rotation _board_orientation = ROTATION_NONE;538539// declination in radians540AP_Float _declination;541542// enable automatic declination code543AP_Int8 _auto_declination;544545// stores which bit is used to indicate we should log compass readings546uint32_t _log_bit = -1;547548// motor compensation type549// 0 = disabled, 1 = enabled for throttle, 2 = enabled for current550AP_Int8 _motor_comp_type;551552// automatic compass orientation on calibration553AP_Int8 _rotate_auto;554555// throttle expressed as a percentage from 0 ~ 1.0, used for motor compensation556float _thr;557558struct mag_state {559AP_Int8 external;560bool healthy;561bool registered;562Compass::Priority priority;563AP_Int8 orientation;564AP_Vector3f offset;565#if AP_COMPASS_DIAGONALS_ENABLED566AP_Vector3f diagonals;567AP_Vector3f offdiagonals;568#endif569AP_Float scale_factor;570571// device id detected at init.572// saved to eeprom when offsets are saved allowing ram &573// eeprom values to be compared as consistency check574AP_Int32 dev_id;575// Initialised when compass is detected576int32_t detected_dev_id;577// Initialised at boot from saved devid578int32_t expected_dev_id;579580// factors multiplied by throttle and added to compass outputs581AP_Vector3f motor_compensation;582583// latest compensation added to compass584Vector3f motor_offset;585586// corrected magnetic field strength587Vector3f field;588589// when we last got data590uint32_t last_update_ms;591uint32_t last_update_usec;592593// board specific orientation594enum Rotation rotation;595596// accumulated samples, protected by _sem, used by AP_Compass_Backend597Vector3f accum;598uint32_t accum_count;599// We only copy persistent params600void copy_from(const mag_state& state);601};602603//Create an Array of mag_state to be accessible by StateIndex only604RestrictIDTypeArray<mag_state, COMPASS_MAX_INSTANCES+1, StateIndex> _state;605606//Convert Priority to StateIndex607StateIndex _get_state_id(Priority priority) const;608//Get State Struct by Priority609const struct mag_state& _get_state(Priority priority) const { return _state[_get_state_id(priority)]; }610//Convert StateIndex to Priority611Priority _get_priority(StateIndex state_id) { return _state[state_id].priority; }612//Method to detect compass beyond initialisation stage613void _detect_runtime(void);614// This method reorganises devid list to match615// priority list, only call before detection at boot616#if COMPASS_MAX_INSTANCES > 1617void _reorder_compass_params();618#endif619// Update Priority List for Mags, by default, we just620// load them as they come up the first time621Priority _update_priority_list(int32_t dev_id);622623// method to check if the mag with the devid624// is a replacement mag625bool is_replacement_mag(uint32_t dev_id);626627//remove the devid from unreg compass list628void remove_unreg_dev_id(uint32_t devid);629630void _reset_compass_id();631//Create Arrays to be accessible by Priority only632RestrictIDTypeArray<AP_Int8, COMPASS_MAX_INSTANCES, Priority> _use_for_yaw;633#if COMPASS_MAX_INSTANCES > 1634RestrictIDTypeArray<AP_Int32, COMPASS_MAX_INSTANCES, Priority> _priority_did_stored_list;635RestrictIDTypeArray<int32_t, COMPASS_MAX_INSTANCES, Priority> _priority_did_list;636#endif637638AP_Int16 _offset_max;639640// bitmask of options641enum class Option : uint16_t {642CAL_REQUIRE_GPS = (1U<<0),643ALLOW_DRONECAN_AUTO_REPLACEMENT = (1U<<1),644};645bool option_set(Option opt) const { return (_options.get() & uint16_t(opt)) != 0; }646AP_Int16 _options;647648#if COMPASS_CAL_ENABLED649RestrictIDTypeArray<CompassCalibrator*, COMPASS_MAX_INSTANCES, Priority> _calibrator;650#endif651652#if COMPASS_MOT_ENABLED653// per-motor compass compensation654Compass_PerMotor _per_motor{*this};655#endif656657AP_Float _calibration_threshold;658659// mask of driver types to not load. Bit positions match DEVTYPE_ in backend660AP_Int32 _driver_type_mask;661662#if COMPASS_MAX_UNREG_DEV663// Put extra dev ids detected664AP_Int32 extra_dev_id[COMPASS_MAX_UNREG_DEV];665uint32_t _previously_unreg_mag[COMPASS_MAX_UNREG_DEV];666#endif667668AP_Int8 _filter_range;669670CompassLearn *learn;671bool learn_allocated;672673/// Sets the initial location used to get declination674///675/// @param latitude GPS Latitude.676/// @param longitude GPS Longitude.677///678void try_set_initial_location();679bool _initial_location_set;680681bool _cal_thread_started;682683#if AP_COMPASS_MSP_ENABLED684uint8_t msp_instance_mask;685#endif686bool init_done;687688bool suppress_devid_save;689690uint8_t _first_usable; // first compass usable based on COMPASSx_USE param691};692693namespace AP {694Compass &compass();695};696697698