mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-08 20:09:13 +08:00
Sub: replace smoothing gain with AC_AttitudeControl::set_input_tc
This commit is contained in:
@@ -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
|
||||
|
||||
Reference in New Issue
Block a user