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:
Andrew Tridgell 2013-09-02 09:44:52 +10:00
parent 6c2f623df2
commit f5d20b4085

View File

@ -97,9 +97,11 @@ void SITL_State::_update_ins(float roll, float pitch, float yaw, // Relative
rollRate, pitchRate, yawRate, rollRate, pitchRate, yawRate,
&p, &q, &r); &p, &q, &r);
// minimum noise levels are 2 bits // minimum noise levels are 2 bits, but averaged over many
float accel_noise = 0.1; // samples, giving around 0.01 m/s/s
float gyro_noise = ToRad(0.4); float accel_noise = 0.01;
// minimum gyro noise is also less than 1 bit
float gyro_noise = ToRad(0.04);
if (_motors_on) { if (_motors_on) {
// add extra noise when the motors are on // add extra noise when the motors are on
accel_noise += _sitl->accel_noise; accel_noise += _sitl->accel_noise;