mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: pass dt to avoidance
This commit is contained in:
parent
f48b14b810
commit
094620bc8a
|
@ -302,7 +302,7 @@ void AC_WPNav::calc_loiter_desired_velocity(float nav_dt, float ekfGndSpdLimit)
|
|||
|
||||
// Limit the velocity to prevent fence violations
|
||||
if (_avoid != nullptr) {
|
||||
_avoid->adjust_velocity(_pos_control.get_pos_xy_kP(), _loiter_accel_cmss, desired_vel);
|
||||
_avoid->adjust_velocity(_pos_control.get_pos_xy_kP(), _loiter_accel_cmss, desired_vel, nav_dt);
|
||||
}
|
||||
|
||||
// send adjusted feed forward velocity back to position controller
|
||||
|
|
Loading…
Reference in New Issue