Skip to content

tactics2d.math

tactics2d.math.geometry

Circle

This class implement some frequently operations on circle.

TODO

To improve the performance, we will rewrite the methods in C++ in the future.

ConstructBy

Bases: Enum

The method to derive a circle.

Attributes:

Name Type Description
ThreePoints int

Derive a circle by three points.

TangentVector int

Derive a circle by a tangent point, a heading and a radius.

get_arc(center_point, radius, delta_angle, start_angle, clockwise=True, step_size=0.1) staticmethod

This function gets the points on an arc curve line.

Parameters:

Name Type Description Default
center_point ndarray

The center of the arc. The shape is (2,).

required
radius float

The radius of the arc.

required
delta_angle float

The angle of the arc. This values is expected to be positive. The unit is radian.

required
start_angle float

The start angle of the arc. The unit is radian.

required
clockwise bool

The direction of the arc. True represents clockwise. False represents counterclockwise.

True
step_size float

The step size of the arc. The unit is radian.

0.1

Returns:

Name Type Description
arc_points ndarray

The points on the arc. The shape is (int(radius * delta / step_size), 2).

get_circle(method, *args) staticmethod

This function gets a circle by different given conditions.

Parameters:

Name Type Description Default
method ConstructBy

The method to derive a circle. The available choices are Circle.ConstructBy.ThreePoints) and Circle.ConstructBy.TangentVector).

required
*args tuple

The arguments of the method.

()

Returns:

Name Type Description
center ndarray

The center of the circle. The shape is (2,).

radius float

The radius of the circle.

Raises:

Type Description
NotImplementedError

The input method id is not an available choice.

get_circle_by_tangent_vector(tangent_point, heading, radius, side) staticmethod

This function gets a circle by a tangent point, a heading and a radius.

Parameters:

Name Type Description Default
tangent_point ndarray

The tangent point on the circle. The shape is (2,).

required
heading float

The heading of the tangent point. The unit is radian.

required
radius float

The radius of the circle.

required
side int

The location of circle center relative to the tangent point. "L" represents left. "R" represents right.

required

Returns:

Name Type Description
center ndarray

The center of the circle. The shape is (2,).

radius float

The radius of the circle.

get_circle_by_three_points(pt1, pt2, pt3) staticmethod

This function gets a circle by three points.

Parameters:

Name Type Description Default
pt1 Union[list, ndarray]

The first point. The shape is (2,).

required
pt2 Union[list, ndarray]

The second point. The shape is (2,).

required
pt3 Union[list, ndarray]

The third point. The shape is (2,).

required

Returns:

Name Type Description
center ndarray

The center of the circle. The shape is (2,).

radius float

The radius of the circle.

Vector

This class implement some frequently operations on vector.

TODO

To improve the performance, we will rewrite the methods in C++ in the future.

angle(vec1, vec2) staticmethod

This method calculate the angle between two vectors.

Parameters:

Name Type Description Default
vec1 ndarray

The first vector. The shape is (n,).

required
vec2 ndarray

The second vector. The shape is (n,).

required

Returns:

Name Type Description
angle float

The angle between two vectors in radians. The value is in the range [0, pi].

tactics2d.math.interpolate

BSpline

This class implements a B-spline curve interpolator.

Attributes:

Name Type Description
degree int

The degree of the B-spline curve. Usually denoted as $p$ in the literature. The degree of a B-spline curve is equal to the degree of the highest degree basis function. The order of a B-spline curve is equal to $p + 1$.

__init__(degree)

Initialize the B-spline curve interpolator.

Parameters:

Name Type Description Default
degree int

The degree of the B-spline curve. Usually denoted as p in the literature.

required

Raises:

Type Description
ValueError

The degree of a B-spline curve must be non-negative.

cox_deBoor(knot_vectors, degree, u)

Get the value of the basis function Ni, p(u) at u.

Parameters:

Name Type Description Default
knot_vectors ndarray

The subset of knot vectors ${u_i, u_{i+1}, \dots, u_{i+p+1}}. The shape is $(p + 2, )$.

required
degree int

The degree of the basis function. Usually denoted as $p$ in the literature.

required
u float

The value at which the basis function is evaluated.

required

get_curve(control_points, knot_vectors=None, n_interpolation=100)

Get the interpolation points of a b-spline curve.

Parameters:

Name Type Description Default
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)$.

required
knot_vectors ndarray

The knots of the curve. Usually denoted as $u_0, u_1, \dots, u_t$ in literature. The shape is $(t + 1, )$.

None
n_interpolation int

The number of interpolation points.

100

Returns:

Name Type Description
curve_points ndarray

The interpolation points of the curve. The shape is (n_interpolation, 2).

Bezier

This class implement a Bezier curve interpolator.

Attributes:

Name Type Description
order int

The order of the Bezier curve. The order of a Bezier curve is equal to the number of control points minus one.

__init__(order)

Initialize the Bezier curve interpolator.

Parameters:

Name Type Description Default
order int

The order of the Bezier curve.

required

Raises:

Type Description
ValueError

The order of a Bezier curve must be greater than or equal to one.

de_casteljau(points, t, order)

The de Casteljau algorithm for Bezier curves.

Parameters:

Name Type Description Default
points ndarray

The interpolation points of the curve. The shape is (order + 1, 2).

required
t float

The binomial coefficient.

required
order int

The order of the Bezier curve.

required

get_curve(control_points, n_interpolation)

Parameters:

Name Type Description Default
control_points ndarray

The control points of the curve. The shape is (order + 1, 2).

required
n_interpolation int

The number of interpolations.

required

Returns:

Name Type Description
curve_points ndarray

The interpolated points of the curve. The shape is (n_interpolation, 2).

CubicSpline

This class implement a cubic spline interpolator.

Attributes:

Name Type Description
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:

Name Type Description
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.

__init__(boundary_type=BoundaryType.NotAKnot)

Initialize the cubic spline interpolator.

Parameters:

Name Type Description Default
boundary_type BoundaryType

Boundary condition type. Defaults to BoundaryType.NotAKnot. The available options are CubicSpline.BoundaryType.Natural, CubicSpline.BoundaryType.Clamped, and CubicSpline.BoundaryType.NotAKnot.

NotAKnot

Raises:

Type Description
ValueError

The boundary type is not valid. Please choose from CubicSpline.BoundaryType.Natural, CubicSpline.BoundaryType.Clamped, and CubicSpline.BoundaryType.NotAKnot.

get_curve(control_points, xx=(0, 0), n_interpolation=100)

Get the interpolation points of a cubic spline curve.

Parameters:

Name Type Description Default
control_points ndarray

The control points of the curve. The shape is (n + 1, 2).

required
xx float

The first derivative of the curve at the first and the last control points. These conditions will be used when the boundary condition is "clamped". Defaults to (0, 0).

(0, 0)
n_interpolation int

The number of interpolations between every two control points. Defaults to 100.

100

Returns:

Name Type Description
curve_points ndarray

The interpolation points of the curve. The shape is (n_interpolation * n + 1, 2).

get_parameters(control_points, xx=(0, 0))

Get the parameters of the cubic functions

Parameters:

Name Type Description Default
control_points ndarray

The control points of the curve. The shape is (n + 1, 2).

required
xx float

The first derivative of the curve at the first and the last control points. Defaults to (0, 0).

(0, 0)

Returns:

Name Type Description
a ndarray

The constant parameters of the cubic functions. The shape is (n, 1).

b ndarray

The linear parameters of the cubic functions. The shape is (n, 1).

c ndarray

The quadratic parameters of the cubic functions. The shape is (n, 1).

d ndarray

The cubic parameters of the cubic functions. The shape is (n, 1).

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:

Name Type Description
radius float

The minimum turning radius.

__init__(radius)

Initialize the Dubins curve interpolator.

Parameters:

Name Type Description Default
radius float

The minimum turning radius.

required

Raises:

Type Description
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:

Name Type Description Default
start_point ndarray

The start point of the curve. The shape is (2,).

required
start_heading float

The heading of the start point. The unit is radian.

required
end_point ndarray

The end point of the curve. The shape is (2,).

required
end_heading float

The heading of the end point. The unit is radian.

required

Returns:

Name Type Description
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:

Name Type Description Default
start_point ndarray

The start point of the curve. The shape is (2,).

required
start_heading float

The heading of the start point. The unit is radian.

required
end_point ndarray

The end point of the curve. The shape is (2,).

required
end_heading float

The heading of the end point. The unit is radian.

required
step_size float

The step size of the curve. Defaults to 0.1.

0.1

Returns:

Name Type Description
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:

Name Type Description Default
start_point ndarray

The start point of the curve. The shape is (2,).

required
start_heading float

The heading of the start point. The unit is radian.

required
end_point ndarray

The end point of the curve. The shape is (2,).

required
end_heading float

The heading of the end point. The unit is radian.

required

Returns:

Name Type Description
shortest_path DubinsPath

The shortest Dubins path.

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:

Name Type Description
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:

Name Type Description Default
start_point ndarray

The start point of the curve. The shape is (2,).

required
start_heading float

The start heading of the curve.

required
end_point ndarray

The end point of the curve. The shape is (2,).

required
end_heading float

The end heading of the curve.

required

Returns:

Name Type Description
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:

Name Type Description Default
start_point ndarray

The start point of the curve. The shape is (2,).

required
start_heading float

The start heading of the curve.

required
end_point ndarray

The end point of the curve. The shape is (2,).

required
end_heading float

The end heading of the curve.

required

Returns:

Name Type Description
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:

Name Type Description Default
start_point ndarray

The start point of the curve. The shape is (2,).

required
start_heading float

The start heading of the curve.

required
end_point ndarray

The end point of the curve. The shape is (2,).

required
end_heading float

The end heading of the curve.

required

Returns:

Name Type Description
shortest_path ReedsSheppPath

The shortest Reeds-Shepp path connecting two points.

Spiral

This class implements a spiral interpolation.

get_spiral(length, start_point, heading, start_curvature, gamma) staticmethod

This function gets the points on a spiral curve line.

Parameters:

Name Type Description Default
length float

The length of the spiral.

required
start_point ndarray

The start point of the spiral. The shape is (2,).

required
heading float

The heading of the start point. The unit is radian.

required
start_curvature float

The curvature of the start point.

required
gamma float

The rate of change of curvature

required

Returns:

Type Description
ndarray

np.ndarray: The points on the spiral curve line. The shape is (n_interpolate, 2).