mirror of https://github.com/ArduPilot/ardupilot
AC_PosControl: pass dt to att control sqrt_controller
This commit is contained in:
parent
62cc25022c
commit
b9ed8b292a
|
@ -378,7 +378,7 @@ void AC_PosControl::pos_to_rate_z()
|
|||
}
|
||||
|
||||
// calculate _vel_target.z using from _pos_error.z using sqrt controller
|
||||
_vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms);
|
||||
_vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_pos_z.kP(), _accel_z_cms, _dt);
|
||||
|
||||
// check speed limits
|
||||
// To-Do: check these speed limits here or in the pos->rate controller
|
||||
|
|
Loading…
Reference in New Issue