Classes | Functions
swri_geometry_util Namespace Reference

Classes

class  Polygon
 
struct  PolygonD
 
struct  Vertex
 

Functions

bool ClosestPointToLines (const tf::Vector3 &a1, const tf::Vector3 &a2, const tf::Vector3 &b1, const tf::Vector3 &b2, tf::Vector3 &point)
 
bool CubicSplineInterpolation (const std::vector< cv::Vec2d > &points, double delta, std::vector< std::vector< cv::Vec2d > > &splines)
 
bool CubicSplineInterpolation (const std::vector< tf::Vector3 > &points, double delta, std::vector< std::vector< tf::Vector3 > > &splines)
 
double DistanceFromLineSegment (const tf::Vector3 &line_start, const tf::Vector3 &line_end, const tf::Vector3 &point)
 
double DistanceFromLineSegment (const cv::Vec2d &line_start, const cv::Vec2d &line_end, const cv::Vec2d &point)
 
double DistanceFromPlane (const tf::Vector3 &plane_normal, const tf::Vector3 &plane_point, const tf::Vector3 &point)
 
double DistanceFromPolygon (const std::vector< cv::Vec2d > &polygon, const cv::Vec2d &point)
 
bool LineIntersection (const cv::Vec2d &p1, const cv::Vec2d &p2, const cv::Vec2d &p3, const cv::Vec2d &p4, cv::Vec2d &c)
 
bool LineSegmentIntersection (const cv::Vec2d &p1, const cv::Vec2d &p2, const cv::Vec2d &p3, const cv::Vec2d &p4, cv::Vec2d &c)
 
bool PointInPolygon (const std::vector< cv::Vec2d > &polygon, const cv::Vec2d &point)
 
bool PointOnLineSegment (const cv::Vec2d &p1, const cv::Vec2d &p2, const cv::Vec2d &p3)
 
double PolygonIntersectionArea (const std::vector< cv::Vec2d > &a, const std::vector< cv::Vec2d > &b)
 
bool PolygonsIntersect (const std::vector< cv::Vec2d > &a, const std::vector< cv::Vec2d > &b)
 
tf::Vector3 ProjectPointToPlane (const tf::Vector3 &plane_normal, const tf::Vector3 &plane_point, const tf::Vector3 &point)
 
tf::Vector3 ProjectToLineSegment (const tf::Vector3 &line_start, const tf::Vector3 &line_end, const tf::Vector3 &point)
 
cv::Vec2d ProjectToLineSegment (const cv::Vec2d &line_start, const cv::Vec2d &line_end, const cv::Vec2d &point)
 

Function Documentation

bool swri_geometry_util::ClosestPointToLines ( const tf::Vector3 a1,
const tf::Vector3 a2,
const tf::Vector3 b1,
const tf::Vector3 b2,
tf::Vector3 point 
)

Find closest point to two 3D lines.

Parameters
[in]a1First point on line 1.
[in]a2Second point on line 1.
[in]b1First point on line 2.
[in]b2Second point on line 2.
[out]pointThe closest point to both lines.
Returns
True unless a1 == a2, b1 == b2, or lines are parallel.

Definition at line 167 of file geometry_util.cpp.

bool swri_geometry_util::CubicSplineInterpolation ( const std::vector< cv::Vec2d > &  points,
double  delta,
std::vector< std::vector< cv::Vec2d > > &  splines 
)

Definition at line 37 of file cubic_spline.cpp.

bool swri_geometry_util::CubicSplineInterpolation ( const std::vector< tf::Vector3 > &  points,
double  delta,
std::vector< std::vector< tf::Vector3 > > &  splines 
)

Definition at line 159 of file cubic_spline.cpp.

double swri_geometry_util::DistanceFromLineSegment ( const tf::Vector3 line_start,
const tf::Vector3 line_end,
const tf::Vector3 point 
)

Definition at line 51 of file geometry_util.cpp.

double swri_geometry_util::DistanceFromLineSegment ( const cv::Vec2d &  line_start,
const cv::Vec2d &  line_end,
const cv::Vec2d &  point 
)

Definition at line 59 of file geometry_util.cpp.

double swri_geometry_util::DistanceFromPlane ( const tf::Vector3 plane_normal,
const tf::Vector3 plane_point,
const tf::Vector3 point 
)

Calculate the distance from a point to a plane.

Parameters
[in]plane_normalThe normal vector of the plane.
[in]plane_pointA point on the plane.
[in]pointThe point to measure the distance of.
Returns
The distance of the point from the plane.

Definition at line 34 of file geometry_util.cpp.

double swri_geometry_util::DistanceFromPolygon ( const std::vector< cv::Vec2d > &  polygon,
const cv::Vec2d &  point 
)

Calcuate the distance between a point and the bounds of a polygon.

The polygon vertices are assumed to be ordered sequentially.

The distance returned is positive even if the point is within the polygon.

Parameters
[in]polygonThe list of polygon vertices.
[in]pointThe point.
Returns
The distance from the point to the polygon. -1 is returned if the polygon is empty.

Definition at line 149 of file geometry_util.cpp.

bool swri_geometry_util::LineIntersection ( const cv::Vec2d &  p1,
const cv::Vec2d &  p2,
const cv::Vec2d &  p3,
const cv::Vec2d &  p4,
cv::Vec2d &  c 
)

Calculate the instersection between two lines defined by 4 points.

Parameters
[in]p1First point of line segment 1.
[in]p2Second point of line segment 1.
[in]p3First point of line segment 2.
[in]p4Second point of line segment 2.
[out]cThe intersection point.
Returns
True if the lines are not parallel.

Definition at line 43 of file intersection.cpp.

bool swri_geometry_util::LineSegmentIntersection ( const cv::Vec2d &  p1,
const cv::Vec2d &  p2,
const cv::Vec2d &  p3,
const cv::Vec2d &  p4,
cv::Vec2d &  c 
)

Calculate the instersection between two line segments defined by 4 points.

In the case of parallel overlapping segments, the intersection point closest to p1 is returned.

Parameters
[in]p1First point of line segment 1.
[in]p2Second point of line segment 1.
[in]p3First point of line segment 2.
[in]p4Second point of line segment 2.
[out]cThe intersection point.
Returns
True if the line segments intersect.

Definition at line 65 of file intersection.cpp.

bool swri_geometry_util::PointInPolygon ( const std::vector< cv::Vec2d > &  polygon,
const cv::Vec2d &  point 
)

Test if a point is within the bounds of a polygon.

The polygon is assumed to be non-intersecting and that the vertices are ordered sequentially in clock-wise fashion.

Parameters
[in]polygonThe list of polygon vertices.
[in]pointThe point.
Returns
True if the point is within the bounds of the polygon.

Definition at line 119 of file geometry_util.cpp.

bool swri_geometry_util::PointOnLineSegment ( const cv::Vec2d &  p1,
const cv::Vec2d &  p2,
const cv::Vec2d &  p3 
)

Check if a point is on a line segment.

Parameters
[in]p1The point.
[in]p2First point of the line segemnt.
[in]p3Second point of the line segemnt.
Returns
True if the point is on the line segment.

Definition at line 155 of file intersection.cpp.

double swri_geometry_util::PolygonIntersectionArea ( const std::vector< cv::Vec2d > &  a,
const std::vector< cv::Vec2d > &  b 
)

Definition at line 213 of file intersection.cpp.

bool swri_geometry_util::PolygonsIntersect ( const std::vector< cv::Vec2d > &  a,
const std::vector< cv::Vec2d > &  b 
)

Definition at line 176 of file intersection.cpp.

tf::Vector3 swri_geometry_util::ProjectPointToPlane ( const tf::Vector3 plane_normal,
const tf::Vector3 plane_point,
const tf::Vector3 point 
)

Definition at line 42 of file geometry_util.cpp.

tf::Vector3 swri_geometry_util::ProjectToLineSegment ( const tf::Vector3 line_start,
const tf::Vector3 line_end,
const tf::Vector3 point 
)

Definition at line 70 of file geometry_util.cpp.

cv::Vec2d swri_geometry_util::ProjectToLineSegment ( const cv::Vec2d &  line_start,
const cv::Vec2d &  line_end,
const cv::Vec2d &  point 
)

Definition at line 94 of file geometry_util.cpp.



swri_geometry_util
Author(s): Marc Alban
autogenerated on Fri Jun 7 2019 22:05:39