From 429e8d5e50c3c2096e4fb922b0aa8fcf1385bc0f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 19 Feb 2014 17:05:53 +0900 Subject: [PATCH] Copter: integrate AttControl feel param --- ArduCopter/control_stabilize.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_stabilize.pde b/ArduCopter/control_stabilize.pde index b9e9ac544e..7b928435a3 100644 --- a/ArduCopter/control_stabilize.pde +++ b/ArduCopter/control_stabilize.pde @@ -51,7 +51,7 @@ static void stabilize_run() attitude_control.init_targets(); }else{ // call attitude controller - attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate); + attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, g.rc_feel_rp); // body-frame rate controller is run directly from 100hz loop }