Browse Source

SITL: handle negative throttle

- negative throttle was causing negative offsets
master
Tom Pittenger 9 years ago committed by Andrew Tridgell
parent
commit
1f714ed75d
  1. 4
      libraries/SITL/SIM_Aircraft.cpp

4
libraries/SITL/SIM_Aircraft.cpp

@ -218,10 +218,10 @@ void Aircraft::add_noise(float throttle) @@ -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);
}
/*

Loading…
Cancel
Save