From 2cd6d986d5400a8c6804446908aefb6b3ebd9ccf Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Wed, 20 Aug 2014 22:14:48 +0900 Subject: [PATCH] TradHeli: call passthrough_bf_roll_pitch_rate_yaw --- ArduCopter/heli_control_acro.pde | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ArduCopter/heli_control_acro.pde b/ArduCopter/heli_control_acro.pde index 068569c4b..4f3feb8d1 100644 --- a/ArduCopter/heli_control_acro.pde +++ b/ArduCopter/heli_control_acro.pde @@ -39,14 +39,15 @@ static void heli_acro_run() if (!motors.has_flybar()){ // convert the input to the desired body frame rate get_pilot_desired_angle_rates(g.rc_1.control_in, g.rc_2.control_in, g.rc_4.control_in, target_roll, target_pitch, target_yaw); + // run attitude controller + attitude_control.rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw); }else{ // flybar helis only need yaw rate control get_pilot_desired_yaw_rate(g.rc_4.control_in, target_yaw); + // run attitude controller + attitude_control.passthrough_bf_roll_pitch_rate_yaw(g.rc_1.control_in, g.rc_2.control_in, target_yaw); } - // run attitude controller - attitude_control.rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw); - // output pilot's throttle without angle boost attitude_control.set_throttle_out(g.rc_3.control_in, false); } -- GitLab