|
scenario_simulator_v2 C++ API
|
#include <line_segment.hpp>
Public Member Functions | |
| LineSegment (const geometry_msgs::msg::Point &start_point, const geometry_msgs::msg::Point &end_point) | |
| LineSegment (const geometry_msgs::msg::Point &start_point, const geometry_msgs::msg::Vector3 &vec, double length) | |
| auto | isIntersect2D (const geometry_msgs::msg::Point &point) const -> bool |
| Checking the intersection with 1 line segment and 1 point in 2D (x,y) coordinate. Ignore z axis. More... | |
| auto | isIntersect2D (const LineSegment &line) const -> bool |
| Checking the intersection with 2 line segments in 2D (x,y) coordinate. Ignore z axis. More... | |
| auto | isInBounds2D (const geometry_msgs::msg::Point &point) const -> bool |
| Checks if the given point lies within the bounding box of the line segment. More... | |
| auto | getPoint (const double s, const bool denormalize_s=false) const -> geometry_msgs::msg::Point |
| Get point on the line segment from s value. More... | |
| auto | getPose (const double s, const bool denormalize_s=false, const bool fill_pitch=true) const -> geometry_msgs::msg::Pose |
| Get pose on the line segment from s value. Orientation of thee return value was calculated from the vector of the line segment. More... | |
| auto | get2DIntersectionSValue (const geometry_msgs::msg::Point &point, const bool denormalize_s=false) const -> std::optional< double > |
| Find intersection point of 1 line segment and 1 point. More... | |
| auto | get2DIntersectionSValue (const LineSegment &line, const bool denormalize_s=false) const -> std::optional< double > |
| Get S value of the intersection point of two line segment. More... | |
| auto | getIntersection2D (const LineSegment &line) const -> std::optional< geometry_msgs::msg::Point > |
| Find intersection point of two line segments. More... | |
| auto | getSValue (const geometry_msgs::msg::Pose &pose, double threshold_distance, bool denormalize_s) const -> std::optional< double > |
| auto | getNormalVector () const -> geometry_msgs::msg::Vector3 |
| Get normal vector of the line segment. More... | |
| auto | get2DVectorSlope () const -> double |
| auto | getSquaredDistanceIn2D (const geometry_msgs::msg::Point &point, const double s, const bool denormalize_s=false) const -> double |
| Get squared distance (Square of euclidean distance) between specified 3D point and specified 3D point on line segment in 2D. (x,y) More... | |
| auto | getSquaredDistanceVector (const geometry_msgs::msg::Point &point, const double s, const bool denormalize_s=false) const -> geometry_msgs::msg::Vector3 |
| Get 3D vector from specified 3D point to specified 3D point on line segment. More... | |
| auto | relativePointPosition2D (const geometry_msgs::msg::Point &point) const -> int |
| Determines the relative position of a point with respect to the line segment. More... | |
Public Attributes | |
| const geometry_msgs::msg::Point | start_point |
| const geometry_msgs::msg::Point | end_point |
| const geometry_msgs::msg::Vector3 | vector |
| const geometry_msgs::msg::Vector3 | vector_2d |
| const double | length |
| const double | length_2d |
| math::geometry::LineSegment::LineSegment | ( | const geometry_msgs::msg::Point & | start_point, |
| const geometry_msgs::msg::Point & | end_point | ||
| ) |
| math::geometry::LineSegment::LineSegment | ( | const geometry_msgs::msg::Point & | start_point, |
| const geometry_msgs::msg::Vector3 & | vec, | ||
| double | length | ||
| ) |
| auto math::geometry::LineSegment::get2DIntersectionSValue | ( | const geometry_msgs::msg::Point & | point, |
| const bool | denormalize_s = false |
||
| ) | const -> std::optional<double> |
Find intersection point of 1 line segment and 1 point.
| point | point of you want to find intersection. |
| auto math::geometry::LineSegment::get2DIntersectionSValue | ( | const LineSegment & | line, |
| const bool | denormalize_s = false |
||
| ) | const -> std::optional<double> |
Get S value of the intersection point of two line segment.
| line | The line segment you want to check intersection. |
| denormalize_s | If true, s value should be normalized in range [0,1]. If false, s value is not normalized. |
| auto math::geometry::LineSegment::get2DVectorSlope | ( | ) | const -> double |
| auto math::geometry::LineSegment::getIntersection2D | ( | const LineSegment & | line | ) | const -> std::optional<geometry_msgs::msg::Point> |
Find intersection point of two line segments.
| line | Line segment of you want to find intersection. |
| auto math::geometry::LineSegment::getNormalVector | ( | ) | const -> geometry_msgs::msg::Vector3 |
Get normal vector of the line segment.
| auto math::geometry::LineSegment::getPoint | ( | const double | s, |
| const bool | denormalize_s = false |
||
| ) | const -> geometry_msgs::msg::Point |
Get point on the line segment from s value.
| s | Normalized s value in coordinate along line segment. |
| denormalize_s | If true, s value should be normalized in range [0,1]. If false, s value is not normalized. |
| auto math::geometry::LineSegment::getPose | ( | const double | s, |
| const bool | denormalize_s = false, |
||
| const bool | fill_pitch = true |
||
| ) | const -> geometry_msgs::msg::Pose |
Get pose on the line segment from s value. Orientation of thee return value was calculated from the vector of the line segment.
| s | Normalized s value in coordinate along line segment. |
| denormalize_s | If true, s value should be normalized in range [0,1]. If false, s value is not normalized. |
| fill_pitch | If true, the pitch value of the orientation is filled. If false, the pitch value of the orientation is 0. This parameter is introduced for backward-compatibility. |
| auto math::geometry::LineSegment::getSquaredDistanceIn2D | ( | const geometry_msgs::msg::Point & | point, |
| const double | s, | ||
| const bool | denormalize_s = false |
||
| ) | const -> double |
Get squared distance (Square of euclidean distance) between specified 3D point and specified 3D point on line segment in 2D. (x,y)
| point | Specified 3D point |
| S | value of specified 3D point in coordinate along line segment. |
| denormalize_s | If true, the s value is denormalized. If false, the s value should be normalized in range [0,1]. |
| auto math::geometry::LineSegment::getSquaredDistanceVector | ( | const geometry_msgs::msg::Point & | point, |
| const double | s, | ||
| const bool | denormalize_s = false |
||
| ) | const -> geometry_msgs::msg::Vector3 |
Get 3D vector from specified 3D point to specified 3D point on line segment.
| point | Specified 3D point |
| s | S value of specified 3D point in coordinate along line segment. |
| denormalize_s | If true, the s value is denormalized. If false, the s value should be normalized in range [0,1]. |
| auto math::geometry::LineSegment::getSValue | ( | const geometry_msgs::msg::Pose & | pose, |
| double | threshold_distance, | ||
| bool | denormalize_s | ||
| ) | const -> std::optional<double> |
| auto math::geometry::LineSegment::isInBounds2D | ( | const geometry_msgs::msg::Point & | point | ) | const -> bool |
Checks if the given point lies within the bounding box of the line segment.
| point | Points you want to test. |
true if the points is within the bounds.false otherwise. | auto math::geometry::LineSegment::isIntersect2D | ( | const geometry_msgs::msg::Point & | point | ) | const -> bool |
Checking the intersection with 1 line segment and 1 point in 2D (x,y) coordinate. Ignore z axis.
| point | point you want to check intersection. |
| auto math::geometry::LineSegment::isIntersect2D | ( | const LineSegment & | line | ) | const -> bool |
Checking the intersection with 2 line segments in 2D (x,y) coordinate. Ignore z axis.
| line | line segments you want to check intersection. |
| auto math::geometry::LineSegment::relativePointPosition2D | ( | const geometry_msgs::msg::Point & | point | ) | const -> int |
Determines the relative position of a point with respect to the line segment.
This method computes the relative position of a given point with respect to the line segment defined by start_point and end_point using a cross product. The result indicates on which side of the line segment the point lies.
| point | The point to be evaluated. |
1 if the point is to the left of the line segment (when moving from start_point to end_point).-1 if the point is to the right of the line segment.0 if the point is collinear with the line segment (i.e., lies exactly on the line defined by start_point and end_point). | const geometry_msgs::msg::Point math::geometry::LineSegment::end_point |
| const double math::geometry::LineSegment::length |
| const double math::geometry::LineSegment::length_2d |
| const geometry_msgs::msg::Point math::geometry::LineSegment::start_point |
| const geometry_msgs::msg::Vector3 math::geometry::LineSegment::vector |
| const geometry_msgs::msg::Vector3 math::geometry::LineSegment::vector_2d |