#include #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include #endif #include #include #include #include #include #include #include #include "AP_Compass_config.h" #include "AP_Compass_SITL.h" #include "AP_Compass_AK8963.h" #include "AP_Compass_Backend.h" #include "AP_Compass_BMM150.h" #include "AP_Compass_HMC5843.h" #include "AP_Compass_IST8308.h" #include "AP_Compass_IST8310.h" #include "AP_Compass_LSM303D.h" #include "AP_Compass_LSM9DS1.h" #include "AP_Compass_LIS3MDL.h" #include "AP_Compass_AK09916.h" #include "AP_Compass_QMC5883L.h" #if AP_COMPASS_DRONECAN_ENABLED #include "AP_Compass_DroneCAN.h" #endif #include "AP_Compass_QMC5883P.h" #include "AP_Compass_MMC3416.h" #include "AP_Compass_MMC5xx3.h" #include "AP_Compass_MAG3110.h" #include "AP_Compass_RM3100.h" #if AP_COMPASS_MSP_ENABLED #include "AP_Compass_MSP.h" #endif #if AP_COMPASS_EXTERNALAHRS_ENABLED #include "AP_Compass_ExternalAHRS.h" #endif #include "AP_Compass.h" #include "Compass_learn.h" #include extern const AP_HAL::HAL& hal; #ifndef AP_COMPASS_ENABLE_DEFAULT #define AP_COMPASS_ENABLE_DEFAULT 1 #endif #ifndef COMPASS_LEARN_DEFAULT #define COMPASS_LEARN_DEFAULT Compass::LEARN_NONE #endif #ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT #define AP_COMPASS_OFFSETS_MAX_DEFAULT 1800 #endif #ifndef HAL_COMPASS_FILTER_DEFAULT #define HAL_COMPASS_FILTER_DEFAULT 0 // turned off by default #endif #ifndef HAL_COMPASS_AUTO_ROT_DEFAULT #define HAL_COMPASS_AUTO_ROT_DEFAULT 2 #endif const AP_Param::GroupInfo Compass::var_info[] = { // index 0 was used for the old orientation matrix #ifndef HAL_BUILD_AP_PERIPH // @Param: OFS_X // @DisplayName: Compass offsets in milligauss on the X axis // @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame // @Range: -400 400 // @Units: mGauss // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: OFS_Y // @DisplayName: Compass offsets in milligauss on the Y axis // @Description: Offset to be added to the compass y-axis values to compensate for metal in the frame // @Range: -400 400 // @Units: mGauss // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: OFS_Z // @DisplayName: Compass offsets in milligauss on the Z axis // @Description: Offset to be added to the compass z-axis values to compensate for metal in the frame // @Range: -400 400 // @Units: mGauss // @Increment: 1 // @User: Advanced AP_GROUPINFO("OFS", 1, Compass, _state._priv_instance[0].offset, 0), // @Param: DEC // @DisplayName: Compass declination // @Description: An angle to compensate between the true north and magnetic north // @Range: -3.142 3.142 // @Units: rad // @Increment: 0.01 // @User: Standard AP_GROUPINFO("DEC", 2, Compass, _declination, 0), #endif // HAL_BUILD_AP_PERIPH #if COMPASS_LEARN_ENABLED // @Param: LEARN // @DisplayName: Learn compass offsets automatically // @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. // @Values: 0:Disabled,1:Internal-Learning,2:EKF-Learning,3:InFlight-Learning // @User: Advanced AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT), #endif #ifndef HAL_BUILD_AP_PERIPH // @Param: USE // @DisplayName: Use compass for yaw // @Description: Enable or disable the use of the compass (instead of the GPS) for determining heading // @Values: 0:Disabled,1:Enabled // @User: Advanced AP_GROUPINFO("USE", 4, Compass, _use_for_yaw._priv_instance[0], 1), // true if used for DCM yaw // @Param: AUTODEC // @DisplayName: Auto Declination // @Description: Enable or disable the automatic calculation of the declination based on gps location // @Values: 0:Disabled,1:Enabled // @User: Advanced AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1), #endif #if COMPASS_MOT_ENABLED // @Param: MOTCT // @DisplayName: Motor interference compensation type // @Description: Set motor interference compensation type to disabled, throttle or current. Do not change manually. // @Values: 0:Disabled,1:Use Throttle,2:Use Current // @User: Advanced // @Calibration: 1 AP_GROUPINFO("MOTCT", 6, Compass, _motor_comp_type, AP_COMPASS_MOT_COMP_DISABLED), // @Param: MOT_X // @DisplayName: Motor interference compensation for body frame X axis // @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) // @Range: -1000 1000 // @Units: mGauss/A // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: MOT_Y // @DisplayName: Motor interference compensation for body frame Y axis // @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) // @Range: -1000 1000 // @Units: mGauss/A // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: MOT_Z // @DisplayName: Motor interference compensation for body frame Z axis // @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) // @Range: -1000 1000 // @Units: mGauss/A // @Increment: 1 // @User: Advanced AP_GROUPINFO("MOT", 7, Compass, _state._priv_instance[0].motor_compensation, 0), #endif #ifndef HAL_BUILD_AP_PERIPH // @Param: ORIENT // @DisplayName: Compass orientation // @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. // @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 2 // @User: Advanced AP_GROUPINFO("ORIENT", 8, Compass, _state._priv_instance[0].orientation, ROTATION_NONE), // @Param: EXTERNAL // @DisplayName: Compass is attached via an external cable // @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. // @Values: 0:Internal,1:External,2:ForcedExternal // @User: Advanced AP_GROUPINFO("EXTERNAL", 9, Compass, _state._priv_instance[0].external, 0), #endif #if COMPASS_MAX_INSTANCES > 1 // @Param: OFS2_X // @DisplayName: Compass2 offsets in milligauss on the X axis // @Description: Offset to be added to compass2's x-axis values to compensate for metal in the frame // @Range: -400 400 // @Units: mGauss // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: OFS2_Y // @DisplayName: Compass2 offsets in milligauss on the Y axis // @Description: Offset to be added to compass2's y-axis values to compensate for metal in the frame // @Range: -400 400 // @Units: mGauss // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: OFS2_Z // @DisplayName: Compass2 offsets in milligauss on the Z axis // @Description: Offset to be added to compass2's z-axis values to compensate for metal in the frame // @Range: -400 400 // @Units: mGauss // @Increment: 1 // @User: Advanced AP_GROUPINFO("OFS2", 10, Compass, _state._priv_instance[1].offset, 0), // @Param: MOT2_X // @DisplayName: Motor interference compensation to compass2 for body frame X axis // @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) // @Range: -1000 1000 // @Units: mGauss/A // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: MOT2_Y // @DisplayName: Motor interference compensation to compass2 for body frame Y axis // @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) // @Range: -1000 1000 // @Units: mGauss/A // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: MOT2_Z // @DisplayName: Motor interference compensation to compass2 for body frame Z axis // @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) // @Range: -1000 1000 // @Units: mGauss/A // @Increment: 1 // @User: Advanced AP_GROUPINFO("MOT2", 11, Compass, _state._priv_instance[1].motor_compensation, 0), #endif // COMPASS_MAX_INSTANCES #if COMPASS_MAX_INSTANCES > 2 // @Param: OFS3_X // @DisplayName: Compass3 offsets in milligauss on the X axis // @Description: Offset to be added to compass3's x-axis values to compensate for metal in the frame // @Range: -400 400 // @Units: mGauss // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: OFS3_Y // @DisplayName: Compass3 offsets in milligauss on the Y axis // @Description: Offset to be added to compass3's y-axis values to compensate for metal in the frame // @Range: -400 400 // @Units: mGauss // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: OFS3_Z // @DisplayName: Compass3 offsets in milligauss on the Z axis // @Description: Offset to be added to compass3's z-axis values to compensate for metal in the frame // @Range: -400 400 // @Units: mGauss // @Increment: 1 // @User: Advanced AP_GROUPINFO("OFS3", 13, Compass, _state._priv_instance[2].offset, 0), // @Param: MOT3_X // @DisplayName: Motor interference compensation to compass3 for body frame X axis // @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) // @Range: -1000 1000 // @Units: mGauss/A // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: MOT3_Y // @DisplayName: Motor interference compensation to compass3 for body frame Y axis // @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) // @Range: -1000 1000 // @Units: mGauss/A // @Increment: 1 // @User: Advanced // @Calibration: 1 // @Param: MOT3_Z // @DisplayName: Motor interference compensation to compass3 for body frame Z axis // @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) // @Range: -1000 1000 // @Units: mGauss/A // @Increment: 1 // @User: Advanced AP_GROUPINFO("MOT3", 14, Compass, _state._priv_instance[2].motor_compensation, 0), #endif // COMPASS_MAX_INSTANCES // @Param: DEV_ID // @DisplayName: Compass device id // @Description: Compass device id. Automatically detected, do not set manually // @ReadOnly: True // @User: Advanced AP_GROUPINFO("DEV_ID", 15, Compass, _state._priv_instance[0].dev_id, 0), #if COMPASS_MAX_INSTANCES > 1 // @Param: DEV_ID2 // @DisplayName: Compass2 device id // @Description: Second compass's device id. Automatically detected, do not set manually // @ReadOnly: True // @User: Advanced AP_GROUPINFO("DEV_ID2", 16, Compass, _state._priv_instance[1].dev_id, 0), #endif // COMPASS_MAX_INSTANCES #if COMPASS_MAX_INSTANCES > 2 // @Param: DEV_ID3 // @DisplayName: Compass3 device id // @Description: Third compass's device id. Automatically detected, do not set manually // @ReadOnly: True // @User: Advanced AP_GROUPINFO("DEV_ID3", 17, Compass, _state._priv_instance[2].dev_id, 0), #endif // COMPASS_MAX_INSTANCES #if COMPASS_MAX_INSTANCES > 1 // @Param: USE2 // @DisplayName: Compass2 used for yaw // @Description: Enable or disable the secondary compass for determining heading. // @Values: 0:Disabled,1:Enabled // @User: Advanced AP_GROUPINFO("USE2", 18, Compass, _use_for_yaw._priv_instance[1], 1), // @Param: ORIENT2 // @DisplayName: Compass2 orientation // @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. // @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 2 // @User: Advanced AP_GROUPINFO("ORIENT2", 19, Compass, _state._priv_instance[1].orientation, ROTATION_NONE), // @Param: EXTERN2 // @DisplayName: Compass2 is attached via an external cable // @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. // @Values: 0:Internal,1:External,2:ForcedExternal // @User: Advanced AP_GROUPINFO("EXTERN2",20, Compass, _state._priv_instance[1].external, 0), #endif // COMPASS_MAX_INSTANCES #if COMPASS_MAX_INSTANCES > 2 // @Param: USE3 // @DisplayName: Compass3 used for yaw // @Description: Enable or disable the tertiary compass for determining heading. // @Values: 0:Disabled,1:Enabled // @User: Advanced AP_GROUPINFO("USE3", 21, Compass, _use_for_yaw._priv_instance[2], 1), // @Param: ORIENT3 // @DisplayName: Compass3 orientation // @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. // @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 2 // @User: Advanced AP_GROUPINFO("ORIENT3", 22, Compass, _state._priv_instance[2].orientation, ROTATION_NONE), // @Param: EXTERN3 // @DisplayName: Compass3 is attached via an external cable // @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. // @Values: 0:Internal,1:External,2:ForcedExternal // @User: Advanced AP_GROUPINFO("EXTERN3",23, Compass, _state._priv_instance[2].external, 0), #endif // COMPASS_MAX_INSTANCES #if AP_COMPASS_DIAGONALS_ENABLED // @Param: DIA_X // @DisplayName: Compass soft-iron diagonal X component // @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]] // @User: Advanced // @Calibration: 1 // @Param: DIA_Y // @DisplayName: Compass soft-iron diagonal Y component // @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]] // @User: Advanced // @Calibration: 1 // @Param: DIA_Z // @DisplayName: Compass soft-iron diagonal Z component // @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]] // @User: Advanced AP_GROUPINFO("DIA", 24, Compass, _state._priv_instance[0].diagonals, 1.0), // @Param: ODI_X // @DisplayName: Compass soft-iron off-diagonal X component // @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]] // @User: Advanced // @Calibration: 1 // @Param: ODI_Y // @DisplayName: Compass soft-iron off-diagonal Y component // @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]] // @User: Advanced // @Calibration: 1 // @Param: ODI_Z // @DisplayName: Compass soft-iron off-diagonal Z component // @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]] // @User: Advanced AP_GROUPINFO("ODI", 25, Compass, _state._priv_instance[0].offdiagonals, 0), #if COMPASS_MAX_INSTANCES > 1 // @Param: DIA2_X // @DisplayName: Compass2 soft-iron diagonal X component // @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]] // @User: Advanced // @Calibration: 1 // @Param: DIA2_Y // @DisplayName: Compass2 soft-iron diagonal Y component // @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]] // @User: Advanced // @Calibration: 1 // @Param: DIA2_Z // @DisplayName: Compass2 soft-iron diagonal Z component // @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]] // @User: Advanced AP_GROUPINFO("DIA2", 26, Compass, _state._priv_instance[1].diagonals, 1.0), // @Param: ODI2_X // @DisplayName: Compass2 soft-iron off-diagonal X component // @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]] // @User: Advanced // @Calibration: 1 // @Param: ODI2_Y // @DisplayName: Compass2 soft-iron off-diagonal Y component // @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]] // @User: Advanced // @Calibration: 1 // @Param: ODI2_Z // @DisplayName: Compass2 soft-iron off-diagonal Z component // @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]] // @User: Advanced AP_GROUPINFO("ODI2", 27, Compass, _state._priv_instance[1].offdiagonals, 0), #endif // COMPASS_MAX_INSTANCES #if COMPASS_MAX_INSTANCES > 2 // @Param: DIA3_X // @DisplayName: Compass3 soft-iron diagonal X component // @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]] // @User: Advanced // @Calibration: 1 // @Param: DIA3_Y // @DisplayName: Compass3 soft-iron diagonal Y component // @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]] // @User: Advanced // @Calibration: 1 // @Param: DIA3_Z // @DisplayName: Compass3 soft-iron diagonal Z component // @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]] // @User: Advanced AP_GROUPINFO("DIA3", 28, Compass, _state._priv_instance[2].diagonals, 1.0), // @Param: ODI3_X // @DisplayName: Compass3 soft-iron off-diagonal X component // @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]] // @User: Advanced // @Calibration: 1 // @Param: ODI3_Y // @DisplayName: Compass3 soft-iron off-diagonal Y component // @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]] // @User: Advanced // @Calibration: 1 // @Param: ODI3_Z // @DisplayName: Compass3 soft-iron off-diagonal Z component // @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]] // @User: Advanced AP_GROUPINFO("ODI3", 29, Compass, _state._priv_instance[2].offdiagonals, 0), #endif // COMPASS_MAX_INSTANCES #endif // AP_COMPASS_DIAGONALS_ENABLED #if COMPASS_CAL_ENABLED // @Param: CAL_FIT // @DisplayName: Compass calibration fitness // @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. // @Range: 4 32 // @Values: 4:Very Strict,8:Strict,16:Default,32:Relaxed // @Increment: 0.1 // @User: Advanced AP_GROUPINFO("CAL_FIT", 30, Compass, _calibration_threshold, AP_COMPASS_CALIBRATION_FITNESS_DEFAULT), #endif #ifndef HAL_BUILD_AP_PERIPH // @Param: OFFS_MAX // @DisplayName: Compass maximum offset // @Description: This sets the maximum allowed compass offset in calibration and arming checks // @Range: 500 3000 // @Increment: 1 // @User: Advanced AP_GROUPINFO("OFFS_MAX", 31, Compass, _offset_max, AP_COMPASS_OFFSETS_MAX_DEFAULT), #endif #if COMPASS_MOT_ENABLED // @Group: PMOT // @Path: Compass_PerMotor.cpp AP_SUBGROUPINFO(_per_motor, "PMOT", 32, Compass, Compass_PerMotor), #endif // @Param: DISBLMSK // @DisplayName: Compass disable driver type mask // @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 startup // @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 // @User: Advanced AP_GROUPINFO("DISBLMSK", 33, Compass, _driver_type_mask, 0), // @Param: FLTR_RNG // @DisplayName: Range in which sample is accepted // @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. // @Units: % // @Range: 0 100 // @Increment: 1 AP_GROUPINFO("FLTR_RNG", 34, Compass, _filter_range, HAL_COMPASS_FILTER_DEFAULT), #if COMPASS_CAL_ENABLED // @Param: AUTO_ROT // @DisplayName: Automatically check orientation // @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. // @Values: 0:Disabled,1:CheckOnly,2:CheckAndFix,3:use same tolerance to auto rotate 45 deg rotations AP_GROUPINFO("AUTO_ROT", 35, Compass, _rotate_auto, HAL_COMPASS_AUTO_ROT_DEFAULT), #endif #if COMPASS_MAX_INSTANCES > 1 // @Param: PRIO1_ID // @DisplayName: Compass device id with 1st order priority // @Description: Compass device id with 1st order priority, set automatically if 0. Reboot required after change. // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PRIO1_ID", 36, Compass, _priority_did_stored_list._priv_instance[0], 0), // @Param: PRIO2_ID // @DisplayName: Compass device id with 2nd order priority // @Description: Compass device id with 2nd order priority, set automatically if 0. Reboot required after change. // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PRIO2_ID", 37, Compass, _priority_did_stored_list._priv_instance[1], 0), #endif // COMPASS_MAX_INSTANCES #if COMPASS_MAX_INSTANCES > 2 // @Param: PRIO3_ID // @DisplayName: Compass device id with 3rd order priority // @Description: Compass device id with 3rd order priority, set automatically if 0. Reboot required after change. // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PRIO3_ID", 38, Compass, _priority_did_stored_list._priv_instance[2], 0), #endif // COMPASS_MAX_INSTANCES // @Param: ENABLE // @DisplayName: Enable Compass // @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. // @User: Standard // @RebootRequired: True // @Values: 0:Disabled,1:Enabled AP_GROUPINFO("ENABLE", 39, Compass, _enabled, AP_COMPASS_ENABLE_DEFAULT), #ifndef HAL_BUILD_AP_PERIPH // @Param: SCALE // @DisplayName: Compass1 scale factor // @Description: Scaling factor for first compass to compensate for sensor scaling errors. If this is 0 then no scaling is done // @User: Standard // @Range: 0 1.3 AP_GROUPINFO("SCALE", 40, Compass, _state._priv_instance[0].scale_factor, 0), #if COMPASS_MAX_INSTANCES > 1 // @Param: SCALE2 // @DisplayName: Compass2 scale factor // @Description: Scaling factor for 2nd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done // @User: Standard // @Range: 0 1.3 AP_GROUPINFO("SCALE2", 41, Compass, _state._priv_instance[1].scale_factor, 0), #endif #if COMPASS_MAX_INSTANCES > 2 // @Param: SCALE3 // @DisplayName: Compass3 scale factor // @Description: Scaling factor for 3rd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done // @User: Standard // @Range: 0 1.3 AP_GROUPINFO("SCALE3", 42, Compass, _state._priv_instance[2].scale_factor, 0), #endif #endif // HAL_BUILD_AP_PERIPH #ifndef HAL_BUILD_AP_PERIPH // @Param: OPTIONS // @DisplayName: Compass options // @Description: This sets options to change the behaviour of the compass // @Bitmask: 0:CalRequireGPS // @Bitmask: 1: Allow missing DroneCAN compasses to be automaticaly replaced (calibration still required) // @User: Advanced AP_GROUPINFO("OPTIONS", 43, Compass, _options, 0), #endif #if COMPASS_MAX_UNREG_DEV > 0 // @Param: DEV_ID4 // @DisplayName: Compass4 device id // @Description: Extra 4th compass's device id. Automatically detected, do not set manually // @ReadOnly: True // @User: Advanced AP_GROUPINFO("DEV_ID4", 44, Compass, extra_dev_id[0], 0), #endif // COMPASS_MAX_UNREG_DEV #if COMPASS_MAX_UNREG_DEV > 1 // @Param: DEV_ID5 // @DisplayName: Compass5 device id // @Description: Extra 5th compass's device id. Automatically detected, do not set manually // @ReadOnly: True // @User: Advanced AP_GROUPINFO("DEV_ID5", 45, Compass, extra_dev_id[1], 0), #endif // COMPASS_MAX_UNREG_DEV #if COMPASS_MAX_UNREG_DEV > 2 // @Param: DEV_ID6 // @DisplayName: Compass6 device id // @Description: Extra 6th compass's device id. Automatically detected, do not set manually // @ReadOnly: True // @User: Advanced AP_GROUPINFO("DEV_ID6", 46, Compass, extra_dev_id[2], 0), #endif // COMPASS_MAX_UNREG_DEV #if COMPASS_MAX_UNREG_DEV > 3 // @Param: DEV_ID7 // @DisplayName: Compass7 device id // @Description: Extra 7th compass's device id. Automatically detected, do not set manually // @ReadOnly: True // @User: Advanced AP_GROUPINFO("DEV_ID7", 47, Compass, extra_dev_id[3], 0), #endif // COMPASS_MAX_UNREG_DEV #if COMPASS_MAX_UNREG_DEV > 4 // @Param: DEV_ID8 // @DisplayName: Compass8 device id // @Description: Extra 8th compass's device id. Automatically detected, do not set manually // @ReadOnly: True // @User: Advanced AP_GROUPINFO("DEV_ID8", 48, Compass, extra_dev_id[4], 0), #endif // COMPASS_MAX_UNREG_DEV // @Param: CUS_ROLL // @DisplayName: Custom orientation roll offset // @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. // @Range: -180 180 // @Units: deg // @Increment: 1 // @RebootRequired: True // @User: Advanced // index 49 // @Param: CUS_PIT // @DisplayName: Custom orientation pitch offset // @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. // @Range: -180 180 // @Units: deg // @Increment: 1 // @RebootRequired: True // @User: Advanced // index 50 // @Param: CUS_YAW // @DisplayName: Custom orientation yaw offset // @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. // @Range: -180 180 // @Units: deg // @Increment: 1 // @RebootRequired: True // @User: Advanced // index 51 AP_GROUPEND }; // Default constructor. // Note that the Vector/Matrix constructors already implicitly zero // their values. // Compass::Compass(void) { if (_singleton != nullptr) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL AP_HAL::panic("Compass must be singleton"); #endif return; } _singleton = this; AP_Param::setup_object_defaults(this, var_info); } // Default init method // void Compass::init() { if (!_enabled) { return; } /* on init() if any devid is set then we set suppress_devid_save to false. This is used to determine if we save device ids during the init process. */ suppress_devid_save = true; for (uint8_t i=0; i 1 if (_priority_did_stored_list._priv_instance[i] != 0) { suppress_devid_save = false; break; } #endif } // convert to new custom rotation method // PARAMETER_CONVERSION - Added: Nov-2021 #if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) for (StateIndex i(0); i 1 // Look if there was a primary compass setup in previous version // if so and the primary compass is not set in current setup // make the devid as primary. if (_priority_did_stored_list[Priority(0)] == 0) { uint16_t k_param_compass; if (AP_Param::find_top_level_key_by_pointer(this, k_param_compass)) { const AP_Param::ConversionInfo primary_compass_old_param = {k_param_compass, 12, AP_PARAM_INT8, ""}; AP_Int8 value; value.set(0); bool primary_param_exists = AP_Param::find_old_parameter(&primary_compass_old_param, &value); int8_t oldvalue = value.get(); if ((oldvalue!=0) && (oldvalue 1 // This method calls set_and_save_ifchanged on parameters // which are set() but not saved() during normal runtime, // do not move this call without ensuring that is not happening // read comments under set_and_save_ifchanged for details if (!suppress_devid_save) { _reorder_compass_params(); } #endif if (_compass_count == 0) { // detect available backends. Only called once _detect_backends(); } if (_compass_count != 0) { // get initial health status hal.scheduler->delay(100); read(); } // set the dev_id to 0 for undetected compasses, to make it easier // for users to see how many compasses are detected. We don't do a // set_and_save() as the user may have temporarily removed the // compass, and we don't want to force a re-cal if they plug it // back in again for (StateIndex i(0); i 1 || COMPASS_MAX_UNREG_DEV // Update Priority List for Mags, by default, we just // load them as they come up the first time Compass::Priority Compass::_update_priority_list(int32_t dev_id) { // Check if already in priority list for (Priority i(0); i= _compass_count) { _compass_count = uint8_t(i)+1; } return i; } } // We are not in priority list, let's add at first empty for (Priority i(0); i= _compass_count) { _compass_count = uint8_t(i)+1; } return i; } } return Priority(COMPASS_MAX_INSTANCES); } #endif #if COMPASS_MAX_INSTANCES > 1 // This method reorganises devid list to match // priority list, only call before detection at boot void Compass::_reorder_compass_params() { mag_state swap_state; StateIndex curr_state_id; for (Priority i(0); i= COMPASS_MAX_UNREG_DEV) { AP_HAL::panic("Too many compass instances"); } for (uint8_t i=0; i= _unreg_compass_count) { _unreg_compass_count = i+1; } instance = i+COMPASS_MAX_INSTANCES; return false; } else if (extra_dev_id[i] == 0) { extra_dev_id[_unreg_compass_count++].set(dev_id); instance = i+COMPASS_MAX_INSTANCES; return false; } } #else AP_HAL::panic("Too many compass instances"); #endif return false; } Compass::StateIndex Compass::_get_state_id(Compass::Priority priority) const { #if COMPASS_MAX_INSTANCES > 1 if (_priority_did_list[priority] == 0) { return StateIndex(COMPASS_MAX_INSTANCES); } for (StateIndex i(0); iget_device() that prevents duplicate devices being opened */ bool Compass::_have_i2c_driver(uint8_t bus, uint8_t address) const { for (StateIndex i(0); i 0 #define CHECK_UNREG_LIMIT_RETURN if (_unreg_compass_count == COMPASS_MAX_UNREG_DEV) return #else #define CHECK_UNREG_LIMIT_RETURN #endif /* macro to add a backend with check for too many backends or compass instances. We don't try to start more than the maximum allowed */ #define ADD_BACKEND(driver_type, backend) \ do { if (_driver_enabled(driver_type)) { _add_backend(backend); } \ CHECK_UNREG_LIMIT_RETURN; \ } while (0) #define GET_I2C_DEVICE(bus, address) _have_i2c_driver(bus, address)?nullptr:hal.i2c_mgr->get_device(bus, address) /* look for compasses on external i2c buses */ void Compass::_probe_external_i2c_compasses(void) { #if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) bool all_external = (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2); (void)all_external; // in case all backends using this are compiled out #endif #if AP_COMPASS_HMC5843_ENABLED // external i2c bus FOREACH_I2C_EXTERNAL(i) { ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR), true, ROTATION_ROLL_180)); } #if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_MINDPXV2 && AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_AEROFC) { // internal i2c bus FOREACH_I2C_INTERNAL(i) { ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(i, HAL_COMPASS_HMC5843_I2C_ADDR), all_external, all_external?ROTATION_ROLL_180:ROTATION_YAW_270)); } } #endif // !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) #endif // AP_COMPASS_HMC5843_ENABLED #if AP_COMPASS_QMC5883L_ENABLED //external i2c bus FOREACH_I2C_EXTERNAL(i) { ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR), true, HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL)); } // internal i2c bus #if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) if (all_external) { // only probe QMC5883L on internal if we are treating internals as externals FOREACH_I2C_INTERNAL(i) { ADD_BACKEND(DRIVER_QMC5883L, AP_Compass_QMC5883L::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883L_I2C_ADDR), all_external, all_external?HAL_COMPASS_QMC5883L_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883L_ORIENTATION_INTERNAL)); } } #endif #endif // AP_COMPASS_QMC5883L_ENABLED #if AP_COMPASS_QMC5883P_ENABLED //external i2c bus FOREACH_I2C_EXTERNAL(i) { ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR), true, HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL)); } // internal i2c bus #if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) if (all_external) { // only probe QMC5883P on internal if we are treating internals as externals FOREACH_I2C_INTERNAL(i) { ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR), all_external, all_external?HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883P_ORIENTATION_INTERNAL)); } } #endif #endif // AP_COMPASS_QMC5883P_ENABLED #ifndef HAL_BUILD_AP_PERIPH // AK09916 on ICM20948 #if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED FOREACH_I2C_EXTERNAL(i) { ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR), GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR), true, ROTATION_PITCH_180_YAW_90)); ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR), GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR2), true, ROTATION_PITCH_180_YAW_90)); } #if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) FOREACH_I2C_INTERNAL(i) { ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR), GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR), all_external, ROTATION_PITCH_180_YAW_90)); ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR), GET_I2C_DEVICE(i, HAL_COMPASS_ICM20948_I2C_ADDR2), all_external, ROTATION_PITCH_180_YAW_90)); } #endif #endif // AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED #endif // HAL_BUILD_AP_PERIPH #if AP_COMPASS_LIS3MDL_ENABLED // lis3mdl on bus 0 with default address #if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) FOREACH_I2C_INTERNAL(i) { ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR), all_external, all_external?ROTATION_YAW_90:ROTATION_NONE)); } // lis3mdl on bus 0 with alternate address FOREACH_I2C_INTERNAL(i) { ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2), all_external, all_external?ROTATION_YAW_90:ROTATION_NONE)); } #endif // external lis3mdl on bus 1 with default address FOREACH_I2C_EXTERNAL(i) { ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR), true, ROTATION_YAW_90)); } // external lis3mdl on bus 1 with alternate address FOREACH_I2C_EXTERNAL(i) { ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(GET_I2C_DEVICE(i, HAL_COMPASS_LIS3MDL_I2C_ADDR2), true, ROTATION_YAW_90)); } #endif // AP_COMPASS_LIS3MDL_ENABLED #if AP_COMPASS_AK09916_ENABLED // AK09916. This can be found twice, due to the ICM20948 i2c bus pass-thru, so we need to be careful to avoid that FOREACH_I2C_EXTERNAL(i) { ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR), true, ROTATION_YAW_270)); } #if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) FOREACH_I2C_INTERNAL(i) { ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe(GET_I2C_DEVICE(i, HAL_COMPASS_AK09916_I2C_ADDR), all_external, all_external?ROTATION_YAW_270:ROTATION_NONE)); } #endif #endif // AP_COMPASS_AK09916_ENABLED #if AP_COMPASS_IST8310_ENABLED // IST8310 on external and internal bus if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV5 && AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV6) { enum Rotation default_rotation = AP_COMPASS_IST8310_DEFAULT_ROTATION; if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_AEROFC) { default_rotation = ROTATION_PITCH_180_YAW_90; } // probe all 4 possible addresses const uint8_t ist8310_addr[] = { 0x0C, 0x0D, 0x0E, 0x0F }; for (uint8_t a=0; a= 0) { ADD_BACKEND(DRIVER_EXTERNALAHRS, new AP_Compass_ExternalAHRS(serial_port)); } #endif #if AP_FEATURE_BOARD_DETECT if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) { // default to disabling LIS3MDL on pixhawk2 due to hardware issue #if AP_COMPASS_LIS3MDL_ENABLED _driver_type_mask.set_default(1U<get_device(HAL_COMPASS_HMC5843_NAME), false, ROTATION_PITCH_180)); #endif #if AP_COMPASS_LSM303D_ENABLED ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_NONE)); #endif break; case AP_BoardConfig::PX4_BOARD_PIXHAWK2: #if AP_COMPASS_LSM303D_ENABLED ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME), ROTATION_YAW_270)); #endif #if AP_COMPASS_AK8963_ENABLED // we run the AK8963 only on the 2nd MPU9250, which leaves the // first MPU9250 to run without disturbance at high rate ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_YAW_270)); #endif #if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED ADD_BACKEND(DRIVER_AK09916, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_ROLL_180_YAW_90)); #endif break; case AP_BoardConfig::PX4_BOARD_FMUV5: case AP_BoardConfig::PX4_BOARD_FMUV6: #if AP_COMPASS_IST8310_ENABLED FOREACH_I2C_EXTERNAL(i) { ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR), true, ROTATION_ROLL_180_YAW_90)); } FOREACH_I2C_INTERNAL(i) { ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, HAL_COMPASS_IST8310_I2C_ADDR), false, ROTATION_ROLL_180_YAW_90)); } #endif // AP_COMPASS_IST8310_ENABLED break; case AP_BoardConfig::PX4_BOARD_SP01: #if AP_COMPASS_AK8963_ENABLED ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(1, ROTATION_NONE)); #endif break; case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO: #if AP_COMPASS_AK8963_ENABLED ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90)); #endif #if AP_COMPASS_LIS3MDL_ENABLED ADD_BACKEND(DRIVER_LIS3MDL, AP_Compass_LIS3MDL::probe(hal.spi->get_device(HAL_COMPASS_LIS3MDL_NAME), false, ROTATION_NONE)); #endif // AP_COMPASS_LIS3MDL_ENABLED break; case AP_BoardConfig::PX4_BOARD_PHMINI: #if AP_COMPASS_AK8963_ENABLED ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180)); #endif break; case AP_BoardConfig::PX4_BOARD_AUAV21: #if AP_COMPASS_AK8963_ENABLED ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_ROLL_180_YAW_90)); #endif break; case AP_BoardConfig::PX4_BOARD_PH2SLIM: #if AP_COMPASS_AK8963_ENABLED ADD_BACKEND(DRIVER_AK8963, AP_Compass_AK8963::probe_mpu9250(0, ROTATION_YAW_270)); #endif break; case AP_BoardConfig::PX4_BOARD_MINDPXV2: #if AP_COMPASS_HMC5843_ENABLED ADD_BACKEND(DRIVER_HMC5843, AP_Compass_HMC5843::probe(GET_I2C_DEVICE(0, HAL_COMPASS_HMC5843_I2C_ADDR), false, ROTATION_YAW_90)); #endif #if AP_COMPASS_LSM303D_ENABLED ADD_BACKEND(DRIVER_LSM303D, AP_Compass_LSM303D::probe(hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME), ROTATION_PITCH_180_YAW_270)); #endif break; default: break; } #endif } #if AP_COMPASS_DRONECAN_ENABLED /* look for DroneCAN compasses */ void Compass::probe_dronecan_compasses(void) { if (!_driver_enabled(DRIVER_UAVCAN)) { return; } for (uint8_t i=0; i 0 if (_unreg_compass_count == COMPASS_MAX_UNREG_DEV) { break; } #endif } #if COMPASS_MAX_UNREG_DEV > 0 if (option_set(Option::ALLOW_DRONECAN_AUTO_REPLACEMENT) && !suppress_devid_save) { // check if there's any uavcan compass in prio slot that's not found // and replace it if there's a replacement compass for (Priority i(0); i 0 } #endif // AP_COMPASS_DRONECAN_ENABLED // Check if the devid is a potential replacement compass // Following are the checks done to ensure the compass is a replacement // * The compass is an UAVCAN compass // * The compass wasn't seen before this boot as additional unreg mag // * The compass might have been seen before but never setup bool Compass::is_replacement_mag(uint32_t devid) { #if COMPASS_MAX_INSTANCES > 1 // We only do this for UAVCAN mag if (devid == 0 || (AP_HAL::Device::devid_get_bus_type(devid) != AP_HAL::Device::BUS_TYPE_UAVCAN)) { return false; } #if COMPASS_MAX_UNREG_DEV > 0 // Check that its not an unused additional mag for (uint8_t i = 0; i 1 // We only do this for UAVCAN mag if (devid == 0 || (AP_HAL::Device::devid_get_bus_type(devid) != AP_HAL::Device::BUS_TYPE_UAVCAN)) { return; } #if COMPASS_MAX_UNREG_DEV > 0 for (uint8_t i = 0; i 1 // Check if any of the registered devs are not registered for (Priority i(0); iget_soft_armed()) { return; } static uint32_t last_try; //Try once every second if ((AP_HAL::millis() - last_try) < 1000) { return; } last_try = AP_HAL::millis(); if (_driver_enabled(DRIVER_UAVCAN)) { for (uint8_t i=0; iread(); } uint32_t time = AP_HAL::millis(); bool any_healthy = false; for (StateIndex i(0); i < COMPASS_MAX_INSTANCES; i++) { _state[i].healthy = (time - _state[i].last_update_ms < 500); any_healthy |= _state[i].healthy; } #if COMPASS_LEARN_ENABLED if (_learn == LEARN_INFLIGHT && !learn_allocated) { learn_allocated = true; learn = new CompassLearn(*this); } if (_learn == LEARN_INFLIGHT && learn != nullptr) { learn->update(); } #endif #if HAL_LOGGING_ENABLED if (any_healthy && _log_bit != (uint32_t)-1 && AP::logger().should_log(_log_bit)) { AP::logger().Write_Compass(); } #endif // Set _first_usable parameter for (Priority i(0); i get_count()) { return false; } // exit immediately if all offsets are zero if (is_zero(get_offsets(i).length())) { return false; } StateIndex id = _get_state_id(Priority(i)); // exit immediately if dev_id hasn't been detected if (_state[id].detected_dev_id == 0 || id == COMPASS_MAX_INSTANCES) { return false; } #ifdef HAL_USE_EMPTY_STORAGE // the load() call below returns zeroes on empty storage, so the // check-stored-value check here will always fail. Since nobody // really cares about the empty-storage case, shortcut out here // for simplicity. return true; #endif // back up cached value of dev_id int32_t dev_id_cache_value = _state[id].dev_id; // load dev_id from eeprom _state[id].dev_id.load(); // 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 unconfigured if (_state[id].dev_id != _state[id].detected_dev_id || _state[id].dev_id != dev_id_cache_value) { // restore cached value _state[id].dev_id.set(dev_id_cache_value); // return failure return false; } // if we got here then it must be configured return true; } bool Compass::configured(char *failure_msg, uint8_t failure_msg_len) { #if COMPASS_MAX_INSTANCES > 1 // Check if any of the registered devs are not registered for (Priority i(0); i AP_COMPASS_MAX_XYZ_ANG_DIFF) { return false; } // check for an unacceptable angle difference on the xy plane const float xy_ang_diff = mag_field_xy.angle(primary_mag_field_xy); if (xy_ang_diff > AP_COMPASS_MAX_XY_ANG_DIFF) { return false; } // check for an unacceptable length difference on the xy plane const float xy_len_diff = (primary_mag_field_xy-mag_field_xy).length(); if (xy_len_diff > AP_COMPASS_MAX_XY_LENGTH_DIFF) { return false; } } return true; } bool Compass::healthy(uint8_t i) const { return (i < COMPASS_MAX_INSTANCES) ? _get_state(Priority(i)).healthy : false; } /* return true if we have a valid scale factor */ bool Compass::have_scale_factor(uint8_t i) const { if (!available()) { return false; } StateIndex id = _get_state_id(Priority(i)); if (id >= COMPASS_MAX_INSTANCES || _state[id].scale_factor < COMPASS_MIN_SCALE_FACTOR || _state[id].scale_factor > COMPASS_MAX_SCALE_FACTOR) { return false; } return true; } #if AP_COMPASS_MSP_ENABLED void Compass::handle_msp(const MSP::msp_compass_data_message_t &pkt) { if (!_driver_enabled(DRIVER_MSP)) { return; } if (!init_done) { if (pkt.instance < 8) { msp_instance_mask |= 1U<handle_msp(pkt); } } } #endif // AP_COMPASS_MSP_ENABLED #if AP_COMPASS_EXTERNALAHRS_ENABLED void Compass::handle_external(const AP_ExternalAHRS::mag_data_message_t &pkt) { if (!_driver_enabled(DRIVER_EXTERNALAHRS)) { return; } for (uint8_t i=0; i<_backend_count; i++) { _backends[i]->handle_external(pkt); } } #endif // AP_COMPASS_EXTERNALAHRS_ENABLED // force save of current calibration as valid void Compass::force_save_calibration(void) { for (StateIndex i(0); i