Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AC_PosControl: Include FF in _pid_vel_xy integrator initialisation #22506

Merged
merged 1 commit into from
Dec 27, 2022
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 1 addition & 3 deletions libraries/AC_AttitudeControl/AC_PosControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -448,8 +448,6 @@ void AC_PosControl::init_xy_controller_stopping_point()
get_stopping_point_xy_cm(_pos_target.xy());
_vel_desired.xy().zero();
_accel_desired.xy().zero();

_pid_vel_xy.set_integrator(_accel_target);
}

// relax_velocity_controller_xy - initialise the position controller to the current position and velocity with decaying acceleration.
Expand Down Expand Up @@ -513,7 +511,7 @@ void AC_PosControl::init_xy_controller()
_pid_vel_xy.reset_filter();
// initialise the I term to _accel_target - _accel_desired
// _accel_desired is zero and can be removed from the equation
_pid_vel_xy.set_integrator(_accel_target);
_pid_vel_xy.set_integrator(_accel_target.xy() - _vel_target.xy() * _pid_vel_xy.ff());

// initialise ekf xy reset handler
init_ekf_xy_reset();
Expand Down