From 1f714ed75d1197498ad7993f9a1eef2690b2db3c Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 26 Jan 2016 18:18:57 -0800 Subject: [PATCH] SITL: handle negative throttle - negative throttle was causing negative offsets --- libraries/SITL/SIM_Aircraft.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index fb24a9c119..96ab199d4c 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -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); } /*