SITL: handle negative throttle

- negative throttle was causing negative offsets
This commit is contained in:
Tom Pittenger 2016-01-26 18:18:57 -08:00 committed by Andrew Tridgell
parent f695f37ca3
commit 1f714ed75d

View File

@ -218,10 +218,10 @@ void Aircraft::add_noise(float throttle)
{
gyro += Vector3f(rand_normal(0, 1),
rand_normal(0, 1),
rand_normal(0, 1)) * gyro_noise * throttle;
rand_normal(0, 1)) * gyro_noise * fabsf(throttle);
accel_body += Vector3f(rand_normal(0, 1),
rand_normal(0, 1),
rand_normal(0, 1)) * accel_noise * throttle;
rand_normal(0, 1)) * accel_noise * fabsf(throttle);
}
/*