SITL: add SIM_VIB_MOT_MULT to allow motor noise to have a different amplitude to the fixed frequency noise
This commit is contained in:
parent
c0c61660b0
commit
2033cf3b4a
@ -208,6 +208,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||
AP_GROUPINFO("VIB_MOT_MAX", 61, SITL, vibe_motor, 0.0f),
|
||||
// minimum throttle for simulated ins noise
|
||||
AP_GROUPINFO("INS_THR_MIN", 62, SITL, ins_noise_throttle_min, 0.1f),
|
||||
// amplitude scaling of motor noise relative to gyro/accel noise
|
||||
AP_GROUPINFO("VIB_MOT_MULT", 63, SITL, vibe_motor_scale, 1.0f),
|
||||
|
||||
AP_GROUPEND
|
||||
|
||||
|
@ -251,6 +251,8 @@ public:
|
||||
|
||||
// max frequency to use as baseline for adding motor noise for the gyros and accels
|
||||
AP_Float vibe_motor;
|
||||
// amplitude scaling of motor noise relative to gyro/accel noise
|
||||
AP_Float vibe_motor_scale;
|
||||
// minimum throttle for addition of ins noise
|
||||
AP_Float ins_noise_throttle_min;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user