AC_PosControl: pass dt to att control sqrt_controller

This commit is contained in:
Leonard Hall 2017-11-16 21:29:29 +09:00 committed by Randy Mackay
parent 62cc25022c
commit b9ed8b292a
1 changed files with 1 additions and 1 deletions

View File

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