AC_AttitudeControl: AC_PosControl: Change set_correction_speed_accel_z to use input arguments

This commit is contained in:
Leonard Hall 2021-09-07 16:01:04 +09:30 committed by Randy Mackay
parent 7f092a8bd3
commit 8a1e452d3c
1 changed files with 1 additions and 1 deletions

View File

@ -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) 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 // 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. /// init_z_controller - initialise the position controller to the current position, velocity, acceleration and attitude.