This package provides classes to manage/manipulate Trajectory.
The interpolator class interpolates given bases
and values
. Following interpolators are implemented.
- Linear
- AkimaSpline
- CubicSpline
- NearestNeighbor
- Stairstep
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/overview/interpolators.drawio.svg") }})
The builder internally executes interpolation and return the result in the form of expected<T, E>
. If successful, it contains the interpolator object.
--8<--
common/autoware_trajectory/examples/example_readme.cpp:53:68
--8<--
Otherwise it contains the error object representing the failure reason. In the below snippet, cubic spline interpolation fails because the number of input points is 3, which is below the minimum_required_points() = 4
of CubicSpline
.
--8<--
common/autoware_trajectory/examples/example_readme.cpp:109:119
--8<--
In such cases the result expected
object contains InterpolationFailure
type with an error message like "base size 3 is less than minimum required 4".
The Trajectory class provides mathematical continuous representation and object oriented interface for discrete array of following point types
-
geometry_msgs::Point
-
geometry_msgs::Pose
-
autoware_planning_msgs::PathPoint
-
autoware_planning_msgs::PathPointWithLaneId
-
autoware_planning_msgs::TrajectoryPoint
-
lanelet::ConstPoint3d
by interpolating the given underlying points. Once built, arbitrary point on the curve is continuously parametrized by a single s
coordinate.
--8<--
common/autoware_trajectory/examples/example_readme.cpp:547:562
--8<--
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/overview/trajectory.drawio.svg") }})
This section introduces strict definition of several words used in this package to clarify the description of API and help the developers understand and grasp the geometric meaning of algorithms.
Word | Meaning | Illustration |
---|---|---|
curve |
curve is an oriented bounded curve denoted as (x(s), y(s), z(s)) with additional properties, parameterized by s (s = 0 at the start). |
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/nomenclature/curve.drawio.svg") }}) There are 5 underlying pointsand the arc length between each interval is |
underlying |
underlying points of a curve refers to the list of 3D points from which the curve was interpolated. |
|
arc length [m] |
arc length denotes the approximate 3D length of of a curve and is computed based on the discrete underlying points. |
|
s [m] |
s denotes the 3D arc length coordinate starting from the base point (mostly the start point) of the curve and a point is identified by trajectory(s) .Due to this definition, the actual curve length and arc length have subtle difference as illustrated. |
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/nomenclature/approximation.drawio.svg") }}) The point for The exact curve length is |
curvature |
curvature is computed using only X-Y 2D coordinate. This is based on the normal and natural assumption that roads are flat. Mathematically, it asserts that Gaussian curvature of road is uniformly 0.The sign of curvature is positive if the center of turning circle is on the left side, otherwise negative. |
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/nomenclature/curvature.drawio.svg") }}) |
Class | method/function | description |
---|---|---|
Common Functions | minimum_required_points() |
return the number of points required for each concrete interpolator |
compute(double s) -> T |
compute the interpolated value at given base |
|
compute(vector<double> s) -> vector<T> |
compute the interpolated values at for each base values in |
|
compute_first_derivative(double s) -> double |
compute the first derivative of at given base |
|
compute_second_derivative(double s) -> double |
compute the second derivative of at given base |
AkimaSpline
requires at least 5 points to interpolate.
--8<--
common/autoware_trajectory/examples/example_readme.cpp:137:151
--8<--
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/akima_spline.drawio.svg") }})
CubicSpline
requires at least 4 points to interpolate.
--8<--
common/autoware_trajectory/examples/example_readme.cpp:192:201
--8<--
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/cubic_spline.drawio.svg") }})
Linear
requires at least 2 points to interpolate.
--8<--
common/autoware_trajectory/examples/example_readme.cpp:242:250
--8<--
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/linear.drawio.svg") }})
StairStep
requires at least 2 points to interpolate.
--8<--
common/autoware_trajectory/examples/example_readme.cpp:291:300
--8<--
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/stairstep.drawio.svg") }})
Several Trajectory<T>
are defined in the following inheritance hierarchy according to the sub object relationships.
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/nomenclature/trajectory_hierarchy.drawio.svg") }})
Each derived class in the diagram inherits the methods of all of its descending subclasses. For example, all of the classes have the methods like length()
, curvature()
in common.
Header / function | description | detail |
---|---|---|
<autoware/trajectory/utils/shift.hpp |
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/utils/shift/shift.drawio.svg") }}) This is the case where |
|
|
contains
|
Returns the shifted trajectory as well the s values indicating where the shift starts and completes on the new shifted trajectory. |
|
contains
|
|
|
contains
|
|
|
Following formulation, return a shifted Trajectory object if the parameters are feasible, otherwise return Error object indicating error reason(i.e. |
For derivation, see formulation. The example code for this plot is found example |
<autoware/trajectory/utils/pretty_build.hpp> |
||
|
A convenient function that will almost surely succeed in constructing a Trajectory class unless the given points size is 0 or 1. Input points are interpolated to 3 points using Linear and to 4 points using Cubic so that it returns
default interpolators setting.You may need to call align_orientation_with_trajectory_direction if you did not give desired orientation. |
|
shift
function laterally offsets given curve by
Starting from the initial longitudinal velocity of
$$ \begin{align} & t_{1}: & s_{1} &= v^{\rm lon}0 T_j + \frac{1}{2} a^{\rm lon} T_j^2, & v{1} &= v^{\rm lon}0 + a^{\rm lon} T_j, & l{1} &= \frac{1}{6}jT_j^3 \ & t_{2}: & s_{2} &= v^{\rm lon}1 T_a + \frac{1}{2} a^{\rm lon} T_a^2, & v{2} &= v^{\rm lon}1 + a^{\rm lon} T_a, & l{2} &= \frac{1}{6}j T_j^3 + \frac{1}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j \ & t_{3}: & s_{3} &= v^{\rm lon}2 T_j + \frac{1}{2} a^{\rm lon} T_j^2, & v{3} &= v^{\rm lon}2 + a^{\rm lon} T_j, & l{3} &= j T_j^3 + \frac{3}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j \ & t_{4}: & s_{4} &= v^{\rm lon}3 T_v + \frac{1}{2} a^{\rm lon} T_v^2, & v{4} &= v^{\rm lon}3 + a^{\rm lon} T_v, & l{4} &= j T_j^3 + \frac{3}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j + j(T_a + T_j)T_j T_v \ & t_{5}: & s_{5} &= v^{\rm lon}4 T_j + \frac{1}{2} a^{\rm lon} T_j^2, & v{5} &= v^{\rm lon}4 + a^{\rm lon} T_j, & l{5} &= \frac{11}{6} j T_j^3 + \frac{5}{2} j T_a T_j^2 + \frac{1}{2} j T_a^2 T_j + j(T_a + T_j)T_j T_v \ & t_{6}: & s_{6} &= v^{\rm lon}5 T_a + \frac{1}{2} a^{\rm lon} T_a^2, & v{6} &= v^{\rm lon}5 + a^{\rm lon} T_a, & l{6} &= \frac{11}{6} j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j + j(T_a + T_j)T_j T_v \ & t_{7}: & s_{7} &= v^{\rm lon}6 T_j + \frac{1}{2} a^{\rm lon} T_j^2, & v{7} &= v^{\rm lon}6 + a^{\rm lon} T_j, & l{7} &= 2 j T_j^3 + 3 j T_a T_j^2 + j T_a^2 T_j + j(T_a + T_j)T_j T_v \end{align} $$
Given following inputs,
- desired longitudinal distance
$L_{\mathrm{lon}}$ - desired lateral shift distance
$L$ - longitudinal initial velocity
$v_{\mathrm{lon}}$ - longitudinal acceleration
$a_{\mathrm{lon}}$ - lateral acceleration limit
$a_{\mathrm{lim}}^{\mathrm{lat}}$
shift
internally computes
- total time of shift
$T_{\mathrm{total}}$ - maximum lateral acceleration
$a_{\mathrm{max}}^{\mathrm{lat}}$ during the shift - constant/zero jerk time
$T_{\mathrm{j}}, T_{\mathrm{a}}$ respectively - required jerk
$j$
as following
to obtain
If
pretty_build
is a convenient wrapper tailored for most Autoware Planning/Control component, which will never fail to interpolate unless the given points size is 0 or 1.
--8<--
common/autoware_trajectory/examples/example_pretty_build.cpp:93:97
--8<--
You can also specify interpolation method to Builder{}
before calling .build(points)
using autoware::experimental::trajectory::interpolator::CubicSpline;
std::optional<Trajectory<autoware_planning_msgs::msg::PathPoint>> trajectory =
Trajectory<autoware_planning_msgs::msg::PathPoint>::Builder{}
.set_xy_interpolator<CubicSpline>() // Set interpolator for x-y plane
.build(points);
trajectory->crop(1.0, 2.0);
--8<--
common/autoware_trajectory/examples/example_shift.cpp:97:117
--8<--
[View in Drawio]({{ drawio("/common/autoware_trajectory/images/utils/shift/shift_num_points.drawio.svg") }})
Set 3.0[m] ~ 5.0[m] part of velocity to 0.0
trajectory->longitudinal_velocity_mps(3.0, 5.0) = 0.0;
std::vector<autoware_planning_msgs::msg::PathPoint> points = trajectory->restore();