mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_WPNav: resolve twitch when passing spline waypoints
The target positions target velocity was being reset to zero as we passed through a spline waypoint.
This commit is contained in:
parent
e836d1aa2b
commit
1c6606cc58
@ -695,7 +695,7 @@ void AC_WPNav::set_spline_origin_and_destination(const Vector3f& origin, const V
|
||||
// before beginning it's spline path to the next waypoint. Note: we are using the previous segment's origin and destination
|
||||
_spline_origin_vel = (_destination - _origin);
|
||||
_spline_time = 0.0f; // To-Do: this should be set based on how much overrun there was from straight segment?
|
||||
_spline_vel_scaler = 0.0f; // To-Do: this should be set based on speed at end of prev straight segment?
|
||||
_spline_vel_scaler = _pos_control.get_vel_target().length(); // start velocity target from current target velocity
|
||||
}else{
|
||||
// previous segment is splined, vehicle will fly through origin
|
||||
// we can use the previous segment's destination velocity as this segment's origin velocity
|
||||
@ -707,7 +707,7 @@ void AC_WPNav::set_spline_origin_and_destination(const Vector3f& origin, const V
|
||||
}else{
|
||||
_spline_time = 0.0f;
|
||||
}
|
||||
_spline_vel_scaler = 0.0f;
|
||||
// Note: we leave _spline_vel_scaler as it was from end of previous segment
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user