Browse Source

AP_Motors: Tradheli- fixes servo_test function for Dual Heli frame

mission-4.1.18
bnsgeyer 7 years ago committed by Randy Mackay
parent
commit
63bafa2c7f
  1. 6
      libraries/AP_Motors/AP_MotorsHeli_Dual.cpp

6
libraries/AP_Motors/AP_MotorsHeli_Dual.cpp

@ -562,10 +562,10 @@ void AP_MotorsHeli_Dual::servo_test() @@ -562,10 +562,10 @@ void AP_MotorsHeli_Dual::servo_test()
_pitch_test -= (1.0f / (_loop_rate/2));
_oscillate_angle += 8 * M_PI / _loop_rate;
} 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;
} 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;
} else { // reset cycle
_servo_test_cycle_time = 0.0f;
@ -581,7 +581,7 @@ void AP_MotorsHeli_Dual::servo_test() @@ -581,7 +581,7 @@ void AP_MotorsHeli_Dual::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;
}

Loading…
Cancel
Save