#include <catmull_rom_spline.hpp>
|
| CatmullRomSpline ()=default |
|
| CatmullRomSpline (const std::vector< geometry_msgs::msg::Point > &control_points) |
|
auto | getLength () const -> double override |
|
auto | getMaximum2DCurvature () const -> double |
|
auto | getPoint (const double s) const -> geometry_msgs::msg::Point |
|
auto | getPoint (const double s, const double offset) const -> geometry_msgs::msg::Point |
|
auto | getTangentVector (const double s) const -> geometry_msgs::msg::Vector3 |
|
auto | getNormalVector (const double s) const -> geometry_msgs::msg::Vector3 |
|
auto | getPose (const double s, const bool fill_pitch=true) const -> geometry_msgs::msg::Pose |
|
auto | getTrajectory (const double start_s, const double end_s, const double resolution, const double offset=0.0) const -> std::vector< geometry_msgs::msg::Point > |
|
auto | getSValue (const geometry_msgs::msg::Pose &pose, double threshold_distance=3.0) const -> std::optional< double > |
|
auto | getSquaredDistanceIn2D (const geometry_msgs::msg::Point &point, const double s) const -> double |
|
auto | getSquaredDistanceVector (const geometry_msgs::msg::Point &point, const double s) const -> geometry_msgs::msg::Vector3 |
|
auto | getCollisionPointsIn2D (const std::vector< geometry_msgs::msg::Point > &polygon, const bool search_backward=false) const -> std::set< double > |
|
auto | getCollisionPointIn2D (const geometry_msgs::msg::Point &point0, const geometry_msgs::msg::Point &point1, const bool search_backward=false) const -> std::optional< double > |
|
auto | getCollisionPointIn2D (const std::vector< geometry_msgs::msg::Point > &polygon, const bool search_backward=false) const -> std::optional< double > override |
| Get collision point in 2D (x and y) More...
|
|
auto | getPolygon (const double width, const size_t num_points=30, const double z_offset=0) -> std::vector< geometry_msgs::msg::Point > |
|
virtual | ~CatmullRomSpline ()=default |
|
virtual | ~CatmullRomSplineInterface ()=default |
|
◆ CatmullRomSpline() [1/2]
math::geometry::CatmullRomSpline::CatmullRomSpline |
( |
| ) |
|
|
default |
◆ CatmullRomSpline() [2/2]
math::geometry::CatmullRomSpline::CatmullRomSpline |
( |
const std::vector< geometry_msgs::msg::Point > & |
control_points | ) |
|
|
explicit |
- Note
- In this case, spline is interpreted as point.
-
In this case, spline is interpreted as line segment.
-
In this case, spline is interpreted as curve.
◆ ~CatmullRomSpline()
virtual math::geometry::CatmullRomSpline::~CatmullRomSpline |
( |
| ) |
|
|
virtualdefault |
◆ getCollisionPointIn2D() [1/2]
auto math::geometry::CatmullRomSpline::getCollisionPointIn2D |
( |
const geometry_msgs::msg::Point & |
point0, |
|
|
const geometry_msgs::msg::Point & |
point1, |
|
|
const bool |
search_backward = false |
|
) |
| const -> std::optional<double> |
◆ getCollisionPointIn2D() [2/2]
auto math::geometry::CatmullRomSpline::getCollisionPointIn2D |
( |
const std::vector< geometry_msgs::msg::Point > & |
polygon, |
|
|
const bool |
search_backward = false |
|
) |
| const -> std::optional<double> |
|
overridevirtual |
Get collision point in 2D (x and y)
- Parameters
-
polygon | points of polygons. |
search_backward | If true, return collision points with maximum s value. If false, return collision points with minimum s value. |
- Returns
- std::optional<double> Denormalized s values along the frenet coordinate of the spline curve.
Implements math::geometry::CatmullRomSplineInterface.
◆ getCollisionPointsIn2D()
auto math::geometry::CatmullRomSpline::getCollisionPointsIn2D |
( |
const std::vector< geometry_msgs::msg::Point > & |
polygon, |
|
|
const bool |
search_backward = false |
|
) |
| const -> std::set<double> |
- Note
- If the spline has three or more control points.
-
The local_polygon is assumed to be closed
-
If the spline has two control points. (Same as single line segment.)
-
If the spline has one control point. (Same as point.)
-
In this case, spline is interpreted as point.
-
In this case, spline is interpreted as line segment.
-
In this case, spline is interpreted as curve.
◆ getLength()
auto math::geometry::CatmullRomSpline::getLength |
( |
| ) |
const -> double |
|
inlineoverridevirtual |
◆ getMaximum2DCurvature()
auto math::geometry::CatmullRomSpline::getMaximum2DCurvature |
( |
| ) |
const -> double |
◆ getNormalVector()
auto math::geometry::CatmullRomSpline::getNormalVector |
( |
const double |
s | ) |
const -> geometry_msgs::msg::Vector3 |
◆ getPoint() [1/2]
auto math::geometry::CatmullRomSpline::getPoint |
( |
const double |
s | ) |
const -> geometry_msgs::msg::Point |
◆ getPoint() [2/2]
auto math::geometry::CatmullRomSpline::getPoint |
( |
const double |
s, |
|
|
const double |
offset |
|
) |
| const -> geometry_msgs::msg::Point |
◆ getPolygon()
auto math::geometry::CatmullRomSpline::getPolygon |
( |
const double |
width, |
|
|
const size_t |
num_points = 30 , |
|
|
const double |
z_offset = 0 |
|
) |
| -> std::vector<geometry_msgs::msg::Point> |
◆ getPose()
auto math::geometry::CatmullRomSpline::getPose |
( |
const double |
s, |
|
|
const bool |
fill_pitch = true |
|
) |
| const -> geometry_msgs::msg::Pose |
◆ getSquaredDistanceIn2D()
auto math::geometry::CatmullRomSpline::getSquaredDistanceIn2D |
( |
const geometry_msgs::msg::Point & |
point, |
|
|
const double |
s |
|
) |
| const -> double |
◆ getSquaredDistanceVector()
auto math::geometry::CatmullRomSpline::getSquaredDistanceVector |
( |
const geometry_msgs::msg::Point & |
point, |
|
|
const double |
s |
|
) |
| const -> geometry_msgs::msg::Vector3 |
◆ getSValue()
auto math::geometry::CatmullRomSpline::getSValue |
( |
const geometry_msgs::msg::Pose & |
pose, |
|
|
double |
threshold_distance = 3.0 |
|
) |
| const -> std::optional<double> |
◆ getTangentVector()
auto math::geometry::CatmullRomSpline::getTangentVector |
( |
const double |
s | ) |
const -> geometry_msgs::msg::Vector3 |
- Note
- The current implementation uses
index_and_s
instead of structured binding (const auto [index, s_value] = getCurveIndexAndS(s)
) because some tests fail when using structured binding. The root cause of these test failures is under investigation.
◆ getTrajectory()
auto math::geometry::CatmullRomSpline::getTrajectory |
( |
const double |
start_s, |
|
|
const double |
end_s, |
|
|
const double |
resolution, |
|
|
const double |
offset = 0.0 |
|
) |
| const -> std::vector<geometry_msgs::msg::Point> |
◆ control_points
const std::vector<geometry_msgs::msg::Point> math::geometry::CatmullRomSpline::control_points |
The documentation for this class was generated from the following files: