From d66a980be3cc961324e4f25d47be770fbdb83ec4 Mon Sep 17 00:00:00 2001 From: bnsgeyer Date: Sun, 29 Oct 2017 00:24:48 -0400 Subject: [PATCH] AP_Motors: TradHeli - fixed servo test function --- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 378fcf74ff..5776754c0a 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -520,11 +520,11 @@ void AP_MotorsHeli_Single::servo_test() _oscillate_angle += 8 * M_PI / _loop_rate; _yaw_test = 0.5f * sinf(_oscillate_angle); } else if (_servo_test_cycle_time >= 5.0f && _servo_test_cycle_time < 6.0f){ // Raise swash to top - _collective_test += (1.0f / _loop_rate); + _collective_test = 1.0f; _oscillate_angle += 2 * M_PI / _loop_rate; _yaw_test = sinf(_oscillate_angle); } else if (_servo_test_cycle_time >= 11.0f && _servo_test_cycle_time < 12.0f){ // Lower swash to bottom - _collective_test -= (1.0f / _loop_rate); + _collective_test = 0.0f; _oscillate_angle += 2 * M_PI / _loop_rate; _yaw_test = sinf(_oscillate_angle); } else { // reset cycle @@ -541,7 +541,7 @@ void AP_MotorsHeli_Single::servo_test() } // over-ride servo commands to move servos through defined ranges - _throttle_in = _collective_test; + _throttle_filter.reset(_collective_test); _roll_in = _roll_test; _pitch_in = _pitch_test; _yaw_in = _yaw_test;