Sub: replace smoothing gain with AC_AttitudeControl::set_input_tc

This commit is contained in:
Randy Mackay
2017-07-10 11:49:42 +09:00
parent a727305a59
commit da17034a3d
10 changed files with 27 additions and 51 deletions

View File

@@ -78,9 +78,9 @@ void Sub::circle_run()
// call attitude controller
if (circle_pilot_yaw_override) {
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate, get_smoothing_gain());
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
} else {
attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), circle_nav.get_yaw(), true, get_smoothing_gain());
attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), circle_nav.get_yaw(), true);
}
// adjust climb rate using rangefinder