mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
SITL: handle negative throttle
- negative throttle was causing negative offsets
This commit is contained in:
parent
f695f37ca3
commit
1f714ed75d
@ -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…
Reference in New Issue
Block a user