From d4998089c8d19c227d0ce93c1ecedeada638ebbe Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 3 Feb 2016 10:26:46 +0900 Subject: [PATCH] AP_Motors: example sketch provides roll, pitch, yaw in -1 to +1 range --- .../AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index d7fda15190..b0c7a4d6bd 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -156,9 +156,9 @@ void stability_test() pitch_in = rpy_tests[p]; yaw_in = rpy_tests[y]; throttle_in = throttle_tests[t]/1000.0f; - motors.set_pitch(roll_in); - motors.set_roll(pitch_in); - motors.set_yaw(yaw_in); + motors.set_pitch(roll_in/4500.0f); + motors.set_roll(pitch_in/4500.0f); + motors.set_yaw(yaw_in/4500.0f); motors.set_throttle(throttle_in); motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); #if HELI_TEST == 0