14 #ifndef GEOMETRY__SPLINE__CATMULL_ROM_SPLINE_HPP_
15 #define GEOMETRY__SPLINE__CATMULL_ROM_SPLINE_HPP_
21 #include <geometry_msgs/msg/point.hpp>
36 auto getLength() const ->
double override {
return total_length_; }
38 auto
getPoint(const
double s) const -> geometry_msgs::msg::Point;
39 auto
getPoint(const
double s, const
double offset) const -> geometry_msgs::msg::Point;
41 auto
getNormalVector(const
double s) const -> geometry_msgs::msg::Vector3;
42 auto
getPose(const
double s, const
bool fill_pitch = true) const -> geometry_msgs::msg::Pose;
44 const
double start_s, const
double end_s, const
double resolution,
45 const
double offset = 0.0) const ->
std::vector<geometry_msgs::msg::Point>;
46 auto
getSValue(const geometry_msgs::msg::Pose & pose,
double threshold_distance = 3.0) const
47 ->
std::optional<
double>;
51 -> geometry_msgs::msg::Vector3;
53 const
std::vector<geometry_msgs::msg::Point> & polygon,
54 const
bool search_backward = false) const ->
std::set<
double>;
56 const geometry_msgs::msg::Point & point0, const geometry_msgs::msg::Point & point1,
57 const
bool search_backward = false) const ->
std::optional<
double>;
59 const
std::vector<geometry_msgs::msg::Point> & polygon,
60 const
bool search_backward = false) const ->
std::optional<
double> override;
61 auto
getPolygon(const
double width, const
size_t num_points = 30, const
double z_offset = 0)
62 ->
std::vector<geometry_msgs::msg::Point>;
67 auto getRightBounds(const
double width, const
size_t num_points = 30, const
double z_offset = 0)
68 const ->
std::vector<geometry_msgs::msg::Point>;
69 auto getLeftBounds(const
double width, const
size_t num_points = 30, const
double z_offset = 0)
70 const ->
std::vector<geometry_msgs::msg::Point>;
71 auto getSInSplineCurve(const
size_t curve_index, const
double s) const ->
double;
72 auto getCurveIndexAndS(const
double s) const ->
std::pair<
size_t,
double>;
73 auto checkConnection() const ->
bool;
74 auto equals(const geometry_msgs::msg::Point & p0, const geometry_msgs::msg::Point & p1) const
78 std::vector<
double> length_list_;
79 std::vector<
double> maximum_2d_curvatures_;
Definition: catmull_rom_spline_interface.hpp:30
Definition: catmull_rom_spline.hpp:32
auto getCollisionPointIn2D(const geometry_msgs::msg::Point &point0, const geometry_msgs::msg::Point &point1, const bool search_backward=false) const -> std::optional< double >
Definition: catmull_rom_spline.cpp:374
auto getPoint(const double s) const -> geometry_msgs::msg::Point
Definition: catmull_rom_spline.cpp:516
auto getSValue(const geometry_msgs::msg::Pose &pose, double threshold_distance=3.0) const -> std::optional< double >
Definition: catmull_rom_spline.cpp:399
const std::vector< geometry_msgs::msg::Point > control_points
Definition: catmull_rom_spline.hpp:63
auto getPolygon(const double width, const size_t num_points=30, const double z_offset=0) -> std::vector< geometry_msgs::msg::Point >
Definition: catmull_rom_spline.cpp:29
auto getSquaredDistanceVector(const geometry_msgs::msg::Point &point, const double s) const -> geometry_msgs::msg::Vector3
Definition: catmull_rom_spline.cpp:478
auto getSquaredDistanceIn2D(const geometry_msgs::msg::Point &point, const double s) const -> double
Definition: catmull_rom_spline.cpp:442
auto getLength() const -> double override
Definition: catmull_rom_spline.hpp:36
CatmullRomSpline()=default
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 >
Definition: catmull_rom_spline.cpp:100
auto getPose(const double s, const bool fill_pitch=true) const -> geometry_msgs::msg::Pose
Definition: catmull_rom_spline.cpp:642
auto getCollisionPointsIn2D(const std::vector< geometry_msgs::msg::Point > &polygon, const bool search_backward=false) const -> std::set< double >
Definition: catmull_rom_spline.cpp:281
auto getMaximum2DCurvature() const -> double
Definition: catmull_rom_spline.cpp:563
auto getTangentVector(const double s) const -> geometry_msgs::msg::Vector3
Definition: catmull_rom_spline.cpp:605
auto getNormalVector(const double s) const -> geometry_msgs::msg::Vector3
Definition: catmull_rom_spline.cpp:576
Definition: hermite_curve.hpp:32
Definition: line_segment.hpp:30
Definition: bounding_box.hpp:32