2011-12-28 05:31:36 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-08-11 03:28:42 -03:00
# include <AP_HAL/AP_HAL.h>
2011-02-14 00:25:20 -04:00
# include "Compass.h"
2015-08-11 03:28:42 -03:00
# include <AP_Vehicle/AP_Vehicle.h>
2015-02-23 19:17:44 -04:00
extern AP_HAL : : HAL & hal ;
# if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
# define COMPASS_LEARN_DEFAULT 0
# else
# define COMPASS_LEARN_DEFAULT 1
# endif
2011-02-14 00:25:20 -04:00
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo Compass : : var_info [ ] = {
2012-03-09 22:45:35 -04:00
// index 0 was used for the old orientation matrix
2013-01-02 03:07:33 -04:00
// @Param: OFS_X
2015-09-29 16:51:21 -03:00
// @DisplayName: Compass offsets in milligauss on the X axis
2013-01-02 03:07:33 -04:00
// @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame
// @Range: -400 400
2015-10-15 08:32:47 -03:00
// @Units: milligauss
2013-01-02 03:07:33 -04:00
// @Increment: 1
// @Param: OFS_Y
2015-09-29 16:51:21 -03:00
// @DisplayName: Compass offsets in milligauss on the Y axis
2013-01-02 03:07:33 -04:00
// @Description: Offset to be added to the compass y-axis values to compensate for metal in the frame
// @Range: -400 400
2015-10-15 08:32:47 -03:00
// @Units: milligauss
2013-01-02 03:07:33 -04:00
// @Increment: 1
// @Param: OFS_Z
2015-09-29 16:51:21 -03:00
// @DisplayName: Compass offsets in milligauss on the Z axis
2013-01-02 03:07:33 -04:00
// @Description: Offset to be added to the compass z-axis values to compensate for metal in the frame
// @Range: -400 400
2015-10-15 08:32:47 -03:00
// @Units: milligauss
2013-01-02 03:07:33 -04:00
// @Increment: 1
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " OFS " , 1 , Compass , _state [ 0 ] . offset , 0 ) ,
2013-01-02 03:07:33 -04:00
// @Param: DEC
// @DisplayName: Compass declination
// @Description: An angle to compensate between the true north and magnetic north
// @Range: -3.142 3.142
// @Units: Radians
// @Increment: 0.01
// @User: Standard
2012-08-06 22:02:14 -03:00
AP_GROUPINFO ( " DEC " , 2 , Compass , _declination , 0 ) ,
2013-01-02 03:07:33 -04:00
// @Param: LEARN
// @DisplayName: Learn compass offsets automatically
// @Description: Enable or disable the automatic learning of compass offsets
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " LEARN " , 3 , Compass , _learn , COMPASS_LEARN_DEFAULT ) ,
2013-01-02 03:07:33 -04:00
// @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
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " USE " , 4 , Compass , _state [ 0 ] . use_for_yaw , 1 ) , // true if used for DCM yaw
2013-01-02 03:07:33 -04:00
// @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
2012-08-06 22:02:14 -03:00
AP_GROUPINFO ( " AUTODEC " , 5 , Compass , _auto_declination , 1 ) ,
2013-02-27 03:57:04 -04:00
2013-03-03 10:02:12 -04:00
// @Param: MOTCT
// @DisplayName: Motor interference compensation type
2013-05-11 02:50:36 -03:00
// @Description: Set motor interference compensation type to disabled, throttle or current. Do not change manually.
2013-03-03 10:02:12 -04:00
// @Values: 0:Disabled,1:Use Throttle,2:Use Current
2015-10-15 08:32:47 -03:00
// @User: Advanced
2013-03-03 10:02:12 -04:00
AP_GROUPINFO ( " MOTCT " , 6 , Compass , _motor_comp_type , AP_COMPASS_MOT_COMP_DISABLED ) ,
2013-02-27 03:57:04 -04:00
// @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
2013-03-01 10:59:53 -04:00
// @Range: -1000 1000
2013-05-11 02:50:36 -03:00
// @Units: Offset per Amp or at Full Throttle
2013-02-27 03:57:04 -04:00
// @Increment: 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
2013-03-01 10:59:53 -04:00
// @Range: -1000 1000
2013-05-11 02:50:36 -03:00
// @Units: Offset per Amp or at Full Throttle
2013-02-27 03:57:04 -04:00
// @Increment: 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
2013-03-01 10:59:53 -04:00
// @Range: -1000 1000
2013-05-11 02:50:36 -03:00
// @Units: Offset per Amp or at Full Throttle
2013-02-27 03:57:04 -04:00
// @Increment: 1
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " MOT " , 7 , Compass , _state [ 0 ] . motor_compensation , 0 ) ,
2013-02-27 03:57:04 -04:00
2013-05-01 23:27:35 -03:00
// @Param: ORIENT
// @DisplayName: Compass orientation
2014-02-26 21:46:27 -04:00
// @Description: The orientation of the compass relative to the autopilot board. This will default to the right value for each board type, but can be changed if you have an external compass. See the documentation for your external compass for the right value. The correct orientation should give the X axis forward, the Y axis to the right and the Z axis down. So if your aircraft is pointing west it should show a positive value for the Y axis, and a value close to zero for the X axis. On a PX4 or Pixhawk with an external compass the correct value is zero if the compass is correctly oriented. NOTE: This orientation is combined with any AHRS_ORIENTATION setting.
2015-01-02 04:19:12 -04:00
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw136,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll90
2015-10-15 08:32:47 -03:00
// @User: Advanced
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " ORIENT " , 8 , Compass , _state [ 0 ] . orientation , ROTATION_NONE ) ,
2013-05-01 23:27:35 -03:00
2013-08-30 01:02:09 -03:00
// @Param: EXTERNAL
// @DisplayName: Compass is attached via an external cable
2014-02-26 21:46:27 -04:00
// @Description: Configure compass so it is attached externally. This is auto-detected on PX4 and Pixhawk, but must be set correctly on an APM2. 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
2013-08-30 01:02:09 -03:00
// @Values: 0:Internal,1:External
// @User: Advanced
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " EXTERNAL " , 9 , Compass , _state [ 0 ] . external , 0 ) ,
2013-08-30 01:02:09 -03:00
2014-09-27 05:59:26 -03:00
// @Param: OFS2_X
2015-09-29 16:51:21 -03:00
// @DisplayName: Compass2 offsets in milligauss on the X axis
2014-09-27 05:59:26 -03:00
// @Description: Offset to be added to compass2's x-axis values to compensate for metal in the frame
// @Range: -400 400
2015-10-15 08:32:47 -03:00
// @Units: milligauss
2014-09-27 05:59:26 -03:00
// @Increment: 1
// @Param: OFS2_Y
2015-09-29 16:51:21 -03:00
// @DisplayName: Compass2 offsets in milligauss on the Y axis
2014-09-27 05:59:26 -03:00
// @Description: Offset to be added to compass2's y-axis values to compensate for metal in the frame
// @Range: -400 400
2015-10-15 08:32:47 -03:00
// @Units: milligauss
2014-09-27 05:59:26 -03:00
// @Increment: 1
// @Param: OFS2_Z
2015-09-29 16:51:21 -03:00
// @DisplayName: Compass2 offsets in milligauss on the Z axis
2014-09-27 05:59:26 -03:00
// @Description: Offset to be added to compass2's z-axis values to compensate for metal in the frame
// @Range: -400 400
2015-10-15 08:32:47 -03:00
// @Units: milligauss
2014-09-27 05:59:26 -03:00
// @Increment: 1
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " OFS2 " , 10 , Compass , _state [ 1 ] . offset , 0 ) ,
2014-09-27 05:59:26 -03:00
// @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
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Increment: 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
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Increment: 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
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Increment: 1
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " MOT2 " , 11 , Compass , _state [ 1 ] . motor_compensation , 0 ) ,
2014-05-21 23:52:25 -03:00
// @Param: PRIMARY
// @DisplayName: Choose primary compass
2014-07-10 19:32:06 -03:00
// @Description: If more than one compass is available this selects which compass is the primary. Normally 0=External, 1=Internal. If no External compass is attached this parameter is ignored
2015-07-02 01:49:48 -03:00
// @Values: 0:FirstCompass,1:SecondCompass,2:ThirdCompass
2014-05-21 23:52:25 -03:00
// @User: Advanced
AP_GROUPINFO ( " PRIMARY " , 12 , Compass , _primary , 0 ) ,
2013-12-09 02:33:54 -04:00
2014-09-27 05:59:26 -03:00
// @Param: OFS3_X
2015-09-29 16:51:21 -03:00
// @DisplayName: Compass3 offsets in milligauss on the X axis
2014-09-27 05:59:26 -03:00
// @Description: Offset to be added to compass3's x-axis values to compensate for metal in the frame
// @Range: -400 400
2015-10-15 08:32:47 -03:00
// @Units: milligauss
2014-09-27 05:59:26 -03:00
// @Increment: 1
// @Param: OFS3_Y
2015-09-29 16:51:21 -03:00
// @DisplayName: Compass3 offsets in milligauss on the Y axis
2014-09-27 05:59:26 -03:00
// @Description: Offset to be added to compass3's y-axis values to compensate for metal in the frame
// @Range: -400 400
2015-10-15 08:32:47 -03:00
// @Units: milligauss
2014-09-27 05:59:26 -03:00
// @Increment: 1
// @Param: OFS3_Z
2015-09-29 16:51:21 -03:00
// @DisplayName: Compass3 offsets in milligauss on the Z axis
2014-09-27 05:59:26 -03:00
// @Description: Offset to be added to compass3's z-axis values to compensate for metal in the frame
// @Range: -400 400
2015-10-15 08:32:47 -03:00
// @Units: milligauss
2014-09-27 05:59:26 -03:00
// @Increment: 1
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " OFS3 " , 13 , Compass , _state [ 2 ] . offset , 0 ) ,
2014-09-27 05:59:26 -03:00
// @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
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Increment: 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
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Increment: 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
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Increment: 1
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " MOT3 " , 14 , Compass , _state [ 2 ] . motor_compensation , 0 ) ,
2014-07-03 23:07:47 -03:00
2014-07-07 09:24:18 -03:00
// @Param: DEV_ID
// @DisplayName: Compass device id
// @Description: Compass device id. Automatically detected, do not set manually
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " DEV_ID " , 15 , Compass , _state [ 0 ] . dev_id , 0 ) ,
2014-07-07 09:24:18 -03:00
// @Param: DEV_ID2
// @DisplayName: Compass2 device id
// @Description: Second compass's device id. Automatically detected, do not set manually
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " DEV_ID2 " , 16 , Compass , _state [ 1 ] . dev_id , 0 ) ,
2014-07-07 09:24:18 -03:00
// @Param: DEV_ID3
// @DisplayName: Compass3 device id
// @Description: Third compass's device id. Automatically detected, do not set manually
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " DEV_ID3 " , 17 , Compass , _state [ 2 ] . dev_id , 0 ) ,
2014-07-07 09:24:18 -03:00
2014-09-24 10:26:42 -03:00
// @Param: USE2
// @DisplayName: Compass2 used for yaw
// @Description: Enable or disable the second compass for determining heading.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " USE2 " , 18 , Compass , _state [ 1 ] . use_for_yaw , 1 ) ,
2014-09-24 10:26:42 -03:00
// @Param: ORIENT2
// @DisplayName: Compass2 orientation
// @Description: The orientation of the second compass relative to the frame (if external) or autopilot board (if internal).
2015-01-02 04:19:12 -04:00
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw136,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll90
2015-10-15 08:32:47 -03:00
// @User: Advanced
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " ORIENT2 " , 19 , Compass , _state [ 1 ] . orientation , ROTATION_NONE ) ,
2014-09-24 10:26:42 -03:00
2014-11-07 21:21:22 -04:00
// @Param: EXTERN2
2014-09-24 10:26:42 -03:00
// @DisplayName: Compass2 is attached via an external cable
// @Description: Configure second compass so it is attached externally. This is auto-detected on PX4 and Pixhawk.
// @Values: 0:Internal,1:External
// @User: Advanced
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " EXTERN2 " , 20 , Compass , _state [ 1 ] . external , 0 ) ,
2014-09-24 10:26:42 -03:00
// @Param: USE3
// @DisplayName: Compass3 used for yaw
// @Description: Enable or disable the third compass for determining heading.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " USE3 " , 21 , Compass , _state [ 2 ] . use_for_yaw , 1 ) ,
2014-09-24 10:26:42 -03:00
// @Param: ORIENT3
// @DisplayName: Compass3 orientation
// @Description: The orientation of the third compass relative to the frame (if external) or autopilot board (if internal).
2015-01-02 04:19:12 -04:00
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw136,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll90
2015-10-15 08:32:47 -03:00
// @User: Advanced
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " ORIENT3 " , 22 , Compass , _state [ 2 ] . orientation , ROTATION_NONE ) ,
2014-09-24 10:26:42 -03:00
2014-11-07 21:21:22 -04:00
// @Param: EXTERN3
2014-09-24 10:26:42 -03:00
// @DisplayName: Compass3 is attached via an external cable
// @Description: Configure third compass so it is attached externally. This is auto-detected on PX4 and Pixhawk.
// @Values: 0:Internal,1:External
// @User: Advanced
2015-02-23 19:17:44 -04:00
AP_GROUPINFO ( " EXTERN3 " , 23 , Compass , _state [ 2 ] . external , 0 ) ,
2014-09-24 10:26:42 -03:00
2015-03-18 20:18:47 -03:00
// @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]]
// @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]]
// @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]]
AP_GROUPINFO ( " DIA " , 24 , Compass , _state [ 0 ] . diagonals , 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]]
// @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]]
// @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]]
AP_GROUPINFO ( " ODI " , 25 , Compass , _state [ 0 ] . offdiagonals , 0 ) ,
// @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]]
// @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]]
// @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]]
AP_GROUPINFO ( " DIA2 " , 26 , Compass , _state [ 1 ] . diagonals , 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]]
// @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]]
// @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]]
AP_GROUPINFO ( " ODI2 " , 27 , Compass , _state [ 1 ] . offdiagonals , 0 ) ,
// @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]]
// @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]]
// @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]]
AP_GROUPINFO ( " DIA3 " , 28 , Compass , _state [ 2 ] . diagonals , 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]]
// @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]]
// @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]]
AP_GROUPINFO ( " ODI3 " , 29 , Compass , _state [ 2 ] . offdiagonals , 0 ) ,
2015-09-14 04:01:14 -03:00
// @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 20
// @Increment: 0.1
// @User: Advanced
AP_GROUPINFO ( " CAL_FIT " , 30 , Compass , _calibration_threshold , 8.0f ) ,
2012-02-12 03:23:19 -04:00
AP_GROUPEND
2012-02-11 07:53:30 -04:00
} ;
2011-02-14 00:25:20 -04:00
// Default constructor.
// Note that the Vector/Matrix constructors already implicitly zero
// their values.
//
2012-02-11 07:53:30 -04:00
Compass : : Compass ( void ) :
2015-10-15 08:06:31 -03:00
_compass_cal_autoreboot ( false ) ,
_cal_complete_requires_reboot ( false ) ,
_cal_has_run ( false ) ,
2014-11-15 21:58:23 -04:00
_backend_count ( 0 ) ,
_compass_count ( 0 ) ,
2015-03-13 08:32:35 -03:00
_board_orientation ( ROTATION_NONE ) ,
2015-05-02 06:09:03 -03:00
_null_init_done ( false ) ,
2015-04-24 02:12:41 -03:00
_thr_or_curr ( 0.0f ) ,
2015-10-15 08:06:31 -03:00
_hil_mode ( false )
2011-02-14 00:25:20 -04:00
{
2012-12-12 17:43:51 -04:00
AP_Param : : setup_object_defaults ( this , var_info ) ;
2014-11-15 21:58:23 -04:00
for ( uint8_t i = 0 ; i < COMPASS_MAX_BACKEND ; i + + ) {
_backends [ i ] = NULL ;
2015-07-16 05:56:12 -03:00
_state [ i ] . last_update_usec = 0 ;
2015-08-27 23:44:33 -03:00
_reports_sent [ i ] = 0 ;
}
2014-07-10 03:35:40 -03:00
// default device ids to zero. init() method will overwrite with the actual device ids
2014-07-15 00:12:58 -03:00
for ( uint8_t i = 0 ; i < COMPASS_MAX_INSTANCES ; i + + ) {
2015-02-23 19:17:44 -04:00
_state [ i ] . dev_id = 0 ;
2014-07-10 03:35:40 -03:00
}
2011-02-14 00:25:20 -04:00
}
2014-11-15 21:58:23 -04:00
// Default init method
2011-02-14 00:25:20 -04:00
//
bool
Compass : : init ( )
{
2014-11-15 21:58:23 -04:00
if ( _compass_count = = 0 ) {
// detect available backends. Only called once
_detect_backends ( ) ;
}
2015-03-13 02:43:34 -03:00
if ( _compass_count ! = 0 ) {
// get initial health status
hal . scheduler - > delay ( 100 ) ;
read ( ) ;
}
2011-02-14 00:25:20 -04:00
return true ;
}
2014-11-15 21:58:23 -04:00
// Register a new compass instance
//
uint8_t Compass : : register_compass ( void )
{
if ( _compass_count = = COMPASS_MAX_INSTANCES ) {
2015-10-24 18:45:41 -03:00
hal . scheduler - > panic ( " Too many compass instances " ) ;
2014-11-15 21:58:23 -04:00
}
return _compass_count + + ;
}
2015-08-05 17:02:32 -03:00
void Compass : : _add_backend ( AP_Compass_Backend * backend )
2014-11-15 21:58:23 -04:00
{
2015-08-05 17:02:32 -03:00
if ( ! backend )
return ;
if ( _backend_count = = COMPASS_MAX_BACKEND )
2015-10-24 18:45:41 -03:00
hal . scheduler - > panic ( " Too many compass backends " ) ;
2015-08-05 17:02:32 -03:00
_backends [ _backend_count + + ] = backend ;
2014-11-15 21:58:23 -04:00
}
/*
detect available backends for this board
*/
2015-08-05 17:02:32 -03:00
void Compass : : _detect_backends ( void )
2014-11-15 21:58:23 -04:00
{
2015-03-13 08:32:35 -03:00
if ( _hil_mode ) {
2015-08-05 17:02:32 -03:00
_add_backend ( AP_Compass_HIL : : detect ( * this ) ) ;
2015-03-13 08:32:35 -03:00
return ;
}
2014-11-15 21:58:23 -04:00
2015-08-17 21:09:52 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
_add_backend ( AP_Compass_HMC5843 : : detect_i2c ( * this , hal . i2c ) ) ;
_add_backend ( AP_Compass_LSM303D : : detect_spi ( * this ) ) ;
2015-08-12 18:45:30 -03:00
# elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX && \
CONFIG_HAL_BOARD_SUBTYPE ! = HAL_BOARD_SUBTYPE_LINUX_NONE & & \
CONFIG_HAL_BOARD_SUBTYPE ! = HAL_BOARD_SUBTYPE_LINUX_BEBOP & & \
CONFIG_HAL_BOARD_SUBTYPE ! = HAL_BOARD_SUBTYPE_LINUX_MINLURE
2015-08-07 19:54:58 -03:00
_add_backend ( AP_Compass_HMC5843 : : detect_i2c ( * this , hal . i2c ) ) ;
2015-10-05 17:42:00 -03:00
_add_backend ( AP_Compass_AK8963 : : detect_mpu9250 ( * this , hal . spi - > device ( AP_HAL : : SPIDevice_MPU9250 ) ) ) ;
2015-03-13 02:43:34 -03:00
# elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HIL
2015-08-05 17:02:32 -03:00
_add_backend ( AP_Compass_HIL : : detect ( * this ) ) ;
2014-11-15 21:58:23 -04:00
# elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843
2015-08-07 19:54:58 -03:00
_add_backend ( AP_Compass_HMC5843 : : detect_i2c ( * this , hal . i2c ) ) ;
2015-08-10 20:30:32 -03:00
# elif HAL_COMPASS_DEFAULT == HAL_COMPASS_HMC5843_MPU6000
_add_backend ( AP_Compass_HMC5843 : : detect_mpu6000 ( * this ) ) ;
2015-07-10 01:05:21 -03:00
# elif HAL_COMPASS_DEFAULT == HAL_COMPASS_AK8963_I2C && HAL_INS_AK8963_I2C_BUS == 1
2015-08-05 19:02:56 -03:00
_add_backend ( AP_Compass_AK8963 : : detect_i2c ( * this , hal . i2c1 ,
HAL_COMPASS_AK8963_I2C_ADDR ) ) ;
2015-02-23 19:17:44 -04:00
# elif HAL_COMPASS_DEFAULT == HAL_COMPASS_PX4 || HAL_COMPASS_DEFAULT == HAL_COMPASS_VRBRAIN
2015-08-05 17:02:32 -03:00
_add_backend ( AP_Compass_PX4 : : detect ( * this ) ) ;
2014-11-15 21:58:23 -04:00
# else
# error Unrecognised HAL_COMPASS_TYPE setting
# endif
if ( _backend_count = = 0 | |
_compass_count = = 0 ) {
2015-10-25 16:50:51 -03:00
hal . console - > println ( " No Compass backends available " ) ;
2014-11-15 21:58:23 -04:00
}
}
void
Compass : : accumulate ( void )
{
for ( uint8_t i = 0 ; i < _backend_count ; i + + ) {
// call accumulate on each of the backend
_backends [ i ] - > accumulate ( ) ;
}
}
bool
Compass : : read ( void )
{
2015-02-23 19:17:44 -04:00
for ( uint8_t i = 0 ; i < _backend_count ; i + + ) {
2014-11-15 21:58:23 -04:00
// call read on each of the backend. This call updates field[i]
_backends [ i ] - > read ( ) ;
}
2015-03-13 02:43:34 -03:00
for ( uint8_t i = 0 ; i < COMPASS_MAX_INSTANCES ; i + + ) {
_state [ i ] . healthy = ( hal . scheduler - > millis ( ) - _state [ i ] . last_update_ms < 500 ) ;
}
2015-02-23 19:17:44 -04:00
return healthy ( ) ;
2014-11-15 21:58:23 -04:00
}
2015-03-18 20:42:30 -03:00
uint8_t
Compass : : get_healthy_mask ( ) const
{
uint8_t healthy_mask = 0 ;
for ( uint8_t i = 0 ; i < COMPASS_MAX_INSTANCES ; i + + ) {
if ( healthy ( i ) ) {
healthy_mask | = 1 < < i ;
}
}
return healthy_mask ;
}
2014-10-14 19:16:31 -03:00
void
Compass : : set_offsets ( uint8_t i , const Vector3f & offsets )
{
// sanity check compass instance provided
if ( i < COMPASS_MAX_INSTANCES ) {
2015-02-23 19:17:44 -04:00
_state [ i ] . offset . set ( offsets ) ;
2014-10-14 19:16:31 -03:00
}
}
2011-02-14 00:25:20 -04:00
void
2014-07-09 05:09:02 -03:00
Compass : : set_and_save_offsets ( uint8_t i , const Vector3f & offsets )
2011-02-14 00:25:20 -04:00
{
2014-07-10 02:37:27 -03:00
// sanity check compass instance provided
if ( i < COMPASS_MAX_INSTANCES ) {
2015-02-23 19:17:44 -04:00
_state [ i ] . offset . set ( offsets ) ;
2014-07-10 02:37:27 -03:00
save_offsets ( i ) ;
}
2011-02-14 00:25:20 -04:00
}
2015-03-18 20:18:47 -03:00
void
Compass : : set_and_save_diagonals ( uint8_t i , const Vector3f & diagonals )
{
// sanity check compass instance provided
if ( i < COMPASS_MAX_INSTANCES ) {
_state [ i ] . diagonals . set_and_save ( diagonals ) ;
}
}
void
Compass : : set_and_save_offdiagonals ( uint8_t i , const Vector3f & offdiagonals )
{
// sanity check compass instance provided
if ( i < COMPASS_MAX_INSTANCES ) {
_state [ i ] . offdiagonals . set_and_save ( offdiagonals ) ;
}
}
2011-02-14 00:25:20 -04:00
void
2014-07-09 05:07:30 -03:00
Compass : : save_offsets ( uint8_t i )
2011-02-14 00:25:20 -04:00
{
2015-02-23 19:17:44 -04:00
_state [ i ] . offset . save ( ) ; // save offsets
_state [ i ] . dev_id . save ( ) ; // save device id corresponding to these offsets
2014-07-09 05:07:30 -03:00
}
void
Compass : : save_offsets ( void )
{
for ( uint8_t i = 0 ; i < COMPASS_MAX_INSTANCES ; i + + ) {
save_offsets ( i ) ;
2013-12-09 02:33:54 -04:00
}
2011-02-14 00:25:20 -04:00
}
2013-02-27 03:57:04 -04:00
void
2014-07-22 04:29:43 -03:00
Compass : : set_motor_compensation ( uint8_t i , const Vector3f & motor_comp_factor )
2013-02-27 03:57:04 -04:00
{
2015-02-23 19:17:44 -04:00
_state [ i ] . motor_compensation . set ( motor_comp_factor ) ;
2013-02-27 03:57:04 -04:00
}
void
Compass : : save_motor_compensation ( )
{
2013-03-03 10:02:12 -04:00
_motor_comp_type . save ( ) ;
2013-12-09 04:45:31 -04:00
for ( uint8_t k = 0 ; k < COMPASS_MAX_INSTANCES ; k + + ) {
2015-02-23 19:17:44 -04:00
_state [ k ] . motor_compensation . save ( ) ;
2013-12-09 04:45:31 -04:00
}
2013-02-27 03:57:04 -04:00
}
2012-03-30 00:18:06 -03:00
void
2012-08-18 08:41:38 -03:00
Compass : : set_initial_location ( int32_t latitude , int32_t longitude )
2012-03-10 19:19:04 -04:00
{
2012-03-30 00:18:06 -03:00
// if automatic declination is configured, then compute
// the declination based on the initial GPS fix
2012-08-17 03:19:22 -03:00
if ( _auto_declination ) {
// Set the declination based on the lat/lng from GPS
2012-10-11 17:48:39 -03:00
_declination . set ( radians (
AP_Declination : : get_declination (
( float ) latitude / 10000000 ,
( float ) longitude / 10000000 ) ) ) ;
2012-08-17 03:19:22 -03:00
}
2012-03-10 19:19:04 -04:00
}
2014-09-18 09:56:13 -03:00
/// return true if the compass should be used for yaw calculations
bool
Compass : : use_for_yaw ( void ) const
{
uint8_t prim = get_primary ( ) ;
return healthy ( prim ) & & use_for_yaw ( prim ) ;
}
/// return true if the specified compass can be used for yaw calculations
bool
Compass : : use_for_yaw ( uint8_t i ) const
{
2015-02-23 19:17:44 -04:00
return _state [ i ] . use_for_yaw ;
2014-09-18 09:56:13 -03:00
}
2011-02-14 00:25:20 -04:00
void
2013-04-15 09:50:44 -03:00
Compass : : set_declination ( float radians , bool save_to_eeprom )
2011-02-14 00:25:20 -04:00
{
2013-04-15 09:50:44 -03:00
if ( save_to_eeprom ) {
_declination . set_and_save ( radians ) ;
} else {
_declination . set ( radians ) ;
}
2011-02-14 00:25:20 -04:00
}
2011-02-18 23:57:53 -04:00
float
2013-05-08 20:22:00 -03:00
Compass : : get_declination ( ) const
2011-02-18 23:57:53 -04:00
{
2012-08-17 03:19:22 -03:00
return _declination . get ( ) ;
2011-02-18 23:57:53 -04:00
}
2013-08-18 08:08:34 -03:00
/*
calculate a compass heading given the attitude from DCM and the mag vector
*/
2012-06-20 06:30:30 -03:00
float
2013-05-08 20:22:00 -03:00
Compass : : calculate_heading ( const Matrix3f & dcm_matrix ) const
2011-02-14 00:25:20 -04:00
{
2013-08-18 08:08:34 -03:00
float cos_pitch_sq = 1.0f - ( dcm_matrix . c . x * dcm_matrix . c . x ) ;
2011-05-08 15:15:29 -03:00
// Tilt compensated magnetic field Y component:
2015-09-28 16:56:49 -03:00
const Vector3f & field = get_field ( ) ;
2015-02-23 19:17:44 -04:00
float headY = field . y * dcm_matrix . c . z - field . z * dcm_matrix . c . y ;
2012-02-23 19:42:03 -04:00
2011-02-14 00:25:20 -04:00
// Tilt compensated magnetic field X component:
2015-02-23 19:17:44 -04:00
float headX = field . x * cos_pitch_sq - dcm_matrix . c . x * ( field . y * dcm_matrix . c . y + field . z * dcm_matrix . c . z ) ;
2013-05-08 20:19:01 -03:00
2011-02-14 00:25:20 -04:00
// magnetic heading
2011-07-08 00:56:04 -03:00
// 6/4/11 - added constrain to keep bad values from ruining DCM Yaw - Jason S.
2013-05-08 20:19:01 -03:00
float heading = constrain_float ( atan2f ( - headY , headX ) , - 3.15f , 3.15f ) ;
2011-02-14 00:25:20 -04:00
// Declination correction (if supplied)
2013-01-10 14:42:24 -04:00
if ( fabsf ( _declination ) > 0.0f )
2011-02-14 00:25:20 -04:00
{
heading = heading + _declination ;
2013-01-10 14:42:24 -04:00
if ( heading > PI ) // Angle normalization (-180 deg, 180 deg)
heading - = ( 2.0f * PI ) ;
else if ( heading < - PI )
heading + = ( 2.0f * PI ) ;
2011-02-14 00:25:20 -04:00
}
2012-06-20 06:30:30 -03:00
return heading ;
2011-02-14 00:25:20 -04:00
}
2014-07-07 09:24:18 -03:00
/// Returns True if the compasses have been configured (i.e. offsets saved)
///
/// @returns True if compass has been configured
///
bool Compass : : configured ( uint8_t i )
{
// exit immediately if instance is beyond the number of compasses we have available
if ( i > get_count ( ) ) {
return false ;
}
// exit immediately if all offsets are zero
2015-05-04 23:35:20 -03:00
if ( is_zero ( get_offsets ( i ) . length ( ) ) ) {
2014-07-07 09:24:18 -03:00
return false ;
}
2015-08-24 11:53:17 -03:00
// exit immediately if all offsets (mG) are zero
2015-09-28 16:56:49 -03:00
if ( is_zero ( get_offsets ( i ) . length ( ) ) ) {
2015-08-24 11:53:17 -03:00
return false ;
}
2014-07-07 09:24:18 -03:00
// backup detected dev_id
2015-02-23 19:17:44 -04:00
int32_t dev_id_orig = _state [ i ] . dev_id ;
2014-07-07 09:24:18 -03:00
// load dev_id from eeprom
2015-02-23 19:17:44 -04:00
_state [ i ] . dev_id . load ( ) ;
2014-07-07 09:24:18 -03:00
// if different then the device has not been configured
2015-02-23 19:17:44 -04:00
if ( _state [ i ] . dev_id ! = dev_id_orig ) {
2014-07-07 09:24:18 -03:00
// restore device id
2015-02-23 19:17:44 -04:00
_state [ i ] . dev_id = dev_id_orig ;
2014-07-07 09:24:18 -03:00
// return failure
return false ;
}
2012-03-27 01:16:00 -03:00
2014-07-07 09:24:18 -03:00
// if we got here then it must be configured
return true ;
}
bool Compass : : configured ( void )
{
bool all_configured = true ;
for ( uint8_t i = 0 ; i < get_count ( ) ; i + + ) {
2015-03-17 22:38:55 -03:00
all_configured = all_configured & & ( ! use_for_yaw ( i ) | | configured ( i ) ) ;
2014-07-07 09:24:18 -03:00
}
return all_configured ;
}
2014-07-31 22:19:53 -03:00
2014-11-15 21:58:23 -04:00
// Update raw magnetometer values from HIL data
//
2015-05-15 01:04:00 -03:00
void Compass : : setHIL ( uint8_t instance , float roll , float pitch , float yaw )
2014-11-15 21:58:23 -04:00
{
Matrix3f R ;
// create a rotation matrix for the given attitude
R . from_euler ( roll , pitch , yaw ) ;
2015-05-04 23:35:20 -03:00
if ( ! is_equal ( _hil . last_declination , get_declination ( ) ) ) {
2014-11-15 21:58:23 -04:00
_setup_earth_field ( ) ;
2015-02-23 19:17:44 -04:00
_hil . last_declination = get_declination ( ) ;
2014-11-15 21:58:23 -04:00
}
// convert the earth frame magnetic vector to body frame, and
// apply the offsets
2015-05-15 01:04:00 -03:00
_hil . field [ instance ] = R . mul_transpose ( _hil . Bearth ) ;
2014-11-15 21:58:23 -04:00
// apply default board orientation for this compass type. This is
// a noop on most boards
2015-05-15 01:04:00 -03:00
_hil . field [ instance ] . rotate ( MAG_BOARD_ORIENTATION ) ;
2014-11-15 21:58:23 -04:00
// add user selectable orientation
2015-05-15 01:04:00 -03:00
_hil . field [ instance ] . rotate ( ( enum Rotation ) _state [ 0 ] . orientation . get ( ) ) ;
2014-11-15 21:58:23 -04:00
2015-02-23 19:17:44 -04:00
if ( ! _state [ 0 ] . external ) {
2014-11-15 21:58:23 -04:00
// and add in AHRS_ORIENTATION setting if not an external compass
2015-05-15 01:04:00 -03:00
_hil . field [ instance ] . rotate ( _board_orientation ) ;
2014-11-15 21:58:23 -04:00
}
2015-05-15 01:04:00 -03:00
_hil . healthy [ instance ] = true ;
2014-11-15 21:58:23 -04:00
}
// Update raw magnetometer values from HIL mag vector
//
2015-05-15 01:04:00 -03:00
void Compass : : setHIL ( uint8_t instance , const Vector3f & mag )
2014-11-15 21:58:23 -04:00
{
2015-05-15 01:04:00 -03:00
_hil . field [ instance ] = mag ;
_hil . healthy [ instance ] = true ;
2015-07-16 05:56:12 -03:00
_state [ instance ] . last_update_usec = hal . scheduler - > micros ( ) ;
2014-11-15 21:58:23 -04:00
}
2015-05-15 01:04:00 -03:00
const Vector3f & Compass : : getHIL ( uint8_t instance ) const
{
return _hil . field [ instance ] ;
2014-11-15 21:58:23 -04:00
}
// setup _Bearth
void Compass : : _setup_earth_field ( void )
{
// assume a earth field strength of 400
2015-02-23 19:17:44 -04:00
_hil . Bearth ( 400 , 0 , 0 ) ;
2014-11-15 21:58:23 -04:00
// rotate _Bearth for inclination and declination. -66 degrees
// is the inclination in Canberra, Australia
Matrix3f R ;
R . from_euler ( 0 , ToRad ( 66 ) , get_declination ( ) ) ;
2015-02-23 19:17:44 -04:00
_hil . Bearth = R * _hil . Bearth ;
}
/*
set the type of motor compensation to use
*/
void Compass : : motor_compensation_type ( const uint8_t comp_type )
{
if ( _motor_comp_type < = AP_COMPASS_MOT_COMP_CURRENT & & _motor_comp_type ! = ( int8_t ) comp_type ) {
_motor_comp_type = ( int8_t ) comp_type ;
_thr_or_curr = 0 ; // set current current or throttle to zero
for ( uint8_t i = 0 ; i < COMPASS_MAX_INSTANCES ; i + + ) {
set_motor_compensation ( i , Vector3f ( 0 , 0 , 0 ) ) ; // clear out invalid compensation vectors
}
}
2014-11-15 21:58:23 -04:00
}
2015-08-14 21:27:23 -03:00
2015-09-15 03:54:26 -03:00
bool Compass : : consistent ( ) const
2015-08-14 21:27:23 -03:00
{
2015-09-28 16:56:49 -03:00
Vector3f primary_mag_field = get_field ( ) ;
2015-08-14 21:27:23 -03:00
Vector3f primary_mag_field_norm ;
2015-09-15 03:54:26 -03:00
if ( ! primary_mag_field . is_zero ( ) ) {
primary_mag_field_norm = primary_mag_field . normalized ( ) ;
2015-08-14 21:27:23 -03:00
} else {
return false ;
}
Vector2f primary_mag_field_xy = Vector2f ( primary_mag_field . x , primary_mag_field . y ) ;
Vector2f primary_mag_field_xy_norm ;
2015-09-15 03:54:26 -03:00
if ( ! primary_mag_field_xy . is_zero ( ) ) {
primary_mag_field_xy_norm = primary_mag_field_xy . normalized ( ) ;
2015-08-14 21:27:23 -03:00
} else {
return false ;
}
2015-09-15 03:54:26 -03:00
for ( uint8_t i = 0 ; i < get_count ( ) ; i + + ) {
if ( use_for_yaw ( i ) ) {
2015-09-28 16:56:49 -03:00
Vector3f mag_field = get_field ( i ) ;
2015-08-14 21:27:23 -03:00
Vector3f mag_field_norm ;
2015-09-15 03:54:26 -03:00
if ( ! mag_field . is_zero ( ) ) {
mag_field_norm = mag_field . normalized ( ) ;
2015-08-14 21:27:23 -03:00
} else {
return false ;
}
Vector2f mag_field_xy = Vector2f ( mag_field . x , mag_field . y ) ;
Vector2f mag_field_xy_norm ;
2015-09-15 03:54:26 -03:00
if ( ! mag_field_xy . is_zero ( ) ) {
mag_field_xy_norm = mag_field_xy . normalized ( ) ;
2015-08-14 21:27:23 -03:00
} else {
return false ;
}
float xyz_ang_diff = acosf ( constrain_float ( mag_field_norm * primary_mag_field_norm , - 1.0f , 1.0f ) ) ;
float xy_ang_diff = acosf ( constrain_float ( mag_field_xy_norm * primary_mag_field_xy_norm , - 1.0f , 1.0f ) ) ;
float xy_len_diff = ( primary_mag_field_xy - mag_field_xy ) . length ( ) ;
// check for gross misalignment on all axes
bool xyz_ang_diff_large = xyz_ang_diff > AP_COMPASS_MAX_XYZ_ANG_DIFF ;
// check for an unacceptable angle difference on the xy plane
bool xy_ang_diff_large = xy_ang_diff > AP_COMPASS_MAX_XY_ANG_DIFF ;
// check for an unacceptable length difference on the xy plane
bool xy_length_diff_large = xy_len_diff > AP_COMPASS_MAX_XY_LENGTH_DIFF ;
// check for inconsistency in the XY plane
if ( xyz_ang_diff_large | | xy_ang_diff_large | | xy_length_diff_large ) {
return false ;
}
}
}
return true ;
}
2015-09-15 03:54:26 -03:00