mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
SITL: added accel scaling parameters
This commit is contained in:
parent
3e640eed80
commit
9febcc0f98
@ -362,30 +362,35 @@ const AP_Param::GroupInfo SITL::var_sfml_joystick[] = {
|
||||
|
||||
// INS SITL parameters
|
||||
const AP_Param::GroupInfo SITL::var_ins[] = {
|
||||
AP_GROUPINFO("IMUT_START", 1, SITL, imu_temp_start, 25),
|
||||
AP_GROUPINFO("IMUT_END", 2, SITL, imu_temp_end, 45),
|
||||
AP_GROUPINFO("IMUT_TCONST", 3, SITL, imu_temp_tconst, 300),
|
||||
AP_GROUPINFO("IMUT_FIXED", 4, SITL, imu_temp_fixed, 0),
|
||||
AP_SUBGROUPINFO(imu_tcal[0], "IMUT1_", 5, SITL, AP_InertialSensor::TCal),
|
||||
AP_SUBGROUPINFO(imu_tcal[1], "IMUT2_", 6, SITL, AP_InertialSensor::TCal),
|
||||
AP_SUBGROUPINFO(imu_tcal[2], "IMUT3_", 7, SITL, AP_InertialSensor::TCal),
|
||||
AP_GROUPINFO("ACC1_BIAS", 8, SITL, accel_bias[0], 0),
|
||||
AP_GROUPINFO("ACC2_BIAS", 9, SITL, accel_bias[1], 0),
|
||||
AP_GROUPINFO("ACC3_BIAS", 10, SITL, accel_bias[2], 0),
|
||||
AP_GROUPINFO("GYR1_RND", 11, SITL, gyro_noise[0], 0),
|
||||
AP_GROUPINFO("GYR2_RND", 12, SITL, gyro_noise[1], 0),
|
||||
AP_GROUPINFO("GYR3_RND", 13, SITL, gyro_noise[2], 0),
|
||||
AP_GROUPINFO("ACC1_RND", 14, SITL, accel_noise[0], 0),
|
||||
AP_GROUPINFO("ACC2_RND", 15, SITL, accel_noise[1], 0),
|
||||
AP_GROUPINFO("ACC3_RND", 16, SITL, accel_noise[2], 0),
|
||||
AP_GROUPINFO("GYR1_SCALE", 17, SITL, gyro_scale[0], 0),
|
||||
AP_GROUPINFO("GYR2_SCALE", 18, SITL, gyro_scale[1], 0),
|
||||
AP_GROUPINFO("GYR3_SCALE", 19, SITL, gyro_scale[2], 0),
|
||||
AP_GROUPINFO("ACCEL1_FAIL", 20, SITL, accel_fail[0], 0),
|
||||
AP_GROUPINFO("ACCEL2_FAIL", 21, SITL, accel_fail[1], 0),
|
||||
AP_GROUPINFO("ACCEL3_FAIL", 22, SITL, accel_fail[2], 0),
|
||||
AP_GROUPINFO("GYR_FAIL_MSK", 23, SITL, gyro_fail_mask, 0),
|
||||
AP_GROUPINFO("ACC_FAIL_MSK", 24, SITL, accel_fail_mask, 0),
|
||||
AP_GROUPINFO("IMUT_START", 1, SITL, imu_temp_start, 25),
|
||||
AP_GROUPINFO("IMUT_END", 2, SITL, imu_temp_end, 45),
|
||||
AP_GROUPINFO("IMUT_TCONST", 3, SITL, imu_temp_tconst, 300),
|
||||
AP_GROUPINFO("IMUT_FIXED", 4, SITL, imu_temp_fixed, 0),
|
||||
AP_GROUPINFO("ACC1_BIAS", 5, SITL, accel_bias[0], 0),
|
||||
AP_GROUPINFO("ACC2_BIAS", 6, SITL, accel_bias[1], 0),
|
||||
AP_GROUPINFO("ACC3_BIAS", 7, SITL, accel_bias[2], 0),
|
||||
AP_GROUPINFO("GYR1_RND", 8, SITL, gyro_noise[0], 0),
|
||||
AP_GROUPINFO("GYR2_RND", 9, SITL, gyro_noise[1], 0),
|
||||
AP_GROUPINFO("GYR3_RND", 10, SITL, gyro_noise[2], 0),
|
||||
AP_GROUPINFO("ACC1_RND", 11, SITL, accel_noise[0], 0),
|
||||
AP_GROUPINFO("ACC2_RND", 12, SITL, accel_noise[1], 0),
|
||||
AP_GROUPINFO("ACC3_RND", 13, SITL, accel_noise[2], 0),
|
||||
AP_GROUPINFO("GYR1_SCALE", 14, SITL, gyro_scale[0], 0),
|
||||
AP_GROUPINFO("GYR2_SCALE", 15, SITL, gyro_scale[1], 0),
|
||||
AP_GROUPINFO("GYR3_SCALE", 16, SITL, gyro_scale[2], 0),
|
||||
AP_GROUPINFO("ACCEL1_FAIL", 17, SITL, accel_fail[0], 0),
|
||||
AP_GROUPINFO("ACCEL2_FAIL", 18, SITL, accel_fail[1], 0),
|
||||
AP_GROUPINFO("ACCEL3_FAIL", 19, SITL, accel_fail[2], 0),
|
||||
AP_GROUPINFO("GYR_FAIL_MSK", 20, SITL, gyro_fail_mask, 0),
|
||||
AP_GROUPINFO("ACC_FAIL_MSK", 21, SITL, accel_fail_mask, 0),
|
||||
AP_GROUPINFO("ACC1_SCAL", 22, SITL, accel_scale[0], 0),
|
||||
AP_GROUPINFO("ACC2_SCAL", 23, SITL, accel_scale[1], 0),
|
||||
AP_GROUPINFO("ACC3_SCAL", 24, SITL, accel_scale[2], 0),
|
||||
|
||||
// the IMUT parameters must be last due to the enable parameters
|
||||
AP_SUBGROUPINFO(imu_tcal[0], "IMUT1_", 61, SITL, AP_InertialSensor::TCal),
|
||||
AP_SUBGROUPINFO(imu_tcal[1], "IMUT2_", 62, SITL, AP_InertialSensor::TCal),
|
||||
AP_SUBGROUPINFO(imu_tcal[2], "IMUT3_", 63, SITL, AP_InertialSensor::TCal),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -449,6 +449,7 @@ public:
|
||||
AP_Vector3f gyro_scale[INS_MAX_INSTANCES]; // percentage
|
||||
AP_Float accel_noise[INS_MAX_INSTANCES]; // in m/s/s
|
||||
AP_Vector3f accel_bias[INS_MAX_INSTANCES]; // in m/s/s
|
||||
AP_Vector3f accel_scale[INS_MAX_INSTANCES]; // in m/s/s
|
||||
AP_Float accel_fail[INS_MAX_INSTANCES]; // accelerometer failure value
|
||||
// gyro and accel fail masks
|
||||
AP_Int8 gyro_fail_mask;
|
||||
|
Loading…
Reference in New Issue
Block a user