AP_Compass: Also mark Z axis as calibrations, just like the XY

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2024-10-25 15:59:44 +02:00 committed by Andrew Tridgell
parent 909b48b770
commit 6a59d3adae
1 changed files with 12 additions and 0 deletions

View File

@ -99,6 +99,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Units: mGauss // @Units: mGauss
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("OFS", 1, Compass, _state._priv_instance[0].offset, 0), AP_GROUPINFO("OFS", 1, Compass, _state._priv_instance[0].offset, 0),
// @Param: DEC // @Param: DEC
@ -170,6 +171,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Units: mGauss/A // @Units: mGauss/A
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("MOT", 7, Compass, _state._priv_instance[0].motor_compensation, 0), AP_GROUPINFO("MOT", 7, Compass, _state._priv_instance[0].motor_compensation, 0),
#endif #endif
@ -215,6 +217,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Units: mGauss // @Units: mGauss
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("OFS2", 10, Compass, _state._priv_instance[1].offset, 0), AP_GROUPINFO("OFS2", 10, Compass, _state._priv_instance[1].offset, 0),
// @Param: MOT2_X // @Param: MOT2_X
@ -242,6 +245,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Units: mGauss/A // @Units: mGauss/A
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("MOT2", 11, Compass, _state._priv_instance[1].motor_compensation, 0), AP_GROUPINFO("MOT2", 11, Compass, _state._priv_instance[1].motor_compensation, 0),
#endif // COMPASS_MAX_INSTANCES #endif // COMPASS_MAX_INSTANCES
@ -272,6 +276,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Units: mGauss // @Units: mGauss
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("OFS3", 13, Compass, _state._priv_instance[2].offset, 0), AP_GROUPINFO("OFS3", 13, Compass, _state._priv_instance[2].offset, 0),
// @Param: MOT3_X // @Param: MOT3_X
@ -299,6 +304,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @Units: mGauss/A // @Units: mGauss/A
// @Increment: 1 // @Increment: 1
// @User: Advanced // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("MOT3", 14, Compass, _state._priv_instance[2].motor_compensation, 0), AP_GROUPINFO("MOT3", 14, Compass, _state._priv_instance[2].motor_compensation, 0),
#endif // COMPASS_MAX_INSTANCES #endif // COMPASS_MAX_INSTANCES
@ -390,6 +396,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass soft-iron diagonal Z component // @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]] // @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 // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("DIA", 24, Compass, _state._priv_instance[0].diagonals, 1.0), AP_GROUPINFO("DIA", 24, Compass, _state._priv_instance[0].diagonals, 1.0),
// @Param: ODI_X // @Param: ODI_X
@ -408,6 +415,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass soft-iron off-diagonal Z component // @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]] // @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 // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("ODI", 25, Compass, _state._priv_instance[0].offdiagonals, 0), AP_GROUPINFO("ODI", 25, Compass, _state._priv_instance[0].offdiagonals, 0),
#if COMPASS_MAX_INSTANCES > 1 #if COMPASS_MAX_INSTANCES > 1
@ -427,6 +435,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass2 soft-iron diagonal Z component // @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]] // @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 // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("DIA2", 26, Compass, _state._priv_instance[1].diagonals, 1.0), AP_GROUPINFO("DIA2", 26, Compass, _state._priv_instance[1].diagonals, 1.0),
// @Param: ODI2_X // @Param: ODI2_X
@ -445,6 +454,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass2 soft-iron off-diagonal Z component // @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]] // @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 // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("ODI2", 27, Compass, _state._priv_instance[1].offdiagonals, 0), AP_GROUPINFO("ODI2", 27, Compass, _state._priv_instance[1].offdiagonals, 0),
#endif // COMPASS_MAX_INSTANCES #endif // COMPASS_MAX_INSTANCES
@ -465,6 +475,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass3 soft-iron diagonal Z component // @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]] // @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 // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("DIA3", 28, Compass, _state._priv_instance[2].diagonals, 1.0), AP_GROUPINFO("DIA3", 28, Compass, _state._priv_instance[2].diagonals, 1.0),
// @Param: ODI3_X // @Param: ODI3_X
@ -483,6 +494,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass3 soft-iron off-diagonal Z component // @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]] // @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 // @User: Advanced
// @Calibration: 1
AP_GROUPINFO("ODI3", 29, Compass, _state._priv_instance[2].offdiagonals, 0), AP_GROUPINFO("ODI3", 29, Compass, _state._priv_instance[2].offdiagonals, 0),
#endif // COMPASS_MAX_INSTANCES #endif // COMPASS_MAX_INSTANCES
#endif // AP_COMPASS_DIAGONALS_ENABLED #endif // AP_COMPASS_DIAGONALS_ENABLED