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.cpp
Views: 1798
#include "AP_Compass_config.h"12#if AP_COMPASS_ENABLED34#include <AP_HAL/AP_HAL.h>5#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX6#include <AP_HAL_Linux/I2CDevice.h>7#endif8#include <AP_Vehicle/AP_Vehicle_Type.h>9#include <AP_BoardConfig/AP_BoardConfig.h>10#include <AP_Logger/AP_Logger.h>11#include <AP_Vehicle/AP_Vehicle_Type.h>12#include <AP_ExternalAHRS/AP_ExternalAHRS.h>13#include <AP_CustomRotations/AP_CustomRotations.h>14#include <GCS_MAVLink/GCS.h>15#include <AP_AHRS/AP_AHRS.h>1617#include "AP_Compass_config.h"1819#include "AP_Compass_SITL.h"20#include "AP_Compass_AK8963.h"21#include "AP_Compass_Backend.h"22#include "AP_Compass_BMM150.h"23#include "AP_Compass_BMM350.h"24#include "AP_Compass_HMC5843.h"25#include "AP_Compass_IIS2MDC.h"26#include "AP_Compass_IST8308.h"27#include "AP_Compass_IST8310.h"28#include "AP_Compass_LSM303D.h"29#include "AP_Compass_LSM9DS1.h"30#include "AP_Compass_LIS3MDL.h"31#include "AP_Compass_AK09916.h"32#include "AP_Compass_QMC5883L.h"33#if AP_COMPASS_DRONECAN_ENABLED34#include "AP_Compass_DroneCAN.h"35#endif36#include "AP_Compass_QMC5883P.h"37#include "AP_Compass_MMC3416.h"38#include "AP_Compass_MMC5xx3.h"39#include "AP_Compass_MAG3110.h"40#include "AP_Compass_RM3100.h"41#if AP_COMPASS_MSP_ENABLED42#include "AP_Compass_MSP.h"43#endif44#if AP_COMPASS_EXTERNALAHRS_ENABLED45#include "AP_Compass_ExternalAHRS.h"46#endif47#include "AP_Compass.h"48#include "Compass_learn.h"49#include <stdio.h>5051extern const AP_HAL::HAL& hal;5253#ifndef AP_COMPASS_ENABLE_DEFAULT54#define AP_COMPASS_ENABLE_DEFAULT 155#endif5657#ifndef COMPASS_LEARN_DEFAULT58#define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE59#endif6061#ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT62#define AP_COMPASS_OFFSETS_MAX_DEFAULT 180063#endif6465#ifndef HAL_COMPASS_FILTER_DEFAULT66#define HAL_COMPASS_FILTER_DEFAULT 0 // turned off by default67#endif6869#ifndef HAL_COMPASS_AUTO_ROT_DEFAULT70#define HAL_COMPASS_AUTO_ROT_DEFAULT 271#endif7273const AP_Param::GroupInfo Compass::var_info[] = {74// index 0 was used for the old orientation matrix7576#ifndef HAL_BUILD_AP_PERIPH77// @Param: OFS_X78// @DisplayName: Compass offsets in milligauss on the X axis79// @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame80// @Range: -400 40081// @Units: mGauss82// @Increment: 183// @User: Advanced84// @Calibration: 18586// @Param: OFS_Y87// @DisplayName: Compass offsets in milligauss on the Y axis88// @Description: Offset to be added to the compass y-axis values to compensate for metal in the frame89// @Range: -400 40090// @Units: mGauss91// @Increment: 192// @User: Advanced93// @Calibration: 19495// @Param: OFS_Z96// @DisplayName: Compass offsets in milligauss on the Z axis97// @Description: Offset to be added to the compass z-axis values to compensate for metal in the frame98// @Range: -400 40099// @Units: mGauss100// @Increment: 1101// @User: Advanced102// @Calibration: 1103AP_GROUPINFO("OFS", 1, Compass, _state._priv_instance[0].offset, 0),104105// @Param: DEC106// @DisplayName: Compass declination107// @Description: An angle to compensate between the true north and magnetic north108// @Range: -3.142 3.142109// @Units: rad110// @Increment: 0.01111// @User: Standard112AP_GROUPINFO("DEC", 2, Compass, _declination, 0),113#endif // HAL_BUILD_AP_PERIPH114115#if COMPASS_LEARN_ENABLED116// @Param: LEARN117// @DisplayName: Learn compass offsets automatically118// @Description: Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes.119// @Values: 0:Disabled,1:Internal-Learning,2:EKF-Learning,3:InFlight-Learning120// @User: Advanced121AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT),122#endif123124#ifndef HAL_BUILD_AP_PERIPH125// @Param: USE126// @DisplayName: Use compass for yaw127// @Description: Enable or disable the use of the compass (instead of the GPS) for determining heading128// @Values: 0:Disabled,1:Enabled129// @User: Advanced130AP_GROUPINFO("USE", 4, Compass, _use_for_yaw._priv_instance[0], 1), // true if used for DCM yaw131132// @Param: AUTODEC133// @DisplayName: Auto Declination134// @Description: Enable or disable the automatic calculation of the declination based on gps location135// @Values: 0:Disabled,1:Enabled136// @User: Advanced137AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1),138#endif139140#if COMPASS_MOT_ENABLED141// @Param: MOTCT142// @DisplayName: Motor interference compensation type143// @Description: Set motor interference compensation type to disabled, throttle or current. Do not change manually.144// @Values: 0:Disabled,1:Use Throttle,2:Use Current145// @User: Advanced146// @Calibration: 1147AP_GROUPINFO("MOTCT", 6, Compass, _motor_comp_type, AP_COMPASS_MOT_COMP_DISABLED),148149// @Param: MOT_X150// @DisplayName: Motor interference compensation for body frame X axis151// @Description: Multiplied by the current throttle and added to the compass's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)152// @Range: -1000 1000153// @Units: mGauss/A154// @Increment: 1155// @User: Advanced156// @Calibration: 1157158// @Param: MOT_Y159// @DisplayName: Motor interference compensation for body frame Y axis160// @Description: Multiplied by the current throttle and added to the compass's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)161// @Range: -1000 1000162// @Units: mGauss/A163// @Increment: 1164// @User: Advanced165// @Calibration: 1166167// @Param: MOT_Z168// @DisplayName: Motor interference compensation for body frame Z axis169// @Description: Multiplied by the current throttle and added to the compass's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)170// @Range: -1000 1000171// @Units: mGauss/A172// @Increment: 1173// @User: Advanced174// @Calibration: 1175AP_GROUPINFO("MOT", 7, Compass, _state._priv_instance[0].motor_compensation, 0),176#endif177178#ifndef HAL_BUILD_AP_PERIPH179// @Param: ORIENT180// @DisplayName: Compass orientation181// @Description: The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles.182// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2183// @User: Advanced184AP_GROUPINFO("ORIENT", 8, Compass, _state._priv_instance[0].orientation, ROTATION_NONE),185186// @Param: EXTERNAL187// @DisplayName: Compass is attached via an external cable188// @Description: Configure compass so it is attached externally. This is auto-detected on most boards. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.189// @Values: 0:Internal,1:External,2:ForcedExternal190// @User: Advanced191AP_GROUPINFO("EXTERNAL", 9, Compass, _state._priv_instance[0].external, 0),192#endif193194#if COMPASS_MAX_INSTANCES > 1195// @Param: OFS2_X196// @DisplayName: Compass2 offsets in milligauss on the X axis197// @Description: Offset to be added to compass2's x-axis values to compensate for metal in the frame198// @Range: -400 400199// @Units: mGauss200// @Increment: 1201// @User: Advanced202// @Calibration: 1203204// @Param: OFS2_Y205// @DisplayName: Compass2 offsets in milligauss on the Y axis206// @Description: Offset to be added to compass2's y-axis values to compensate for metal in the frame207// @Range: -400 400208// @Units: mGauss209// @Increment: 1210// @User: Advanced211// @Calibration: 1212213// @Param: OFS2_Z214// @DisplayName: Compass2 offsets in milligauss on the Z axis215// @Description: Offset to be added to compass2's z-axis values to compensate for metal in the frame216// @Range: -400 400217// @Units: mGauss218// @Increment: 1219// @User: Advanced220// @Calibration: 1221AP_GROUPINFO("OFS2", 10, Compass, _state._priv_instance[1].offset, 0),222223// @Param: MOT2_X224// @DisplayName: Motor interference compensation to compass2 for body frame X axis225// @Description: Multiplied by the current throttle and added to compass2's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)226// @Range: -1000 1000227// @Units: mGauss/A228// @Increment: 1229// @User: Advanced230// @Calibration: 1231232// @Param: MOT2_Y233// @DisplayName: Motor interference compensation to compass2 for body frame Y axis234// @Description: Multiplied by the current throttle and added to compass2's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)235// @Range: -1000 1000236// @Units: mGauss/A237// @Increment: 1238// @User: Advanced239// @Calibration: 1240241// @Param: MOT2_Z242// @DisplayName: Motor interference compensation to compass2 for body frame Z axis243// @Description: Multiplied by the current throttle and added to compass2's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)244// @Range: -1000 1000245// @Units: mGauss/A246// @Increment: 1247// @User: Advanced248// @Calibration: 1249AP_GROUPINFO("MOT2", 11, Compass, _state._priv_instance[1].motor_compensation, 0),250251#endif // COMPASS_MAX_INSTANCES252253#if COMPASS_MAX_INSTANCES > 2254// @Param: OFS3_X255// @DisplayName: Compass3 offsets in milligauss on the X axis256// @Description: Offset to be added to compass3's x-axis values to compensate for metal in the frame257// @Range: -400 400258// @Units: mGauss259// @Increment: 1260// @User: Advanced261// @Calibration: 1262263// @Param: OFS3_Y264// @DisplayName: Compass3 offsets in milligauss on the Y axis265// @Description: Offset to be added to compass3's y-axis values to compensate for metal in the frame266// @Range: -400 400267// @Units: mGauss268// @Increment: 1269// @User: Advanced270// @Calibration: 1271272// @Param: OFS3_Z273// @DisplayName: Compass3 offsets in milligauss on the Z axis274// @Description: Offset to be added to compass3's z-axis values to compensate for metal in the frame275// @Range: -400 400276// @Units: mGauss277// @Increment: 1278// @User: Advanced279// @Calibration: 1280AP_GROUPINFO("OFS3", 13, Compass, _state._priv_instance[2].offset, 0),281282// @Param: MOT3_X283// @DisplayName: Motor interference compensation to compass3 for body frame X axis284// @Description: Multiplied by the current throttle and added to compass3's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)285// @Range: -1000 1000286// @Units: mGauss/A287// @Increment: 1288// @User: Advanced289// @Calibration: 1290291// @Param: MOT3_Y292// @DisplayName: Motor interference compensation to compass3 for body frame Y axis293// @Description: Multiplied by the current throttle and added to compass3's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)294// @Range: -1000 1000295// @Units: mGauss/A296// @Increment: 1297// @User: Advanced298// @Calibration: 1299300// @Param: MOT3_Z301// @DisplayName: Motor interference compensation to compass3 for body frame Z axis302// @Description: Multiplied by the current throttle and added to compass3's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)303// @Range: -1000 1000304// @Units: mGauss/A305// @Increment: 1306// @User: Advanced307// @Calibration: 1308AP_GROUPINFO("MOT3", 14, Compass, _state._priv_instance[2].motor_compensation, 0),309#endif // COMPASS_MAX_INSTANCES310311// @Param: DEV_ID312// @DisplayName: Compass device id313// @Description: Compass device id. Automatically detected, do not set manually314// @ReadOnly: True315// @User: Advanced316AP_GROUPINFO("DEV_ID", 15, Compass, _state._priv_instance[0].dev_id, 0),317318#if COMPASS_MAX_INSTANCES > 1319// @Param: DEV_ID2320// @DisplayName: Compass2 device id321// @Description: Second compass's device id. Automatically detected, do not set manually322// @ReadOnly: True323// @User: Advanced324AP_GROUPINFO("DEV_ID2", 16, Compass, _state._priv_instance[1].dev_id, 0),325#endif // COMPASS_MAX_INSTANCES326327#if COMPASS_MAX_INSTANCES > 2328// @Param: DEV_ID3329// @DisplayName: Compass3 device id330// @Description: Third compass's device id. Automatically detected, do not set manually331// @ReadOnly: True332// @User: Advanced333AP_GROUPINFO("DEV_ID3", 17, Compass, _state._priv_instance[2].dev_id, 0),334#endif // COMPASS_MAX_INSTANCES335336#if COMPASS_MAX_INSTANCES > 1337// @Param: USE2338// @DisplayName: Compass2 used for yaw339// @Description: Enable or disable the secondary compass for determining heading.340// @Values: 0:Disabled,1:Enabled341// @User: Advanced342AP_GROUPINFO("USE2", 18, Compass, _use_for_yaw._priv_instance[1], 1),343344// @Param: ORIENT2345// @DisplayName: Compass2 orientation346// @Description: The orientation of a second external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles.347// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2348// @User: Advanced349AP_GROUPINFO("ORIENT2", 19, Compass, _state._priv_instance[1].orientation, ROTATION_NONE),350351// @Param: EXTERN2352// @DisplayName: Compass2 is attached via an external cable353// @Description: Configure second compass so it is attached externally. This is auto-detected on most boards. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.354// @Values: 0:Internal,1:External,2:ForcedExternal355// @User: Advanced356AP_GROUPINFO("EXTERN2",20, Compass, _state._priv_instance[1].external, 0),357#endif // COMPASS_MAX_INSTANCES358359#if COMPASS_MAX_INSTANCES > 2360// @Param: USE3361// @DisplayName: Compass3 used for yaw362// @Description: Enable or disable the tertiary compass for determining heading.363// @Values: 0:Disabled,1:Enabled364// @User: Advanced365AP_GROUPINFO("USE3", 21, Compass, _use_for_yaw._priv_instance[2], 1),366367// @Param: ORIENT3368// @DisplayName: Compass3 orientation369// @Description: The orientation of a third external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles.370// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2371// @User: Advanced372AP_GROUPINFO("ORIENT3", 22, Compass, _state._priv_instance[2].orientation, ROTATION_NONE),373374// @Param: EXTERN3375// @DisplayName: Compass3 is attached via an external cable376// @Description: Configure third compass so it is attached externally. This is auto-detected on most boards. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.377// @Values: 0:Internal,1:External,2:ForcedExternal378// @User: Advanced379AP_GROUPINFO("EXTERN3",23, Compass, _state._priv_instance[2].external, 0),380#endif // COMPASS_MAX_INSTANCES381382#if AP_COMPASS_DIAGONALS_ENABLED383// @Param: DIA_X384// @DisplayName: Compass soft-iron diagonal X component385// @Description: DIA_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]386// @User: Advanced387// @Calibration: 1388389// @Param: DIA_Y390// @DisplayName: Compass soft-iron diagonal Y component391// @Description: DIA_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]392// @User: Advanced393// @Calibration: 1394395// @Param: DIA_Z396// @DisplayName: Compass soft-iron diagonal Z component397// @Description: DIA_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]398// @User: Advanced399// @Calibration: 1400AP_GROUPINFO("DIA", 24, Compass, _state._priv_instance[0].diagonals, 1.0),401402// @Param: ODI_X403// @DisplayName: Compass soft-iron off-diagonal X component404// @Description: ODI_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]405// @User: Advanced406// @Calibration: 1407408// @Param: ODI_Y409// @DisplayName: Compass soft-iron off-diagonal Y component410// @Description: ODI_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]411// @User: Advanced412// @Calibration: 1413414// @Param: ODI_Z415// @DisplayName: Compass soft-iron off-diagonal Z component416// @Description: ODI_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]417// @User: Advanced418// @Calibration: 1419AP_GROUPINFO("ODI", 25, Compass, _state._priv_instance[0].offdiagonals, 0),420421#if COMPASS_MAX_INSTANCES > 1422// @Param: DIA2_X423// @DisplayName: Compass2 soft-iron diagonal X component424// @Description: DIA_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]425// @User: Advanced426// @Calibration: 1427428// @Param: DIA2_Y429// @DisplayName: Compass2 soft-iron diagonal Y component430// @Description: DIA_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]431// @User: Advanced432// @Calibration: 1433434// @Param: DIA2_Z435// @DisplayName: Compass2 soft-iron diagonal Z component436// @Description: DIA_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]437// @User: Advanced438// @Calibration: 1439AP_GROUPINFO("DIA2", 26, Compass, _state._priv_instance[1].diagonals, 1.0),440441// @Param: ODI2_X442// @DisplayName: Compass2 soft-iron off-diagonal X component443// @Description: ODI_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]444// @User: Advanced445// @Calibration: 1446447// @Param: ODI2_Y448// @DisplayName: Compass2 soft-iron off-diagonal Y component449// @Description: ODI_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]450// @User: Advanced451// @Calibration: 1452453// @Param: ODI2_Z454// @DisplayName: Compass2 soft-iron off-diagonal Z component455// @Description: ODI_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]456// @User: Advanced457// @Calibration: 1458AP_GROUPINFO("ODI2", 27, Compass, _state._priv_instance[1].offdiagonals, 0),459#endif // COMPASS_MAX_INSTANCES460461#if COMPASS_MAX_INSTANCES > 2462// @Param: DIA3_X463// @DisplayName: Compass3 soft-iron diagonal X component464// @Description: DIA_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]465// @User: Advanced466// @Calibration: 1467468// @Param: DIA3_Y469// @DisplayName: Compass3 soft-iron diagonal Y component470// @Description: DIA_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]471// @User: Advanced472// @Calibration: 1473474// @Param: DIA3_Z475// @DisplayName: Compass3 soft-iron diagonal Z component476// @Description: DIA_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]477// @User: Advanced478// @Calibration: 1479AP_GROUPINFO("DIA3", 28, Compass, _state._priv_instance[2].diagonals, 1.0),480481// @Param: ODI3_X482// @DisplayName: Compass3 soft-iron off-diagonal X component483// @Description: ODI_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]484// @User: Advanced485// @Calibration: 1486487// @Param: ODI3_Y488// @DisplayName: Compass3 soft-iron off-diagonal Y component489// @Description: ODI_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]490// @User: Advanced491// @Calibration: 1492493// @Param: ODI3_Z494// @DisplayName: Compass3 soft-iron off-diagonal Z component495// @Description: ODI_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]496// @User: Advanced497// @Calibration: 1498AP_GROUPINFO("ODI3", 29, Compass, _state._priv_instance[2].offdiagonals, 0),499#endif // COMPASS_MAX_INSTANCES500#endif // AP_COMPASS_DIAGONALS_ENABLED501502#if COMPASS_CAL_ENABLED503// @Param: CAL_FIT504// @DisplayName: Compass calibration fitness505// @Description: This controls the fitness level required for a successful compass calibration. A lower value makes for a stricter fit (less likely to pass). This is the value used for the primary magnetometer. Other magnetometers get double the value.506// @Range: 4 32507// @Values: 4:Very Strict,8:Strict,16:Default,32:Relaxed508// @Increment: 0.1509// @User: Advanced510AP_GROUPINFO("CAL_FIT", 30, Compass, _calibration_threshold, AP_COMPASS_CALIBRATION_FITNESS_DEFAULT),511#endif512513#ifndef HAL_BUILD_AP_PERIPH514// @Param: OFFS_MAX515// @DisplayName: Compass maximum offset516// @Description: This sets the maximum allowed compass offset in calibration and arming checks517// @Range: 500 3000518// @Increment: 1519// @User: Advanced520AP_GROUPINFO("OFFS_MAX", 31, Compass, _offset_max, AP_COMPASS_OFFSETS_MAX_DEFAULT),521#endif522523#if COMPASS_MOT_ENABLED524// @Group: PMOT525// @Path: Compass_PerMotor.cpp526AP_SUBGROUPINFO(_per_motor, "PMOT", 32, Compass, Compass_PerMotor),527#endif528529// @Param: DISBLMSK530// @DisplayName: Compass disable driver type mask531// @Description: This is a bitmask of driver types to disable. If a driver type is set in this mask then that driver will not try to find a sensor at startup532// @Bitmask: 0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:DroneCAN,12:QMC5883,14:MAG3110,15:IST8308,16:RM3100,17:MSP,18:ExternalAHRS,19:MMC5XX3,20:QMC5883P,21:BMM350,22:IIS2MDC533// @User: Advanced534AP_GROUPINFO("DISBLMSK", 33, Compass, _driver_type_mask, 0),535536// @Param: FLTR_RNG537// @DisplayName: Range in which sample is accepted538// @Description: This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.539// @Units: %540// @Range: 0 100541// @Increment: 1542AP_GROUPINFO("FLTR_RNG", 34, Compass, _filter_range, HAL_COMPASS_FILTER_DEFAULT),543544#if COMPASS_CAL_ENABLED545// @Param: AUTO_ROT546// @DisplayName: Automatically check orientation547// @Description: When enabled this will automatically check the orientation of compasses on successful completion of compass calibration. If set to 2 then external compasses will have their orientation automatically corrected.548// @Values: 0:Disabled,1:CheckOnly,2:CheckAndFix,3:use same tolerance to auto rotate 45 deg rotations549AP_GROUPINFO("AUTO_ROT", 35, Compass, _rotate_auto, HAL_COMPASS_AUTO_ROT_DEFAULT),550#endif551552#if COMPASS_MAX_INSTANCES > 1553// @Param: PRIO1_ID554// @DisplayName: Compass device id with 1st order priority555// @Description: Compass device id with 1st order priority, set automatically if 0. Reboot required after change.556// @RebootRequired: True557// @User: Advanced558AP_GROUPINFO("PRIO1_ID", 36, Compass, _priority_did_stored_list._priv_instance[0], 0),559560// @Param: PRIO2_ID561// @DisplayName: Compass device id with 2nd order priority562// @Description: Compass device id with 2nd order priority, set automatically if 0. Reboot required after change.563// @RebootRequired: True564// @User: Advanced565AP_GROUPINFO("PRIO2_ID", 37, Compass, _priority_did_stored_list._priv_instance[1], 0),566#endif // COMPASS_MAX_INSTANCES567568#if COMPASS_MAX_INSTANCES > 2569// @Param: PRIO3_ID570// @DisplayName: Compass device id with 3rd order priority571// @Description: Compass device id with 3rd order priority, set automatically if 0. Reboot required after change.572// @RebootRequired: True573// @User: Advanced574AP_GROUPINFO("PRIO3_ID", 38, Compass, _priority_did_stored_list._priv_instance[2], 0),575#endif // COMPASS_MAX_INSTANCES576577// @Param: ENABLE578// @DisplayName: Enable Compass579// @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.580// @User: Standard581// @RebootRequired: True582// @Values: 0:Disabled,1:Enabled583AP_GROUPINFO("ENABLE", 39, Compass, _enabled, AP_COMPASS_ENABLE_DEFAULT),584585#ifndef HAL_BUILD_AP_PERIPH586// @Param: SCALE587// @DisplayName: Compass1 scale factor588// @Description: Scaling factor for first compass to compensate for sensor scaling errors. If this is 0 then no scaling is done589// @User: Standard590// @Range: 0 1.3591AP_GROUPINFO("SCALE", 40, Compass, _state._priv_instance[0].scale_factor, 0),592593#if COMPASS_MAX_INSTANCES > 1594// @Param: SCALE2595// @DisplayName: Compass2 scale factor596// @Description: Scaling factor for 2nd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done597// @User: Standard598// @Range: 0 1.3599AP_GROUPINFO("SCALE2", 41, Compass, _state._priv_instance[1].scale_factor, 0),600#endif601602#if COMPASS_MAX_INSTANCES > 2603// @Param: SCALE3604// @DisplayName: Compass3 scale factor605// @Description: Scaling factor for 3rd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done606// @User: Standard607// @Range: 0 1.3608AP_GROUPINFO("SCALE3", 42, Compass, _state._priv_instance[2].scale_factor, 0),609#endif610#endif // HAL_BUILD_AP_PERIPH611612#ifndef HAL_BUILD_AP_PERIPH613// @Param: OPTIONS614// @DisplayName: Compass options615// @Description: This sets options to change the behaviour of the compass616// @Bitmask: 0:CalRequireGPS617// @Bitmask: 1: Allow missing DroneCAN compasses to be automaticaly replaced (calibration still required)618// @User: Advanced619AP_GROUPINFO("OPTIONS", 43, Compass, _options, 0),620#endif621622#if COMPASS_MAX_UNREG_DEV > 0623// @Param: DEV_ID4624// @DisplayName: Compass4 device id625// @Description: Extra 4th compass's device id. Automatically detected, do not set manually626// @ReadOnly: True627// @User: Advanced628AP_GROUPINFO("DEV_ID4", 44, Compass, extra_dev_id[0], 0),629#endif // COMPASS_MAX_UNREG_DEV630631#if COMPASS_MAX_UNREG_DEV > 1632// @Param: DEV_ID5633// @DisplayName: Compass5 device id634// @Description: Extra 5th compass's device id. Automatically detected, do not set manually635// @ReadOnly: True636// @User: Advanced637AP_GROUPINFO("DEV_ID5", 45, Compass, extra_dev_id[1], 0),638#endif // COMPASS_MAX_UNREG_DEV639640#if COMPASS_MAX_UNREG_DEV > 2641// @Param: DEV_ID6642// @DisplayName: Compass6 device id643// @Description: Extra 6th compass's device id. Automatically detected, do not set manually644// @ReadOnly: True645// @User: Advanced646AP_GROUPINFO("DEV_ID6", 46, Compass, extra_dev_id[2], 0),647#endif // COMPASS_MAX_UNREG_DEV648649#if COMPASS_MAX_UNREG_DEV > 3650// @Param: DEV_ID7651// @DisplayName: Compass7 device id652// @Description: Extra 7th compass's device id. Automatically detected, do not set manually653// @ReadOnly: True654// @User: Advanced655AP_GROUPINFO("DEV_ID7", 47, Compass, extra_dev_id[3], 0),656#endif // COMPASS_MAX_UNREG_DEV657658#if COMPASS_MAX_UNREG_DEV > 4659// @Param: DEV_ID8660// @DisplayName: Compass8 device id661// @Description: Extra 8th compass's device id. Automatically detected, do not set manually662// @ReadOnly: True663// @User: Advanced664AP_GROUPINFO("DEV_ID8", 48, Compass, extra_dev_id[4], 0),665#endif // COMPASS_MAX_UNREG_DEV666667// @Param: CUS_ROLL668// @DisplayName: Custom orientation roll offset669// @Description: Compass mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.670// @Range: -180 180671// @Units: deg672// @Increment: 1673// @RebootRequired: True674// @User: Advanced675676// index 49677678// @Param: CUS_PIT679// @DisplayName: Custom orientation pitch offset680// @Description: Compass mounting position pitch offset. Positive values = pitch up, negative values = pitch down. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.681// @Range: -180 180682// @Units: deg683// @Increment: 1684// @RebootRequired: True685// @User: Advanced686687// index 50688689// @Param: CUS_YAW690// @DisplayName: Custom orientation yaw offset691// @Description: Compass mounting position yaw offset. Positive values = yaw right, negative values = yaw left. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.692// @Range: -180 180693// @Units: deg694// @Increment: 1695// @RebootRequired: True696// @User: Advanced697698// index 51699700AP_GROUPEND701};702703// Default constructor.704// Note that the Vector/Matrix constructors already implicitly zero705// their values.706//707Compass::Compass(void)708{709if (_singleton != nullptr) {710#if CONFIG_HAL_BOARD == HAL_BOARD_SITL711AP_HAL::panic("Compass must be singleton");712#endif713return;714}715_singleton = this;716AP_Param::setup_object_defaults(this, var_info);717}718719// Default init method720//721void Compass::init()722{723if (!_enabled) {724return;725}726727/*728on init() if any devid is set then we set suppress_devid_save to729false. This is used to determine if we save device ids during730the init process.731*/732suppress_devid_save = true;733for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {734if (_state._priv_instance[i].dev_id != 0) {735suppress_devid_save = false;736break;737}738#if COMPASS_MAX_INSTANCES > 1739if (_priority_did_stored_list._priv_instance[i] != 0) {740suppress_devid_save = false;741break;742}743#endif744}745746// convert to new custom rotation method747// PARAMETER_CONVERSION - Added: Nov-2021748#if AP_CUSTOMROTATIONS_ENABLED749for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {750if (_state[i].orientation != ROTATION_CUSTOM_OLD) {751continue;752}753_state[i].orientation.set_and_save(ROTATION_CUSTOM_2);754AP_Param::ConversionInfo info;755if (AP_Param::find_top_level_key_by_pointer(this, info.old_key)) {756info.type = AP_PARAM_FLOAT;757float rpy[3] = {};758AP_Float rpy_param;759for (info.old_group_element=49; info.old_group_element<=51; info.old_group_element++) {760if (AP_Param::find_old_parameter(&info, &rpy_param)) {761rpy[info.old_group_element-49] = rpy_param.get();762}763}764AP::custom_rotations().convert(ROTATION_CUSTOM_2, rpy[0], rpy[1], rpy[2]);765}766break;767}768#endif // AP_CUSTOMROTATIONS_ENABLED769770#if COMPASS_MAX_INSTANCES > 1771// Look if there was a primary compass setup in previous version772// if so and the primary compass is not set in current setup773// make the devid as primary.774if (_priority_did_stored_list[Priority(0)] == 0) {775uint16_t k_param_compass;776if (AP_Param::find_top_level_key_by_pointer(this, k_param_compass)) {777const AP_Param::ConversionInfo primary_compass_old_param = {k_param_compass, 12, AP_PARAM_INT8, ""};778AP_Int8 value;779value.set(0);780bool primary_param_exists = AP_Param::find_old_parameter(&primary_compass_old_param, &value);781int8_t oldvalue = value.get();782if ((oldvalue!=0) && (oldvalue<COMPASS_MAX_INSTANCES) && primary_param_exists) {783_priority_did_stored_list[Priority(0)].set_and_save_ifchanged(_state[StateIndex(oldvalue)].dev_id);784}785}786}787788// Load priority list from storage, the changes to priority list789// by user only take effect post reboot, after this790if (!suppress_devid_save) {791for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {792if (_priority_did_stored_list[i] != 0) {793_priority_did_list[i] = _priority_did_stored_list[i];794} else {795// Maintain a list without gaps and duplicates796for (Priority j(i+1); j<COMPASS_MAX_INSTANCES; j++) {797int32_t temp;798if (_priority_did_stored_list[j] == _priority_did_stored_list[i]) {799_priority_did_stored_list[j].set_and_save_ifchanged(0);800}801if (_priority_did_stored_list[j] == 0) {802continue;803}804temp = _priority_did_stored_list[j];805_priority_did_stored_list[j].set_and_save_ifchanged(0);806_priority_did_list[i] = temp;807_priority_did_stored_list[i].set_and_save_ifchanged(temp);808break;809}810}811}812}813#endif // COMPASS_MAX_INSTANCES814815// cache expected dev ids for use during runtime detection816for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {817_state[i].expected_dev_id = _state[i].dev_id;818}819820#if COMPASS_MAX_UNREG_DEV821// set the dev_id to 0 for undetected compasses. extra_dev_id is just an822// interface for users to see unreg compasses, we actually never store it823// in storage.824for (uint8_t i=_unreg_compass_count; i<COMPASS_MAX_UNREG_DEV; i++) {825// cache the extra devices detected in last boot826// for detecting replacement mag827_previously_unreg_mag[i] = extra_dev_id[i];828extra_dev_id[i].set(0);829}830#endif831832#if COMPASS_MAX_INSTANCES > 1833// This method calls set_and_save_ifchanged on parameters834// which are set() but not saved() during normal runtime,835// do not move this call without ensuring that is not happening836// read comments under set_and_save_ifchanged for details837if (!suppress_devid_save) {838_reorder_compass_params();839}840#endif841842if (_compass_count == 0) {843// detect available backends. Only called once844_detect_backends();845}846847if (_compass_count != 0) {848// get initial health status849hal.scheduler->delay(100);850read();851}852// set the dev_id to 0 for undetected compasses, to make it easier853// for users to see how many compasses are detected. We don't do a854// set_and_save() as the user may have temporarily removed the855// compass, and we don't want to force a re-cal if they plug it856// back in again857for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {858if (!_state[i].registered) {859_state[i].dev_id.set(0);860}861}862863#ifndef HAL_BUILD_AP_PERIPH864// updating the AHRS orientation updates our own orientation:865AP::ahrs().update_orientation();866#endif867868init_done = true;869suppress_devid_save = false;870}871872#if COMPASS_MAX_INSTANCES > 1 || COMPASS_MAX_UNREG_DEV873// Update Priority List for Mags, by default, we just874// load them as they come up the first time875Compass::Priority Compass::_update_priority_list(int32_t dev_id)876{877// Check if already in priority list878for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {879if (_priority_did_list[i] == dev_id) {880if (i >= _compass_count) {881_compass_count = uint8_t(i)+1;882}883return i;884}885}886887// We are not in priority list, let's add at first empty888for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {889if (_priority_did_stored_list[i] == 0) {890if (suppress_devid_save) {891_priority_did_stored_list[i].set(dev_id);892} else {893_priority_did_stored_list[i].set_and_save(dev_id);894}895_priority_did_list[i] = dev_id;896if (i >= _compass_count) {897_compass_count = uint8_t(i)+1;898}899return i;900}901}902return Priority(COMPASS_MAX_INSTANCES);903}904#endif905906907#if COMPASS_MAX_INSTANCES > 1908// This method reorganises devid list to match909// priority list, only call before detection at boot910void Compass::_reorder_compass_params()911{912mag_state swap_state;913StateIndex curr_state_id;914for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {915if (_priority_did_list[i] == 0) {916continue;917}918curr_state_id = COMPASS_MAX_INSTANCES;919for (StateIndex j(0); j<COMPASS_MAX_INSTANCES; j++) {920if (_priority_did_list[i] == _state[j].dev_id) {921curr_state_id = j;922break;923}924}925if (curr_state_id != COMPASS_MAX_INSTANCES && uint8_t(curr_state_id) != uint8_t(i)) {926//let's swap927swap_state.copy_from(_state[curr_state_id]);928_state[curr_state_id].copy_from(_state[StateIndex(uint8_t(i))]);929_state[StateIndex(uint8_t(i))].copy_from(swap_state);930}931}932}933#endif934935void Compass::mag_state::copy_from(const Compass::mag_state& state)936{937external.set_and_save_ifchanged(state.external);938orientation.set_and_save_ifchanged(state.orientation);939offset.set_and_save_ifchanged(state.offset);940#if AP_COMPASS_DIAGONALS_ENABLED941diagonals.set_and_save_ifchanged(state.diagonals);942offdiagonals.set_and_save_ifchanged(state.offdiagonals);943#endif944scale_factor.set_and_save_ifchanged(state.scale_factor);945dev_id.set_and_save_ifchanged(state.dev_id);946motor_compensation.set_and_save_ifchanged(state.motor_compensation);947expected_dev_id = state.expected_dev_id;948detected_dev_id = state.detected_dev_id;949}950// Register a new compass instance951//952bool Compass::register_compass(int32_t dev_id, uint8_t& instance)953{954955#if COMPASS_MAX_INSTANCES == 1 && !COMPASS_MAX_UNREG_DEV956// simple single compass setup for AP_Periph957Priority priority(0);958StateIndex i(0);959if (_state[i].registered) {960return false;961}962_state[i].registered = true;963_state[i].priority = priority;964instance = uint8_t(i);965_compass_count = 1;966return true;967#else968Priority priority;969// Check if we already have this dev_id registered970for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {971priority = _update_priority_list(dev_id);972if (_state[i].expected_dev_id == dev_id && priority < COMPASS_MAX_INSTANCES) {973_state[i].registered = true;974_state[i].priority = priority;975instance = uint8_t(i);976return true;977}978}979980// This is an unregistered compass, check if any free slot is available981for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {982priority = _update_priority_list(dev_id);983if (_state[i].dev_id == 0 && priority < COMPASS_MAX_INSTANCES) {984_state[i].registered = true;985_state[i].priority = priority;986instance = uint8_t(i);987return true;988}989}990991// This might be a replacement compass module, find any unregistered compass992// instance and replace that993for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {994priority = _update_priority_list(dev_id);995if (!_state[i].registered && priority < COMPASS_MAX_INSTANCES) {996_state[i].registered = true;997_state[i].priority = priority;998instance = uint8_t(i);999return true;1000}1001}1002#endif10031004#if COMPASS_MAX_UNREG_DEV1005// Set extra dev id1006if (_unreg_compass_count >= COMPASS_MAX_UNREG_DEV) {1007AP_HAL::panic("Too many compass instances");1008}10091010for (uint8_t i=0; i<COMPASS_MAX_UNREG_DEV; i++) {1011if (extra_dev_id[i] == dev_id) {1012if (i >= _unreg_compass_count) {1013_unreg_compass_count = i+1;1014}1015instance = i+COMPASS_MAX_INSTANCES;1016return false;1017} else if (extra_dev_id[i] == 0) {1018extra_dev_id[_unreg_compass_count++].set(dev_id);1019instance = i+COMPASS_MAX_INSTANCES;1020return false;1021}1022}1023#else1024AP_HAL::panic("Too many compass instances");1025#endif10261027return false;1028}10291030Compass::StateIndex Compass::_get_state_id(Compass::Priority priority) const1031{1032#if COMPASS_MAX_INSTANCES > 11033if (_priority_did_list[priority] == 0) {1034return StateIndex(COMPASS_MAX_INSTANCES);1035}1036for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {1037if (_priority_did_list[priority] == _state[i].detected_dev_id) {1038return i;1039}1040}1041return StateIndex(COMPASS_MAX_INSTANCES);1042#else1043return StateIndex(0);1044#endif1045}10461047bool Compass::_add_backend(AP_Compass_Backend *backend)1048{1049if (!backend) {1050return false;1051}10521053if (_backend_count == COMPASS_MAX_BACKEND) {1054return false;1055}10561057_backends[_backend_count++] = backend;10581059return true;1060}10611062/*1063return true if a driver type is enabled1064*/1065bool Compass::_driver_enabled(enum DriverType driver_type)1066{1067uint32_t mask = (1U<<uint8_t(driver_type));1068return (mask & uint32_t(_driver_type_mask.get())) == 0;1069}10701071/*1072wrapper around hal.i2c_mgr->get_device() that prevents duplicate devices being opened1073*/1074bool Compass::_have_i2c_driver(uint8_t bus, uint8_t address) const1075{1076for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {1077if (!_state[i].registered) {1078continue;1079}1080if (AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C, bus, address, 0) ==1081AP_HAL::Device::change_bus_id(uint32_t(_state[i].dev_id.get()), 0)) {1082// we are already using this device1083return true;1084}1085}1086return false;1087}10881089#if COMPASS_MAX_UNREG_DEV > 01090#define CHECK_UNREG_LIMIT_RETURN if (_unreg_compass_count == COMPASS_MAX_UNREG_DEV) return1091#else1092#define CHECK_UNREG_LIMIT_RETURN1093#endif10941095/*1096macro to add a backend with check for too many backends or compass1097instances. We don't try to start more than the maximum allowed1098*/1099#define ADD_BACKEND(driver_type, backend) \1100do { if (_driver_enabled(driver_type)) { _add_backend(backend); } \1101CHECK_UNREG_LIMIT_RETURN; \1102} while (0)11031104#define GET_I2C_DEVICE(bus, address) _have_i2c_driver(bus, address)?nullptr:hal.i2c_mgr->get_device(bus, address)11051106/*1107look for compasses on external i2c buses1108*/1109void Compass::_probe_external_i2c_compasses(void)1110{1111#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1112bool all_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2);1113(void)all_external; // in case all backends using this are compiled out1114#endif1115#if AP_COMPASS_HMC5843_ENABLED1116// external i2c bus1117FOREACH_I2C_EXTERNAL(i) {1118ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),1119true, ROTATION_ROLL_180));1120}11211122#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1123if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_MINDPXV2 &&1124AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_AEROFC) {1125// internal i2c bus1126FOREACH_I2C_INTERNAL(i) {1127ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR),1128all_external, all_external?ROTATION_ROLL_180:ROTATION_YAW_270));1129}1130}1131#endif // !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1132#endif // AP_COMPASS_HMC5843_ENABLED11331134#if AP_COMPASS_QMC5883L_ENABLED1135//external i2c bus1136FOREACH_I2C_EXTERNAL(i) {1137ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),1138true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL));1139}11401141// internal i2c bus1142#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1143if (all_external) {1144// only probe QMC5883L on internal if we are treating internals as externals1145FOREACH_I2C_INTERNAL(i) {1146ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR),1147all_external,1148all_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL));1149}1150}1151#endif1152#endif // AP_COMPASS_QMC5883L_ENABLED11531154#if AP_COMPASS_QMC5883P_ENABLED1155//external i2c bus1156FOREACH_I2C_EXTERNAL(i) {1157ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR),1158true, HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL));1159}11601161// internal i2c bus1162#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1163if (all_external) {1164// only probe QMC5883P on internal if we are treating internals as externals1165FOREACH_I2C_INTERNAL(i) {1166ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR),1167all_external,1168all_external?HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883P_ORIENTATION_INTERNAL));1169}1170}1171#endif1172#endif // AP_COMPASS_QMC5883P_ENABLED11731174#if AP_COMPASS_IIS2MDC_ENABLED1175//external i2c bus1176FOREACH_I2C_EXTERNAL(i) {1177ADD_BACKEND(DRIVER_IIS2MDC, AP_Compass_IIS2MDC::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IIS2MDC_I2C_ADDR),1178true, HAL_COMPASS_IIS2MDC_ORIENTATION_EXTERNAL));1179}11801181// internal i2c bus1182#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1183if (all_external) {1184// only probe IIS2MDC on internal if we are treating internals as externals1185FOREACH_I2C_INTERNAL(i) {1186ADD_BACKEND(DRIVER_IIS2MDC, AP_Compass_IIS2MDC::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IIS2MDC_I2C_ADDR),1187all_external,1188all_external?HAL_COMPASS_IIS2MDC_ORIENTATION_EXTERNAL:HAL_COMPASS_IIS2MDC_ORIENTATION_INTERNAL));1189}1190}1191#endif1192#endif // AP_COMPASS_QMC5883P_ENABLED11931194#ifndef HAL_BUILD_AP_PERIPH1195// AK09916 on ICM209481196#if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED1197FOREACH_I2C_EXTERNAL(i) {1198ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),1199GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),1200true, ROTATION_PITCH_180_YAW_90));1201ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),1202GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR2),1203true, ROTATION_PITCH_180_YAW_90));1204}12051206#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1207FOREACH_I2C_INTERNAL(i) {1208ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),1209GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR),1210all_external, ROTATION_PITCH_180_YAW_90));1211ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),1212GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR2),1213all_external, ROTATION_PITCH_180_YAW_90));1214}1215#endif1216#endif // AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED1217#endif // HAL_BUILD_AP_PERIPH12181219#if AP_COMPASS_LIS3MDL_ENABLED1220// lis3mdl on bus 0 with default address1221#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1222FOREACH_I2C_INTERNAL(i) {1223ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),1224all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));1225}12261227// lis3mdl on bus 0 with alternate address1228FOREACH_I2C_INTERNAL(i) {1229ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),1230all_external, all_external?ROTATION_YAW_90:ROTATION_NONE));1231}1232#endif1233// external lis3mdl on bus 1 with default address1234FOREACH_I2C_EXTERNAL(i) {1235ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR),1236true, ROTATION_YAW_90));1237}12381239// external lis3mdl on bus 1 with alternate address1240FOREACH_I2C_EXTERNAL(i) {1241ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2),1242true, ROTATION_YAW_90));1243}1244#endif // AP_COMPASS_LIS3MDL_ENABLED12451246#if AP_COMPASS_AK09916_ENABLED1247// AK09916. This can be found twice, due to the ICM20948 i2c bus pass-thru, so we need to be careful to avoid that1248FOREACH_I2C_EXTERNAL(i) {1249ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),1250true, ROTATION_YAW_270));1251}1252#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1253FOREACH_I2C_INTERNAL(i) {1254ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR),1255all_external, all_external?ROTATION_YAW_270:ROTATION_NONE));1256}1257#endif1258#endif // AP_COMPASS_AK09916_ENABLED12591260#if AP_COMPASS_IST8310_ENABLED1261// IST8310 on external and internal bus1262if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV5 &&1263AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV6) {1264enum Rotation default_rotation = AP_COMPASS_IST8310_DEFAULT_ROTATION;12651266if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_AEROFC) {1267default_rotation = ROTATION_PITCH_180_YAW_90;1268}1269// probe all 4 possible addresses1270const uint8_t ist8310_addr[] = { 0x0C, 0x0D, 0x0E, 0x0F };12711272for (uint8_t a=0; a<ARRAY_SIZE(ist8310_addr); a++) {1273FOREACH_I2C_EXTERNAL(i) {1274ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),1275true, default_rotation));1276}1277#if !defined(HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE) && !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1278FOREACH_I2C_INTERNAL(i) {1279ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]),1280all_external, default_rotation));1281}1282#endif1283}1284}1285#endif // AP_COMPASS_IST8310_ENABLED12861287#if AP_COMPASS_IST8308_ENABLED1288// external i2c bus1289FOREACH_I2C_EXTERNAL(i) {1290ADD_BACKEND(DRIVER_IST8308, AP_Compass_IST8308::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8308_I2C_ADDR),1291true, ROTATION_NONE));1292}1293#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1294FOREACH_I2C_INTERNAL(i) {1295ADD_BACKEND(DRIVER_IST8308, AP_Compass_IST8308::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8308_I2C_ADDR),1296all_external, ROTATION_NONE));1297}1298#endif1299#endif // AP_COMPASS_IST8308_ENABLED13001301#if AP_COMPASS_MMC3416_ENABLED1302// external i2c bus1303FOREACH_I2C_EXTERNAL(i) {1304ADD_BACKEND(DRIVER_MMC3416, AP_Compass_MMC3416::probe(GET_I2C_DEVICE(i, HAL_COMPASS_MMC3416_I2C_ADDR),1305true, ROTATION_NONE));1306}1307#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1308FOREACH_I2C_INTERNAL(i) {1309ADD_BACKEND(DRIVER_MMC3416, AP_Compass_MMC3416::probe(GET_I2C_DEVICE(i, HAL_COMPASS_MMC3416_I2C_ADDR),1310all_external, ROTATION_NONE));1311}1312#endif1313#endif // AP_COMPASS_MMC3416_ENABLED13141315#if AP_COMPASS_RM3100_ENABLED1316#ifdef HAL_COMPASS_RM3100_I2C_ADDR1317const uint8_t rm3100_addresses[] = { HAL_COMPASS_RM3100_I2C_ADDR };1318#else1319// RM3100 can be on 4 different addresses1320const uint8_t rm3100_addresses[] = { HAL_COMPASS_RM3100_I2C_ADDR1,1321HAL_COMPASS_RM3100_I2C_ADDR2,1322HAL_COMPASS_RM3100_I2C_ADDR3,1323HAL_COMPASS_RM3100_I2C_ADDR4 };1324#endif1325// external i2c bus1326FOREACH_I2C_EXTERNAL(i) {1327for (uint8_t j=0; j<ARRAY_SIZE(rm3100_addresses); j++) {1328ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(GET_I2C_DEVICE(i, rm3100_addresses[j]), true, ROTATION_NONE));1329}1330}13311332#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1333FOREACH_I2C_INTERNAL(i) {1334for (uint8_t j=0; j<ARRAY_SIZE(rm3100_addresses); j++) {1335ADD_BACKEND(DRIVER_RM3100, AP_Compass_RM3100::probe(GET_I2C_DEVICE(i, rm3100_addresses[j]), all_external, ROTATION_NONE));1336}1337}1338#endif1339#endif // AP_COMPASS_RM3100_ENABLED13401341#if AP_COMPASS_BMM150_DETECT_BACKENDS_ENABLED1342// BMM150 on I2C1343FOREACH_I2C_EXTERNAL(i) {1344for (uint8_t addr=BMM150_I2C_ADDR_MIN; addr <= BMM150_I2C_ADDR_MAX; addr++) {1345ADD_BACKEND(DRIVER_BMM150,1346AP_Compass_BMM150::probe(GET_I2C_DEVICE(i, addr), true, ROTATION_NONE));1347}1348}1349#endif // AP_COMPASS_BMM150_ENABLED13501351#if AP_COMPASS_BMM350_ENABLED1352// BMM350 on I2C1353FOREACH_I2C_EXTERNAL(i) {1354for (uint8_t addr=BMM350_I2C_ADDR_MIN; addr <= BMM350_I2C_ADDR_MAX; addr++) {1355ADD_BACKEND(DRIVER_BMM350,1356AP_Compass_BMM350::probe(GET_I2C_DEVICE(i, addr), true, ROTATION_NONE));1357}1358}1359#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)1360FOREACH_I2C_INTERNAL(i) {1361for (uint8_t addr=BMM350_I2C_ADDR_MIN; addr <= BMM350_I2C_ADDR_MAX; addr++) {1362ADD_BACKEND(DRIVER_BMM350, AP_Compass_BMM350::probe(GET_I2C_DEVICE(i, addr), all_external, ROTATION_NONE));1363}1364}1365#endif1366#endif // AP_COMPASS_BMM350_ENABLED1367}13681369/*1370detect available backends for this board1371*/1372void Compass::_detect_backends(void)1373{1374#if AP_COMPASS_EXTERNALAHRS_ENABLED1375const int8_t serial_port = AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::COMPASS);1376if (serial_port >= 0) {1377ADD_BACKEND(DRIVER_EXTERNALAHRS, NEW_NOTHROW AP_Compass_ExternalAHRS(serial_port));1378}1379#endif13801381#if AP_FEATURE_BOARD_DETECT1382if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) {1383// default to disabling LIS3MDL on pixhawk2 due to hardware issue1384#if AP_COMPASS_LIS3MDL_ENABLED1385_driver_type_mask.set_default(1U<<DRIVER_LIS3MDL);1386#endif1387}1388#endif13891390#if AP_COMPASS_SITL_ENABLED && !AP_TEST_DRONECAN_DRIVERS1391ADD_BACKEND(DRIVER_SITL, NEW_NOTHROW AP_Compass_SITL());1392#endif13931394#if AP_COMPASS_DRONECAN_ENABLED1395// probe DroneCAN before I2C and SPI so that DroneCAN compasses1396// default to first in the list for a new board1397probe_dronecan_compasses();1398CHECK_UNREG_LIMIT_RETURN;1399#endif14001401#ifdef HAL_PROBE_EXTERNAL_I2C_COMPASSES1402// allow boards to ask for external probing of all i2c compass types in hwdef.dat1403_probe_external_i2c_compasses();1404CHECK_UNREG_LIMIT_RETURN;1405#endif14061407#if AP_COMPASS_MSP_ENABLED1408for (uint8_t i=0; i<8; i++) {1409if (msp_instance_mask & (1U<<i)) {1410ADD_BACKEND(DRIVER_MSP, NEW_NOTHROW AP_Compass_MSP(i));1411}1412}1413#endif14141415// finally look for i2c and spi compasses not found yet1416CHECK_UNREG_LIMIT_RETURN;1417probe_i2c_spi_compasses();14181419if (_backend_count == 0 ||1420_compass_count == 0) {1421DEV_PRINTF("No Compass backends available\n");1422}1423}14241425/*1426probe i2c and SPI compasses1427*/1428void Compass::probe_i2c_spi_compasses(void)1429{1430#if defined(HAL_MAG_PROBE_LIST)1431// driver probes defined by COMPASS lines in hwdef.dat1432HAL_MAG_PROBE_LIST;1433#elif AP_FEATURE_BOARD_DETECT1434switch (AP_BoardConfig::get_board_type()) {1435case AP_BoardConfig::PX4_BOARD_PX4V1:1436case AP_BoardConfig::PX4_BOARD_PIXHAWK:1437case AP_BoardConfig::PX4_BOARD_PHMINI:1438case AP_BoardConfig::PX4_BOARD_AUAV21:1439case AP_BoardConfig::PX4_BOARD_PH2SLIM:1440case AP_BoardConfig::PX4_BOARD_PIXHAWK2:1441case AP_BoardConfig::PX4_BOARD_MINDPXV2:1442case AP_BoardConfig::PX4_BOARD_FMUV5:1443case AP_BoardConfig::PX4_BOARD_FMUV6:1444case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:1445case AP_BoardConfig::PX4_BOARD_AEROFC:1446_probe_external_i2c_compasses();1447CHECK_UNREG_LIMIT_RETURN;1448break;14491450case AP_BoardConfig::PX4_BOARD_PCNC1:1451#if AP_COMPASS_BMM150_ENABLED1452ADD_BACKEND(DRIVER_BMM150,1453AP_Compass_BMM150::probe(GET_I2C_DEVICE(0, 0x10), false, ROTATION_NONE));1454#endif1455break;1456case AP_BoardConfig::VRX_BOARD_BRAIN54:1457case AP_BoardConfig::VRX_BOARD_BRAIN51: {1458#if AP_COMPASS_HMC5843_ENABLED1459// external i2c bus1460ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),1461true, ROTATION_ROLL_180));14621463// internal i2c bus1464ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),1465false, ROTATION_YAW_270));1466#endif // AP_COMPASS_HMC5843_ENABLED1467}1468break;14691470case AP_BoardConfig::VRX_BOARD_BRAIN52:1471case AP_BoardConfig::VRX_BOARD_BRAIN52E:1472case AP_BoardConfig::VRX_BOARD_CORE10:1473case AP_BoardConfig::VRX_BOARD_UBRAIN51:1474case AP_BoardConfig::VRX_BOARD_UBRAIN52: {1475#if AP_COMPASS_HMC5843_ENABLED1476// external i2c bus1477ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(1, HAL_COMPASS_HMC5843_I2C_ADDR),1478true, ROTATION_ROLL_180));1479#endif // AP_COMPASS_HMC5843_ENABLED1480}1481break;14821483default:1484break;1485}1486switch (AP_BoardConfig::get_board_type()) {1487case AP_BoardConfig::PX4_BOARD_PIXHAWK:1488#if AP_COMPASS_HMC5843_ENABLED1489ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(hal.spi->get_device(HAL_COMPASS_HMC5843_NAME),1490false, ROTATION_PITCH_180));1491#endif1492#if AP_COMPASS_LSM303D_ENABLED1493ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_NONE));1494#endif1495break;14961497case AP_BoardConfig::PX4_BOARD_PIXHAWK2:1498#if AP_COMPASS_LSM303D_ENABLED1499ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270));1500#endif1501#if AP_COMPASS_AK8963_ENABLED1502// we run the AK8963 only on the 2nd MPU9250, which leaves the1503// first MPU9250 to run without disturbance at high rate1504ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270));1505#endif1506#if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED1507ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90));1508#endif1509break;15101511case AP_BoardConfig::PX4_BOARD_FMUV5:1512case AP_BoardConfig::PX4_BOARD_FMUV6:1513#if AP_COMPASS_IST8310_ENABLED1514FOREACH_I2C_EXTERNAL(i) {1515ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),1516true, ROTATION_ROLL_180_YAW_90));1517}1518FOREACH_I2C_INTERNAL(i) {1519ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR),1520false, ROTATION_ROLL_180_YAW_90));1521}1522#endif // AP_COMPASS_IST8310_ENABLED1523break;15241525case AP_BoardConfig::PX4_BOARD_SP01:1526#if AP_COMPASS_AK8963_ENABLED1527ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE));1528#endif1529break;15301531case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:1532#if AP_COMPASS_AK8963_ENABLED1533ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));1534#endif1535#if AP_COMPASS_LIS3MDL_ENABLED1536ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME),1537false, ROTATION_NONE));1538#endif // AP_COMPASS_LIS3MDL_ENABLED1539break;15401541case AP_BoardConfig::PX4_BOARD_PHMINI:1542#if AP_COMPASS_AK8963_ENABLED1543ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180));1544#endif1545break;15461547case AP_BoardConfig::PX4_BOARD_AUAV21:1548#if AP_COMPASS_AK8963_ENABLED1549ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90));1550#endif1551break;15521553case AP_BoardConfig::PX4_BOARD_PH2SLIM:1554#if AP_COMPASS_AK8963_ENABLED1555ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_YAW_270));1556#endif1557break;15581559case AP_BoardConfig::PX4_BOARD_MINDPXV2:1560#if AP_COMPASS_HMC5843_ENABLED1561ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR),1562false, ROTATION_YAW_90));1563#endif1564#if AP_COMPASS_LSM303D_ENABLED1565ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270));1566#endif1567break;15681569default:1570break;1571}1572#endif1573}15741575#if AP_COMPASS_DRONECAN_ENABLED1576/*1577look for DroneCAN compasses1578*/1579void Compass::probe_dronecan_compasses(void)1580{1581if (!_driver_enabled(DRIVER_UAVCAN)) {1582return;1583}1584for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {1585AP_Compass_Backend* _uavcan_backend = AP_Compass_DroneCAN::probe(i);1586if (_uavcan_backend) {1587_add_backend(_uavcan_backend);1588}1589#if COMPASS_MAX_UNREG_DEV > 01590if (_unreg_compass_count == COMPASS_MAX_UNREG_DEV) {1591break;1592}1593#endif1594}15951596#if COMPASS_MAX_UNREG_DEV > 01597if (option_set(Option::ALLOW_DRONECAN_AUTO_REPLACEMENT) && !suppress_devid_save) {1598// check if there's any uavcan compass in prio slot that's not found1599// and replace it if there's a replacement compass1600for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {1601if (AP_HAL::Device::devid_get_bus_type(_priority_did_list[i]) != AP_HAL::Device::BUS_TYPE_UAVCAN1602|| _get_state(i).registered) {1603continue;1604}1605// There's a UAVCAN compass missing1606// Let's check if there's a replacement1607for (uint8_t j=0; j<COMPASS_MAX_INSTANCES; j++) {1608uint32_t detected_devid = AP_Compass_DroneCAN::get_detected_devid(j);1609// Check if this is a potential replacement mag1610if (!is_replacement_mag(detected_devid)) {1611continue;1612}1613// We have found a replacement mag, let's replace the existing one1614// with this by setting the priority to zero and calling uavcan probe1615GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Mag: Compass #%d with DEVID %lu replaced", uint8_t(i), (unsigned long)_priority_did_list[i]);1616_priority_did_stored_list[i].set_and_save(0);1617_priority_did_list[i] = 0;16181619AP_Compass_Backend* _uavcan_backend = AP_Compass_DroneCAN::probe(j);1620if (_uavcan_backend) {1621_add_backend(_uavcan_backend);1622// we also need to remove the id from unreg list1623remove_unreg_dev_id(detected_devid);1624} else {1625// the mag has already been allocated,1626// let's begin the replacement1627bool found_replacement = false;1628for (StateIndex k(0); k<COMPASS_MAX_INSTANCES; k++) {1629if ((uint32_t)_state[k].dev_id == detected_devid) {1630if (_state[k].priority <= uint8_t(i)) {1631// we are already on higher priority1632// nothing to do1633break;1634}1635found_replacement = true;1636// reset old priority of replacement mag1637_priority_did_stored_list[_state[k].priority].set_and_save(0);1638_priority_did_list[_state[k].priority] = 0;1639// update new priority1640_state[k].priority = i;1641}1642}1643if (!found_replacement) {1644continue;1645}1646_priority_did_stored_list[i].set_and_save(detected_devid);1647_priority_did_list[i] = detected_devid;1648}1649}1650}1651}1652#endif // #if COMPASS_MAX_UNREG_DEV > 01653}1654#endif // AP_COMPASS_DRONECAN_ENABLED165516561657// Check if the devid is a potential replacement compass1658// Following are the checks done to ensure the compass is a replacement1659// * The compass is an UAVCAN compass1660// * The compass wasn't seen before this boot as additional unreg mag1661// * The compass might have been seen before but never setup1662bool Compass::is_replacement_mag(uint32_t devid) {1663#if COMPASS_MAX_INSTANCES > 11664// We only do this for UAVCAN mag1665if (devid == 0 || (AP_HAL::Device::devid_get_bus_type(devid) != AP_HAL::Device::BUS_TYPE_UAVCAN)) {1666return false;1667}16681669#if COMPASS_MAX_UNREG_DEV > 01670// Check that its not an unused additional mag1671for (uint8_t i = 0; i<COMPASS_MAX_UNREG_DEV; i++) {1672if (_previously_unreg_mag[i] == devid) {1673return false;1674}1675}1676#endif16771678// Check that its not previously setup mag1679for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {1680if ((uint32_t)_state[i].expected_dev_id == devid) {1681return false;1682}1683}1684#endif1685return true;1686}16871688void Compass::remove_unreg_dev_id(uint32_t devid)1689{1690#if COMPASS_MAX_INSTANCES > 11691// We only do this for UAVCAN mag1692if (devid == 0 || (AP_HAL::Device::devid_get_bus_type(devid) != AP_HAL::Device::BUS_TYPE_UAVCAN)) {1693return;1694}16951696#if COMPASS_MAX_UNREG_DEV > 01697for (uint8_t i = 0; i<COMPASS_MAX_UNREG_DEV; i++) {1698if ((uint32_t)extra_dev_id[i] == devid) {1699extra_dev_id[i].set(0);1700return;1701}1702}1703#endif1704#endif1705}17061707void Compass::_reset_compass_id()1708{1709#if COMPASS_MAX_INSTANCES > 11710// Check if any of the registered devs are not registered1711for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {1712if (_priority_did_stored_list[i] != _priority_did_list[i] ||1713_priority_did_stored_list[i] == 0) {1714//We don't touch priorities that might have been touched by the user1715continue;1716}1717if (!_get_state(i).registered) {1718_priority_did_stored_list[i].set_and_save(0);1719GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Mag: Compass #%d with DEVID %lu removed", uint8_t(i), (unsigned long)_priority_did_list[i]);1720}1721}17221723// Check if any of the old registered devs are not registered1724// and hence can be removed1725for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {1726if (_state[i].dev_id == 0 && _state[i].expected_dev_id != 0) {1727// also hard reset dev_ids that are not detected1728_state[i].dev_id.save();1729}1730}1731#endif1732}17331734// Look for devices beyond initialisation1735void1736Compass::_detect_runtime(void)1737{1738#if AP_COMPASS_DRONECAN_ENABLED1739if (!available()) {1740return;1741}17421743//Don't try to add device while armed1744if (hal.util->get_soft_armed()) {1745return;1746}1747static uint32_t last_try;1748//Try once every second1749if ((AP_HAL::millis() - last_try) < 1000) {1750return;1751}1752last_try = AP_HAL::millis();1753if (_driver_enabled(DRIVER_UAVCAN)) {1754for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {1755AP_Compass_Backend* _uavcan_backend = AP_Compass_DroneCAN::probe(i);1756if (_uavcan_backend) {1757_add_backend(_uavcan_backend);1758}1759CHECK_UNREG_LIMIT_RETURN;1760}1761}1762#endif // AP_COMPASS_DRONECAN_ENABLED1763}17641765bool1766Compass::read(void)1767{1768if (!available()) {1769return false;1770}17711772#if HAL_LOGGING_ENABLED1773const bool old_healthy = healthy();1774#endif17751776#ifndef HAL_BUILD_AP_PERIPH1777if (!_initial_location_set) {1778try_set_initial_location();1779}1780#endif17811782_detect_runtime();17831784for (uint8_t i=0; i< _backend_count; i++) {1785// call read on each of the backend. This call updates field[i]1786_backends[i]->read();1787}1788uint32_t time = AP_HAL::millis();1789bool any_healthy = false;1790for (StateIndex i(0); i < COMPASS_MAX_INSTANCES; i++) {1791_state[i].healthy = (time - _state[i].last_update_ms < 500);1792any_healthy |= _state[i].healthy;1793}1794#if COMPASS_LEARN_ENABLED1795if (_learn == LEARN_INFLIGHT && !learn_allocated) {1796learn_allocated = true;1797learn = NEW_NOTHROW CompassLearn(*this);1798}1799if (_learn == LEARN_INFLIGHT && learn != nullptr) {1800learn->update();1801}1802#endif1803#if HAL_LOGGING_ENABLED1804if (any_healthy && _log_bit != (uint32_t)-1 && AP::logger().should_log(_log_bit)) {1805AP::logger().Write_Compass();1806}1807#endif18081809// Set _first_usable parameter1810for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {1811if (_use_for_yaw[i]) {1812_first_usable = uint8_t(i);1813break;1814}1815}1816const bool new_healthy = healthy();18171818#if HAL_LOGGING_ENABLED18191820#define MASK_LOG_ANY 0xFFFF18211822if (new_healthy != old_healthy) {1823if (AP::logger().should_log(MASK_LOG_ANY)) {1824const LogErrorCode code = new_healthy ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY;1825AP::logger().Write_Error(LogErrorSubsystem::COMPASS, code);1826}1827}1828#endif18291830return new_healthy;1831}18321833uint8_t1834Compass::get_healthy_mask() const1835{1836uint8_t healthy_mask = 0;1837for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {1838if (healthy(uint8_t(i))) {1839healthy_mask |= 1 << uint8_t(i);1840}1841}1842return healthy_mask;1843}18441845void1846Compass::set_offsets(uint8_t i, const Vector3f &offsets)1847{1848// sanity check compass instance provided1849StateIndex id = _get_state_id(Priority(i));1850if (id < COMPASS_MAX_INSTANCES) {1851_state[id].offset.set(offsets);1852}1853}18541855void1856Compass::set_and_save_offsets(uint8_t i, const Vector3f &offsets)1857{1858// sanity check compass instance provided1859StateIndex id = _get_state_id(Priority(i));1860if (id < COMPASS_MAX_INSTANCES) {1861_state[id].offset.set(offsets);1862save_offsets(i);1863}1864}18651866#if AP_COMPASS_DIAGONALS_ENABLED1867void1868Compass::set_and_save_diagonals(uint8_t i, const Vector3f &diagonals)1869{1870// sanity check compass instance provided1871StateIndex id = _get_state_id(Priority(i));1872if (id < COMPASS_MAX_INSTANCES) {1873_state[id].diagonals.set_and_save(diagonals);1874}1875}18761877void1878Compass::set_and_save_offdiagonals(uint8_t i, const Vector3f &offdiagonals)1879{1880// sanity check compass instance provided1881StateIndex id = _get_state_id(Priority(i));1882if (id < COMPASS_MAX_INSTANCES) {1883_state[id].offdiagonals.set_and_save(offdiagonals);1884}1885}1886#endif // AP_COMPASS_DIAGONALS_ENABLED18871888void1889Compass::set_and_save_scale_factor(uint8_t i, float scale_factor)1890{1891StateIndex id = _get_state_id(Priority(i));1892if (i < COMPASS_MAX_INSTANCES) {1893_state[id].scale_factor.set_and_save(scale_factor);1894}1895}18961897void1898Compass::save_offsets(uint8_t i)1899{1900StateIndex id = _get_state_id(Priority(i));1901if (id < COMPASS_MAX_INSTANCES) {1902_state[id].offset.save(); // save offsets1903_state[id].dev_id.set_and_save(_state[id].detected_dev_id);1904}1905}19061907void1908Compass::set_and_save_orientation(uint8_t i, Rotation orientation)1909{1910StateIndex id = _get_state_id(Priority(i));1911if (id < COMPASS_MAX_INSTANCES) {1912_state[id].orientation.set_and_save_ifchanged(orientation);1913}1914}19151916void1917Compass::save_offsets(void)1918{1919for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {1920save_offsets(uint8_t(i));1921}1922}19231924void1925Compass::set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor)1926{1927StateIndex id = _get_state_id(Priority(i));1928if (id < COMPASS_MAX_INSTANCES) {1929_state[id].motor_compensation.set(motor_comp_factor);1930}1931}19321933void1934Compass::save_motor_compensation()1935{1936StateIndex id;1937_motor_comp_type.save();1938for (Priority k(0); k<COMPASS_MAX_INSTANCES; k++) {1939id = _get_state_id(k);1940if (id<COMPASS_MAX_INSTANCES) {1941_state[id].motor_compensation.save();1942}1943}1944}19451946void Compass::try_set_initial_location()1947{1948if (!_auto_declination) {1949return;1950}1951if (!_enabled) {1952return;1953}19541955Location loc;1956if (!AP::ahrs().get_location(loc)) {1957return;1958}1959_initial_location_set = true;19601961// if automatic declination is configured, then compute1962// the declination based on the initial GPS fix1963// Set the declination based on the lat/lng from GPS1964_declination.set(radians(1965AP_Declination::get_declination(1966(float)loc.lat / 10000000,1967(float)loc.lng / 10000000)));1968}19691970/// return true if the compass should be used for yaw calculations1971bool1972Compass::use_for_yaw(void) const1973{1974return healthy(_first_usable) && use_for_yaw(_first_usable);1975}19761977/// return true if the specified compass can be used for yaw calculations1978bool1979Compass::use_for_yaw(uint8_t i) const1980{1981if (!available()) {1982return false;1983}1984// when we are doing in-flight compass learning the state1985// estimator must not use the compass. The learning code turns off1986// inflight learning when it has converged1987return _use_for_yaw[Priority(i)] && _learn.get() != LEARN_INFLIGHT;1988}19891990/*1991return the number of enabled sensors. Used to determine if1992non-compass operation is desired1993*/1994uint8_t Compass::get_num_enabled(void) const1995{1996if (get_count() == 0) {1997return 0;1998}1999uint8_t count = 0;2000for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {2001if (use_for_yaw(i)) {2002count++;2003}2004}2005return count;2006}20072008void2009Compass::set_declination(float radians, bool save_to_eeprom)2010{2011if (save_to_eeprom) {2012_declination.set_and_save(radians);2013} else {2014_declination.set(radians);2015}2016}20172018float2019Compass::get_declination() const2020{2021return _declination.get();2022}20232024/*2025calculate a compass heading given the attitude from DCM and the mag vector2026*/2027float2028Compass::calculate_heading(const Matrix3f &dcm_matrix, uint8_t i) const2029{2030/*2031This extracts a roll/pitch-only rotation which is then used to rotate the body frame field into earth frame so the heading can be calculated.2032One could do:2033float roll, pitch, yaw;2034dcm_matrix.to_euler(roll, pitch, yaw)2035Matrix3f rp_rot;2036rp_rot.from_euler(roll, pitch, 0)2037Vector3f ef = rp_rot * field20382039Because only the X and Y components are needed it's more efficient to manually calculate:20402041rp_rot = [ cos(pitch), sin(roll) * sin(pitch), cos(roll) * sin(pitch)20420, cos(roll), -sin(roll)]20432044If the whole matrix is multiplied by cos(pitch) the required trigonometric values can be extracted directly from the existing dcm matrix.2045This multiplication has no effect on the calculated heading as it changes the length of the North/East vector but not its angle.20462047rp_rot = [ cos(pitch)^2, sin(roll) * sin(pitch) * cos(pitch), cos(roll) * sin(pitch) * cos(pitch)20480, cos(roll) * cos(pitch), -sin(roll) * cos(pitch)]20492050Preexisting values can be substituted in:20512052dcm_matrix.c.x = -sin(pitch)2053dcm_matrix.c.y = sin(roll) * cos(pitch)2054dcm_matrix.c.z = cos(roll) * cos(pitch)20552056rp_rot = [ cos(pitch)^2, dcm_matrix.c.y * -dcm_matrix.c.x, dcm_matrix.c.z * -dcm_matrix.c.x20570, dcm_matrix.c.z, -dcm_matrix.c.y]20582059cos(pitch)^2 is stil needed. This is the same as 1 - sin(pitch)^2.2060sin(pitch) is avalable as dcm_matrix.c.x2061*/20622063const float cos_pitch_sq = 1.0f-(dcm_matrix.c.x*dcm_matrix.c.x);20642065// Tilt compensated magnetic field Y component:2066const Vector3f &field = get_field(i);20672068const float headY = field.y * dcm_matrix.c.z - field.z * dcm_matrix.c.y;20692070// Tilt compensated magnetic field X component:2071const float headX = field.x * cos_pitch_sq - dcm_matrix.c.x * (field.y * dcm_matrix.c.y + field.z * dcm_matrix.c.z);20722073// magnetic heading2074// 6/4/11 - added constrain to keep bad values from ruining DCM Yaw - Jason S.2075const float heading = constrain_float(atan2f(-headY,headX), -M_PI, M_PI);20762077// Declination correction2078return wrap_PI(heading + _declination);2079}20802081/// Returns True if the compasses have been configured (i.e. offsets saved)2082///2083/// @returns True if compass has been configured2084///2085bool Compass::configured(uint8_t i)2086{2087// exit immediately if instance is beyond the number of compasses we have available2088if (i > get_count()) {2089return false;2090}20912092// exit immediately if all offsets are zero2093if (is_zero(get_offsets(i).length())) {2094return false;2095}20962097StateIndex id = _get_state_id(Priority(i));2098// exit immediately if dev_id hasn't been detected2099if (_state[id].detected_dev_id == 0 ||2100id == COMPASS_MAX_INSTANCES) {2101return false;2102}21032104#ifdef HAL_USE_EMPTY_STORAGE2105// the load() call below returns zeroes on empty storage, so the2106// check-stored-value check here will always fail. Since nobody2107// really cares about the empty-storage case, shortcut out here2108// for simplicity.2109return true;2110#endif21112112// back up cached value of dev_id2113int32_t dev_id_cache_value = _state[id].dev_id;21142115// load dev_id from eeprom2116_state[id].dev_id.load();21172118// if dev_id loaded from eeprom is different from detected dev id or dev_id loaded from eeprom is different from cached dev_id, compass is unconfigured2119if (_state[id].dev_id != _state[id].detected_dev_id || _state[id].dev_id != dev_id_cache_value) {2120// restore cached value2121_state[id].dev_id.set(dev_id_cache_value);2122// return failure2123return false;2124}21252126// if we got here then it must be configured2127return true;2128}21292130bool Compass::configured(char *failure_msg, uint8_t failure_msg_len)2131{2132#if COMPASS_MAX_INSTANCES > 12133// Check if any of the registered devs are not registered2134for (Priority i(0); i<COMPASS_MAX_INSTANCES; i++) {2135if (_priority_did_list[i] != 0 && use_for_yaw(uint8_t(i))) {2136if (!_get_state(i).registered) {2137snprintf(failure_msg, failure_msg_len, "Compass %d not found", uint8_t(i + 1));2138return false;2139}2140if (_priority_did_list[i] != _priority_did_stored_list[i]) {2141snprintf(failure_msg, failure_msg_len, "Compass order change requires reboot");2142return false;2143}2144}2145}2146#endif21472148bool all_configured = true;2149for (uint8_t i=0; i<get_count(); i++) {2150if (configured(i)) {2151continue;2152}2153if (!use_for_yaw(i)) {2154// we're not planning on using this anyway so sure,2155// whatever, it's configured....2156continue;2157}2158all_configured = false;2159break;2160}2161if (!all_configured) {2162snprintf(failure_msg, failure_msg_len, "Compass not calibrated");2163}2164return all_configured;2165}21662167/*2168set the type of motor compensation to use2169*/2170void Compass::motor_compensation_type(const uint8_t comp_type)2171{2172if (_motor_comp_type <= AP_COMPASS_MOT_COMP_CURRENT && _motor_comp_type != (int8_t)comp_type) {2173_motor_comp_type.set((int8_t)comp_type);2174_thr = 0; // set current throttle to zero2175for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {2176set_motor_compensation(i, Vector3f(0,0,0)); // clear out invalid compensation vectors2177}2178}2179}21802181bool Compass::consistent() const2182{2183const Vector3f &primary_mag_field { get_field() };2184const Vector2f &primary_mag_field_xy { primary_mag_field.xy() };21852186for (uint8_t i=0; i<get_count(); i++) {2187if (!use_for_yaw(i)) {2188// configured not-to-be-used2189continue;2190}21912192const Vector3f &mag_field = get_field(i);2193const Vector2f &mag_field_xy = mag_field.xy();21942195if (mag_field_xy.is_zero()) {2196return false;2197}21982199// check for gross misalignment on all axes2200const float xyz_ang_diff = mag_field.angle(primary_mag_field);2201if (xyz_ang_diff > AP_COMPASS_MAX_XYZ_ANG_DIFF) {2202return false;2203}22042205// check for an unacceptable angle difference on the xy plane2206const float xy_ang_diff = mag_field_xy.angle(primary_mag_field_xy);2207if (xy_ang_diff > AP_COMPASS_MAX_XY_ANG_DIFF) {2208return false;2209}22102211// check for an unacceptable length difference on the xy plane2212const float xy_len_diff = (primary_mag_field_xy-mag_field_xy).length();2213if (xy_len_diff > AP_COMPASS_MAX_XY_LENGTH_DIFF) {2214return false;2215}2216}2217return true;2218}22192220bool Compass::healthy(uint8_t i) const2221{2222return (i < COMPASS_MAX_INSTANCES) ? _get_state(Priority(i)).healthy : false;2223}22242225/*2226return true if we have a valid scale factor2227*/2228bool Compass::have_scale_factor(uint8_t i) const2229{2230if (!available()) {2231return false;2232}2233StateIndex id = _get_state_id(Priority(i));2234if (id >= COMPASS_MAX_INSTANCES ||2235_state[id].scale_factor < COMPASS_MIN_SCALE_FACTOR ||2236_state[id].scale_factor > COMPASS_MAX_SCALE_FACTOR) {2237return false;2238}2239return true;2240}22412242#if AP_COMPASS_MSP_ENABLED2243void Compass::handle_msp(const MSP::msp_compass_data_message_t &pkt)2244{2245if (!_driver_enabled(DRIVER_MSP)) {2246return;2247}2248if (!init_done) {2249if (pkt.instance < 8) {2250msp_instance_mask |= 1U<<pkt.instance;2251}2252} else {2253for (uint8_t i=0; i<_backend_count; i++) {2254_backends[i]->handle_msp(pkt);2255}2256}2257}2258#endif // AP_COMPASS_MSP_ENABLED22592260#if AP_COMPASS_EXTERNALAHRS_ENABLED2261void Compass::handle_external(const AP_ExternalAHRS::mag_data_message_t &pkt)2262{2263if (!_driver_enabled(DRIVER_EXTERNALAHRS)) {2264return;2265}2266for (uint8_t i=0; i<_backend_count; i++) {2267_backends[i]->handle_external(pkt);2268}2269}2270#endif // AP_COMPASS_EXTERNALAHRS_ENABLED22712272// force save of current calibration as valid2273void Compass::force_save_calibration(void)2274{2275for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {2276if (_state[i].dev_id != 0) {2277_state[i].dev_id.save();2278}2279}2280}22812282// singleton instance2283Compass *Compass::_singleton;22842285namespace AP2286{22872288Compass &compass()2289{2290return *Compass::get_singleton();2291}22922293}22942295#endif // AP_COMPASS_ENABLED229622972298