|
|
|
@ -353,6 +353,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
@@ -353,6 +353,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
|
|
|
|
AP_GROUPINFO("EXTERN3",23, Compass, _state._priv_instance[2].external, 0), |
|
|
|
|
#endif // COMPASS_MAX_INSTANCES
|
|
|
|
|
|
|
|
|
|
#ifndef HAL_BUILD_AP_PERIPH |
|
|
|
|
// @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]]
|
|
|
|
@ -388,6 +389,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
@@ -388,6 +389,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
|
|
|
|
// @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), |
|
|
|
|
#endif // HAL_BUILD_AP_PERIPH
|
|
|
|
|
|
|
|
|
|
#if COMPASS_MAX_INSTANCES > 1 |
|
|
|
|
// @Param: DIA2_X
|
|
|
|
@ -476,6 +478,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
@@ -476,6 +478,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
|
|
|
|
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
|
|
|
|
@ -483,6 +486,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
@@ -483,6 +486,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
|
|
|
|
// @Increment: 1
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("OFFS_MAX", 31, Compass, _offset_max, AP_COMPASS_OFFSETS_MAX_DEFAULT), |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if COMPASS_MOT_ENABLED |
|
|
|
|
// @Group: PMOT
|
|
|
|
@ -545,6 +549,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
@@ -545,6 +549,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
|
|
|
|
// @Values: 0:Disabled,1:Enabled
|
|
|
|
|
AP_GROUPINFO("ENABLE", 39, Compass, _enabled, 1), |
|
|
|
|
|
|
|
|
|
#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
|
|
|
|
@ -569,6 +574,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
@@ -569,6 +574,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
|
|
|
|
// @Range: 0 1.3
|
|
|
|
|
AP_GROUPINFO("SCALE3", 42, Compass, _state._priv_instance[2].scale_factor, 0), |
|
|
|
|
#endif |
|
|
|
|
#endif // HAL_BUILD_AP_PERIPH
|
|
|
|
|
|
|
|
|
|
// @Param: OPTIONS
|
|
|
|
|
// @DisplayName: Compass options
|
|
|
|
|