Browse Source

AC_AttitudeControl: AC_PosControl: Change set_correction_speed_accel_z to use input arguments

c415-sdk
Leonard Hall 3 years ago committed by Randy Mackay
parent
commit
e80b0355b8
  1. 2
      libraries/AC_AttitudeControl/AC_PosControl.cpp

2
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 @@ -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.

Loading…
Cancel
Save