scenario_simulator_v2 C++ API
Public Member Functions | Public Attributes | List of all members
math::geometry::LineSegment Class Reference

#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
 

Constructor & Destructor Documentation

◆ LineSegment() [1/2]

math::geometry::LineSegment::LineSegment ( const geometry_msgs::msg::Point &  start_point,
const geometry_msgs::msg::Point &  end_point 
)

◆ LineSegment() [2/2]

math::geometry::LineSegment::LineSegment ( const geometry_msgs::msg::Point &  start_point,
const geometry_msgs::msg::Vector3 &  vec,
double  length 
)

Member Function Documentation

◆ get2DIntersectionSValue() [1/2]

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.

Parameters
pointpoint of you want to find intersection.
Returns
std::optional<double>
Note
This function checks for an SValue along the line. The term "2D" in the function name specifically refers to the intersection point, not the SValue. Therefore, the intersection is determined by disregarding the z-coordinate, hence the term "2D." After finding the intersection, we calculate its position using a proportion. Finally, we multiply this proportion by the actual 3D length to obtain the total SValue.

◆ get2DIntersectionSValue() [2/2]

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.

Parameters
lineThe line segment you want to check intersection.
denormalize_sIf true, s value should be normalized in range [0,1]. If false, s value is not normalized.
Returns
std::optional<double>

◆ get2DVectorSlope()

auto math::geometry::LineSegment::get2DVectorSlope ( ) const -> double

◆ getIntersection2D()

auto math::geometry::LineSegment::getIntersection2D ( const LineSegment line) const -> std::optional<geometry_msgs::msg::Point>

Find intersection point of two line segments.

Parameters
lineLine segment of you want to find intersection.
Returns
std::optional<geometry_msgs::msg::Point> Intersection point, if the value is std::nullopt, lines have no intersection point.

◆ getNormalVector()

auto math::geometry::LineSegment::getNormalVector ( ) const -> geometry_msgs::msg::Vector3

Get normal vector of the line segment.

Returns
geometry_msgs::msg::Vector3

◆ getPoint()

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.

Parameters
sNormalized s value in coordinate along line segment.
denormalize_sIf true, s value should be normalized in range [0,1]. If false, s value is not normalized.
Returns
geometry_msgs::msg::Point

◆ getPose()

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.

Parameters
sNormalized s value in coordinate along line segment.
denormalize_sIf true, s value should be normalized in range [0,1]. If false, s value is not normalized.
fill_pitchIf 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.
Returns
geometry_msgs::msg::Pose

◆ getSquaredDistanceIn2D()

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)

Parameters
pointSpecified 3D point
Svalue of specified 3D point in coordinate along line segment.
denormalize_sIf true, the s value is denormalized. If false, the s value should be normalized in range [0,1].
Returns
double

◆ getSquaredDistanceVector()

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.

Parameters
pointSpecified 3D point
sS value of specified 3D point in coordinate along line segment.
denormalize_sIf true, the s value is denormalized. If false, the s value should be normalized in range [0,1].
Returns
geometry_msgs::msg::Vector3

◆ getSValue()

auto math::geometry::LineSegment::getSValue ( const geometry_msgs::msg::Pose &  pose,
double  threshold_distance,
bool  denormalize_s 
) const -> std::optional<double>

◆ isInBounds2D()

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.

Parameters
pointPoints you want to test.
Returns
  • true if the points is within the bounds.
  • false otherwise.

◆ isIntersect2D() [1/2]

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.

Parameters
pointpoint you want to check intersection.
Returns
true Intersection detected.
false Intersection not detected.

◆ isIntersect2D() [2/2]

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.

Parameters
lineline segments you want to check intersection.
Returns
true Intersection detected.
false Intersection not detected.

◆ relativePointPosition2D()

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.

Parameters
pointThe point to be evaluated.
Returns
  • 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).

Member Data Documentation

◆ end_point

const geometry_msgs::msg::Point math::geometry::LineSegment::end_point

◆ length

const double math::geometry::LineSegment::length

◆ length_2d

const double math::geometry::LineSegment::length_2d

◆ start_point

const geometry_msgs::msg::Point math::geometry::LineSegment::start_point

◆ vector

const geometry_msgs::msg::Vector3 math::geometry::LineSegment::vector

◆ vector_2d

const geometry_msgs::msg::Vector3 math::geometry::LineSegment::vector_2d

The documentation for this class was generated from the following files: