From 226290158bc3f1373777b400ad701e157131b827 Mon Sep 17 00:00:00 2001 From: Gustavo Jose de Sousa Date: Wed, 28 Sep 2016 16:11:14 -0300 Subject: [PATCH] Tools: sitl_calibration: fix PWM values for angular velocity --- Tools/mavproxy_modules/sitl_calibration.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/mavproxy_modules/sitl_calibration.py b/Tools/mavproxy_modules/sitl_calibration.py index b7c04ad5d9..ebc0c24894 100644 --- a/Tools/mavproxy_modules/sitl_calibration.py +++ b/Tools/mavproxy_modules/sitl_calibration.py @@ -89,7 +89,7 @@ class CalController(object): theta = 0 elif theta > max_theta: theta = max_theta - theta_pwm = 1200 + round((theta / max_theta) * 800) + theta_pwm = 1300 + round((theta / max_theta) * 700) self.mpstate.functions.process_stdin('servo set 5 %d' % theta_pwm) self.mpstate.functions.process_stdin('servo set 6 %d' % x_pwm)