|
scenario_simulator_v2 C++ API
|
#include <catmull_rom_spline.hpp>


Public Member Functions | |
| CatmullRomSpline ()=default | |
| CatmullRomSpline (const std::vector< geometry_msgs::msg::Point > &control_points) | |
| CatmullRomSpline (const geometry_msgs::msg::Point &start_point, const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &trajectory) | |
| 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 | getTrajectoryPoses (const double start_s, const double end_s, const double resolution) const -> std::vector< geometry_msgs::msg::Pose > |
| 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 override |
| 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::optional< std::pair< double, double >> &s_range=std::nullopt) 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< std::pair< double, double >> &s_range=std::nullopt) 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 |
Public Member Functions inherited from math::geometry::CatmullRomSplineInterface | |
| virtual | ~CatmullRomSplineInterface ()=default |
Public Attributes | |
| const std::vector< geometry_msgs::msg::Point > | control_points |
|
default |
|
explicit |
|
explicit |
|
virtualdefault |
| 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> |
|
overridevirtual |
Get collision point in 2D (x and y)
| polygon | points of polygons. |
| search_backward | If true, return collision points with maximum s value. If false, return collision points with minimum s value. |
Implements math::geometry::CatmullRomSplineInterface.
| auto math::geometry::CatmullRomSpline::getCollisionPointsIn2D | ( | const std::vector< geometry_msgs::msg::Point > & | polygon, |
| const bool | search_backward = false, |
||
| const std::optional< std::pair< double, double >> & | s_range = std::nullopt |
||
| ) | const -> std::set<double> |
|
inlineoverridevirtual |
Implements math::geometry::CatmullRomSplineInterface.
| auto math::geometry::CatmullRomSpline::getMaximum2DCurvature | ( | ) | const -> double |
| auto math::geometry::CatmullRomSpline::getNormalVector | ( | const double | s | ) | const -> geometry_msgs::msg::Vector3 |
| auto math::geometry::CatmullRomSpline::getPoint | ( | const double | s | ) | const -> geometry_msgs::msg::Point |
| auto math::geometry::CatmullRomSpline::getPoint | ( | const double | s, |
| const double | offset | ||
| ) | const -> geometry_msgs::msg::Point |
| 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> |
| auto math::geometry::CatmullRomSpline::getPose | ( | const double | s, |
| const bool | fill_pitch = true |
||
| ) | const -> geometry_msgs::msg::Pose |
|
overridevirtual |
Implements math::geometry::CatmullRomSplineInterface.
| auto math::geometry::CatmullRomSpline::getSquaredDistanceVector | ( | const geometry_msgs::msg::Point & | point, |
| const double | s | ||
| ) | const -> geometry_msgs::msg::Vector3 |
| auto math::geometry::CatmullRomSpline::getSValue | ( | const geometry_msgs::msg::Pose & | pose, |
| double | threshold_distance = 3.0 |
||
| ) | const -> std::optional<double> |
| auto math::geometry::CatmullRomSpline::getTangentVector | ( | const double | s | ) | const -> geometry_msgs::msg::Vector3 |
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.| 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> |
| auto math::geometry::CatmullRomSpline::getTrajectoryPoses | ( | const double | start_s, |
| const double | end_s, | ||
| const double | resolution | ||
| ) | const -> std::vector<geometry_msgs::msg::Pose> |
| const std::vector<geometry_msgs::msg::Point> math::geometry::CatmullRomSpline::control_points |