diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index d87ac336df5cc2d896b4730a2eb797e92737dccc..b6dc7dbd2e59299001294e4e524ddc2b1325ee2a 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -648,7 +648,7 @@ static AP_InertialNav inertial_nav(ahrs, barometer, gps_glitch, baro_glitch);
 ////////////////////////////////////////////////////////////////////////////////
 #if FRAME_CONFIG == HELI_FRAME
 AC_AttitudeControl_Heli attitude_control(ahrs, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw,
-                        g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw, g.rc_1, g.rc_2);
+                        g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);
 #else
 AC_AttitudeControl attitude_control(ahrs, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw,
                         g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);