SITL: add descriptions for simulated IMU scale factors

This commit is contained in:
Peter Barker 2023-08-07 10:16:25 +10:00 committed by Peter Barker
parent 44c5754e36
commit 65cc16c51d
1 changed files with 43 additions and 0 deletions

View File

@ -607,11 +607,24 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
#if INS_MAX_INSTANCES > 2
AP_GROUPINFO("ACC3_RND", 13, SIM, accel_noise[2], 0),
#endif
// @Param: GYR1_SCALE
// @DisplayName: Gyro 1 scaling factor
// @Description: scaling factors applied to simulated gyroscope
// @User: Advanced
// @Vector3Parameter: 1
AP_GROUPINFO("GYR1_SCALE", 14, SIM, gyro_scale[0], 0),
#if INS_MAX_INSTANCES > 1
// @Param: GYR2_SCALE
// @DisplayName: Gyro 2 scaling factor
// @CopyFieldsFrom: SIM_GYR1_SCALE
// @Vector3Parameter: 1
AP_GROUPINFO("GYR2_SCALE", 15, SIM, gyro_scale[1], 0),
#endif
#if INS_MAX_INSTANCES > 2
// @Param: GYR3_SCALE
// @DisplayName: Gyro 3 scaling factor
// @CopyFieldsFrom: SIM_GYR1_SCALE
// @Vector3Parameter: 1
AP_GROUPINFO("GYR3_SCALE", 16, SIM, gyro_scale[2], 0),
#endif
// @Param: ACCEL1_FAIL
@ -648,11 +661,25 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
// @Values: 0:Disabled, 1:Readings stopped
// @User: Advanced
AP_GROUPINFO("ACC_FAIL_MSK", 21, SIM, accel_fail_mask, 0),
// @Param: ACC1_SCAL
// @DisplayName: Accel 1 scaling factor
// @Description: scaling factors applied to simulated accelerometer
// @User: Advanced
// @Vector3Parameter: 1
AP_GROUPINFO("ACC1_SCAL", 22, SIM, accel_scale[0], 0),
#if INS_MAX_INSTANCES > 1
// @Param: ACC2_SCAL
// @DisplayName: Accel 2 scaling factor
// @CopyFieldsFrom: SIM_ACC1_SCAL
// @Vector3Parameter: 1
AP_GROUPINFO("ACC2_SCAL", 23, SIM, accel_scale[1], 0),
#endif
#if INS_MAX_INSTANCES > 2
// @Param: ACC3_SCAL
// @DisplayName: Accel 3 scaling factor
// @CopyFieldsFrom: SIM_ACC1_SCAL
// @Vector3Parameter: 1
AP_GROUPINFO("ACC3_SCAL", 24, SIM, accel_scale[2], 0),
#endif
AP_GROUPINFO("ACC_TRIM", 25, SIM, accel_trim, 0),
@ -736,6 +763,10 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
#endif
#if INS_MAX_INSTANCES > 3
// @Param: ACC4_SCAL
// @DisplayName: Accel 4 scaling factor
// @CopyFieldsFrom: SIM_ACC1_SCAL
// @Vector3Parameter: 1
AP_GROUPINFO("ACC4_SCAL", 34, SIM, accel_scale[3], 0),
// @Param: ACCEL4_FAIL
@ -745,6 +776,10 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
// @User: Advanced
AP_GROUPINFO("ACCEL4_FAIL", 35, SIM, accel_fail[3], 0),
// @Param: GYR4_SCALE
// @DisplayName: Gyro 4 scaling factor
// @CopyFieldsFrom: SIM_GYR1_SCALE
// @Vector3Parameter: 1
AP_GROUPINFO("GYR4_SCALE", 36, SIM, gyro_scale[3], 0),
AP_GROUPINFO("ACC4_RND", 37, SIM, accel_noise[3], 0),
@ -773,6 +808,10 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
#endif
#if INS_MAX_INSTANCES > 4
// @Param: ACC5_SCAL
// @DisplayName: Accel 4 scaling factor
// @CopyFieldsFrom: SIM_ACC1_SCAL
// @Vector3Parameter: 1
AP_GROUPINFO("ACC5_SCAL", 41, SIM, accel_scale[4], 0),
@ -783,6 +822,10 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
// @User: Advanced
AP_GROUPINFO("ACCEL5_FAIL", 42, SIM, accel_fail[4], 0),
// @Param: GYR5_SCALE
// @DisplayName: Gyro 5 scaling factor
// @CopyFieldsFrom: SIM_GYR1_SCALE
// @Vector3Parameter: 1
AP_GROUPINFO("GYR5_SCALE", 43, SIM, gyro_scale[4], 0),
AP_GROUPINFO("ACC5_RND", 44, SIM, accel_noise[4], 0),