From fc34a2fed1ae706e6a3c9a6305c50a512b428c64 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Sun, 13 Jul 2014 00:50:47 -0700 Subject: [PATCH] Copter: updated AttitudeControl ctor call to reflect changes --- ArduCopter/ArduCopter.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 687ad0eb40..f69a01ebea 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -634,10 +634,10 @@ static AP_InertialNav inertial_nav(ahrs, barometer, gps_glitch); // To-Do: move inertial nav up or other navigation variables down here //////////////////////////////////////////////////////////////////////////////// #if FRAME_CONFIG == HELI_FRAME -AC_AttitudeControl_Heli attitude_control(ahrs, ins, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw, +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); #else -AC_AttitudeControl attitude_control(ahrs, ins, aparm, motors, g.p_stabilize_roll, g.p_stabilize_pitch, g.p_stabilize_yaw, +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); #endif AC_PosControl pos_control(ahrs, inertial_nav, motors, attitude_control,