mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
SITL: reduce the minimum accel and gyro noise
on APM2 and PX4 we do a lot of smoothing of accels and gyros, so a 2 bit error isn't a good representation of the min noise
This commit is contained in:
parent
6c2f623df2
commit
f5d20b4085
@ -97,9 +97,11 @@ void SITL_State::_update_ins(float roll, float pitch, float yaw, // Relative
|
||||
rollRate, pitchRate, yawRate,
|
||||
&p, &q, &r);
|
||||
|
||||
// minimum noise levels are 2 bits
|
||||
float accel_noise = 0.1;
|
||||
float gyro_noise = ToRad(0.4);
|
||||
// minimum noise levels are 2 bits, but averaged over many
|
||||
// samples, giving around 0.01 m/s/s
|
||||
float accel_noise = 0.01;
|
||||
// minimum gyro noise is also less than 1 bit
|
||||
float gyro_noise = ToRad(0.04);
|
||||
if (_motors_on) {
|
||||
// add extra noise when the motors are on
|
||||
accel_noise += _sitl->accel_noise;
|
||||
|
Loading…
Reference in New Issue
Block a user