tactics2d.interpolator
Interpolator module.
BSpline
This class implements a B-spline curve interpolator.
get_curve(control_points, knot_vectors=None, degree=0, n_interpolation=100)
staticmethod
Get the interpolation points of a b-spline curve.
Parameters:
-
control_points(ndarray) –The control points of the curve. Usually denoted as \(P_0, P_1, \dots, P_n\) in literature. The shape is \((n + 1, 2)\).
-
knot_vectors(ndarray, default:None) –The knots of the curve. Usually denoted as \(u_0, u_1, \dots, u_t\) in literature. The shape is \((t + 1, )\). Defaults to None.
-
degree(int, default:0) –The degree of the B-spline curve. Usually denoted as p in the literature. Defaults to 0.
-
n_interpolation(int, default:100) –The number of interpolation points. Defaults to 100.
Returns:
-
curve_points(ndarray) –The interpolation points of the curve. The shape is (n_interpolation, 2).
Bezier
This class implements a Bezier curve interpolator.
get_curve(control_points, n_interpolation, order=None)
staticmethod
Parameters:
-
control_points(ndarray) –The control points of the curve. The shape is (order + 1, 2).
-
n_interpolation(int) –The number of interpolations.
-
order(int, default:None) –The order of the Bezier curve. If not provided, it will be set to the number of control points minus one.
Returns:
-
curve_points(ndarray) –The interpolated points of the curve. The shape is (n_interpolation, 2).
CubicSpline
This class implement a cubic spline interpolator.
Attributes:
-
boundary_type(int) –Boundary condition type. The cubic spline interpolator offers three distinct boundary condition options: Natural (1), Clamped (2), and NotAKnot (3). By default, the not-a-knot boundary condition is applied, serving as a wise choice when specific boundary condition information is unavailable.
BoundaryType
Bases: Enum
The boundary condition type of the cubic spline interpolator.
Attributes:
-
Natural(int) –Natural boundary condition. The second derivative of the curve at the first and the last control points is set to 0.
-
Clamped(int) –Clamped boundary condition. The first derivative of the curve at the first and the last control points is set to the given values.
-
NotAKnot(int) –Not-a-knot boundary condition. The first and the second cubic functions are connected at the second and the third control points, and the last and the second-to-last cubic functions are connected at the last and the second-to-last control points.
get_curve(control_points, first_derivatives=(0, 0), n_interpolation=100, boundary_type=BoundaryType.NotAKnot)
staticmethod
Get the interpolation points of a cubic spline curve.
Parameters:
-
control_points(ndarray) –The control points of the curve. The shape is (n + 1, 2).
-
first_derivatives(tuple, default:(0, 0)) –The first derivatives (f'(x₀), f'(xₙ)) at the first and last control points. Only used for Clamped boundary condition. Defaults to (0, 0).
-
n_interpolation(int, default:100) –The number of interpolations between every two control points. Defaults to 100.
-
boundary_type(Union[int, BoundaryType], default:NotAKnot) –The boundary condition type. It can be an integer value from 1 to 3 or a BoundaryType enum value. Defaults to NotAKnot.
Returns:
-
curve_points(ndarray) –The interpolation points of the curve. The shape is (n_interpolation * n + 1, 2).
Dubins
This class implements a Dubins curve interpolator.
The curve comprises a sequence of three segments: RSR, RSL, LSL, LSR, RLR, and LRL. R stands for the right turn, L for the left turn, and S for the straight line. A Dubins path planner operates within the constraints of forward actions exclusively.
Attributes:
-
radius(float) –The minimum turning radius.
__init__(radius)
Initialize the Dubins curve interpolator.
Parameters:
-
radius(float) –The minimum turning radius.
Raises:
-
ValueError–The minimum turning radius must be positive.
get_all_path(start_point, start_heading, end_point, end_heading)
This function returns all the Dubins paths connecting two points.
Parameters:
-
start_point(ndarray) –The start point of the curve. The shape is (2,).
-
start_heading(float) –The heading of the start point. The unit is radian.
-
end_point(ndarray) –The end point of the curve. The shape is (2,).
-
end_heading(float) –The heading of the end point. The unit is radian.
Returns:
-
paths(list) –A list of Dubins paths.
get_curve(start_point, start_heading, end_point, end_heading, step_size=0.1)
Get the shortest Dubins curve connecting two points.
Parameters:
-
start_point(ndarray) –The start point of the curve. The shape is (2,).
-
start_heading(float) –The heading of the start point. The unit is radian.
-
end_point(ndarray) –The end point of the curve. The shape is (2,).
-
end_heading(float) –The heading of the end point. The unit is radian.
-
step_size(float, default:0.1) –The step size of the curve. Defaults to 0.1.
Returns:
-
shortest_path(DubinsPath) –The shortest Dubins path connecting two points.
get_path(start_point, start_heading, end_point, end_heading)
This function returns the shortest Dubins path connecting two points.
Parameters:
-
start_point(ndarray) –The start point of the curve. The shape is (2,).
-
start_heading(float) –The heading of the start point. The unit is radian.
-
end_point(ndarray) –The end point of the curve. The shape is (2,).
-
end_heading(float) –The heading of the end point. The unit is radian.
Returns:
-
shortest_path(DubinsPath) –The shortest Dubins path.
ParamPoly3
This class implements a parametric cubic polynomial curve interpolation.
fit(pts)
staticmethod
Fit a paramPoly3 curve to a polyline segment.
Transforms the segment to a local frame (origin at start, x-axis along initial heading), then fits cubic polynomials U(p) and V(p) where p is the normalised arc-length parameter in [0, 1].
Parameters:
-
pts(ndarray) –Polyline points in world coordinates. Shape (N, 2).
Returns:
-
tuple | None–tuple | None: A tuple of (x, y, hdg, length, aU, bU, cU, dU, aV, bV, cV, dV). Returns None if the segment is degenerate.
Example
import numpy as np from tactics2d.interpolator.param_poly3 import ParamPoly3 pts = np.array([[0., 0.], [10., 1.], [20., 0.]]) result = ParamPoly3.fit(pts) x, y, hdg, length, aU, bU, cU, dU, aV, bV, cV, dV = result length > 0 True
get_curve(length, start_point, heading, aU, bU, cU, dU, aV, bV, cV, dV, p_range_type='normalized')
staticmethod
Get the points on a paramPoly3 curve defined in the OpenDRIVE standard.
Parameters:
-
length(float) –The arc length of the curve segment.
-
start_point(tuple) –The (x, y) world coordinates of the curve start.
-
heading(float) –The heading angle at the start point in radians.
-
aU(float) –Constant coefficient of the U polynomial.
-
bU(float) –Linear coefficient of the U polynomial.
-
cU(float) –Quadratic coefficient of the U polynomial.
-
dU(float) –Cubic coefficient of the U polynomial.
-
aV(float) –Constant coefficient of the V polynomial.
-
bV(float) –Linear coefficient of the V polynomial.
-
cV(float) –Quadratic coefficient of the V polynomial.
-
dV(float) –Cubic coefficient of the V polynomial.
-
p_range_type(str, default:'normalized') –Parameter range type as specified in OpenDRIVE. "normalized" maps p in [0, 1]; "arcLength" maps p in [0, length]. Defaults to "normalized".
Returns:
-
ndarray–np.ndarray: World-coordinate points on the curve. Shape is (n, 2).
ReedsShepp
This class implements a Reeds-Shepp curve interpolator.
Reference
Reeds, James, and Lawrence Shepp. "Optimal paths for a car that goes both forwards and backwards." Pacific journal of mathematics 145.2 (1990): 367-393.
Attributes:
-
radius(float) –The minimum turning radius of the vehicle.
get_all_path(start_point, start_heading, end_point, end_heading)
Get all the Reeds-Shepp paths connecting two points.
Parameters:
-
start_point(ndarray) –The start point of the curve. The shape is (2,).
-
start_heading(float) –The start heading of the curve.
-
end_point(ndarray) –The end point of the curve. The shape is (2,).
-
end_heading(float) –The end heading of the curve.
Returns:
-
paths(list) –A list of Reeds-Shepp paths.
get_curve(start_point, start_heading, end_point, end_heading, step_size=0.01)
Get the shortest Reeds-Shepp curve connecting two points.
Parameters:
-
start_point(ndarray) –The start point of the curve. The shape is (2,).
-
start_heading(float) –The start heading of the curve.
-
end_point(ndarray) –The end point of the curve. The shape is (2,).
-
end_heading(float) –The end heading of the curve.
Returns:
-
shortest_path(ReedsSheppPath) –The shortest Reeds-Shepp curve connecting two points.
get_path(start_point, start_heading, end_point, end_heading)
Get the shortest Reeds-Shepp path connecting two points.
Parameters:
-
start_point(ndarray) –The start point of the curve. The shape is (2,).
-
start_heading(float) –The start heading of the curve.
-
end_point(ndarray) –The end point of the curve. The shape is (2,).
-
end_heading(float) –The end heading of the curve.
Returns:
-
shortest_path(ReedsSheppPath) –The shortest Reeds-Shepp path connecting two points.
Spiral
This class implements a spiral interpolation.
get_curve(length, start_point, heading, start_curvature, gamma, n_interpolation=100)
staticmethod
This function gets the points on a spiral curve line.
Parameters:
-
length(float) –The length of the spiral.
-
start_point(ndarray) –The start point of the spiral. The shape is (2,).
-
heading(float) –The heading of the start point. The unit is radian.
-
start_curvature(float) –The curvature of the start point.
-
gamma(float) –The rate of change of curvature
-
n_interpolation(int, default:100) –The number of interpolation points. Defaults to 100.
Returns:
-
ndarray–np.ndarray: The points on the spiral curve line. The shape is (n_interpolation, 2).