From 32a9ba0c91d3294c108d25e49ca7e4e4e0b3fb95 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 7 Sep 2021 16:01:04 +0930 Subject: [PATCH] AC_AttitudeControl: AC_PosControl: Change set_correction_speed_accel_z to use input arguments --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 6227cbd706..2632e29f6d 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -727,7 +727,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.