mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: support Control: Refactor to use Jerk
This commit is contained in:
parent
eff91e87ca
commit
eb652b71f9
|
@ -465,8 +465,7 @@ bool AC_WPNav::advance_wp_target_along_track(float dt)
|
||||||
update_vel_accel(_terain_vel, _terain_accel, dt, false);
|
update_vel_accel(_terain_vel, _terain_accel, dt, false);
|
||||||
shape_vel_accel( _wp_desired_speed_xy_cms * offset_z_scaler, 0.0,
|
shape_vel_accel( _wp_desired_speed_xy_cms * offset_z_scaler, 0.0,
|
||||||
_terain_vel, _terain_accel,
|
_terain_vel, _terain_accel,
|
||||||
0.0, _wp_desired_speed_xy_cms,
|
-_wp_accel_cmss, _wp_accel_cmss, _pos_control.get_shaping_jerk_xy_cmsss(), dt, true);
|
||||||
-_wp_accel_cmss, _wp_accel_cmss, _pos_control.get_shaping_tc_xy_s(), dt);
|
|
||||||
vel_time_scalar = _terain_vel / _wp_desired_speed_xy_cms;
|
vel_time_scalar = _terain_vel / _wp_desired_speed_xy_cms;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue