Skip to content

Commit

Permalink
AC_AttitudeControl: AC_PosControl: Change set_correction_speed_accel_…
Browse files Browse the repository at this point in the history
…z to use input arguments
  • Loading branch information
lthall authored and rmackay9 committed Sep 7, 2021
1 parent fd75811 commit 35a93c5
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AC_AttitudeControl/AC_PosControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -712,7 +712,7 @@ void AC_PosControl::set_max_speed_accel_z(float speed_down, float speed_up, floa
void AC_PosControl::set_correction_speed_accel_z(float speed_down, float speed_up, float accel_cmss)
{
// define maximum position error and maximum first and second differential limits
_p_pos_z.set_limits(-fabsf(speed_down), _vel_max_up_cms, _accel_max_z_cmss, 0.0f);
_p_pos_z.set_limits(-fabsf(speed_down), speed_up, accel_cmss, 0.0f);
}

/// init_z_controller - initialise the position controller to the current position, velocity, acceleration and attitude.
Expand Down

0 comments on commit 35a93c5

Please sign in to comment.