Copter: integrate AttControl feel param

This commit is contained in:
Randy Mackay 2014-02-19 17:05:53 +09:00
parent 25ee5d5dc8
commit 429e8d5e50
1 changed files with 1 additions and 1 deletions

View File

@ -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
}