diff --git a/ArduCopter/heli_control_acro.pde b/ArduCopter/heli_control_acro.pde index bcf2db951c..37cdbad83a 100644 --- a/ArduCopter/heli_control_acro.pde +++ b/ArduCopter/heli_control_acro.pde @@ -34,7 +34,7 @@ static void heli_acro_run() pilot_throttle_scaled = get_pilot_desired_throttle(g.rc_3.control_in); // run attitude controller - attitude_control.ratebf_rpy(target_roll, target_pitch, target_yaw); + 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(pilot_throttle_scaled, false); diff --git a/ArduCopter/heli_control_stabilize.pde b/ArduCopter/heli_control_stabilize.pde index 12e83d3082..7b66405c72 100644 --- a/ArduCopter/heli_control_stabilize.pde +++ b/ArduCopter/heli_control_stabilize.pde @@ -37,7 +37,7 @@ static void heli_stabilize_run() pilot_throttle_scaled = get_pilot_desired_throttle(g.rc_3.control_in); // call attitude controller - attitude_control.angleef_rp_rateef_y(target_roll, target_pitch, target_yaw_rate); + attitude_control.angle_ef_roll_pitch_rate_ef_yaw(target_roll, target_pitch, target_yaw_rate); // output pilot's throttle - note that TradHeli does not used angle-boost attitude_control.set_throttle_out(pilot_throttle_scaled, false);