Functions
cloud_geometry::intersections Namespace Reference

Functions

bool lineToBoxIntersection (const std::vector< double > &line, const std::vector< double > &cube)
 Bounding box intersection modified from Graphics Gems Vol I. The method returns a non-zero value if the bounding box is hit.
bool lineToCircleIntersection (const std::vector< double > &line, const std::vector< double > &circle)
 Check the intersection between a line segment and a circle.
bool lineWithLineIntersection (const std::vector< double > &line_a, const std::vector< double > &line_b, geometry_msgs::Point32 &point, double sqr_eps)
 Get the intersection of a two 3D lines in space as a 3D point.
bool lineWithPlaneIntersection (const std::vector< double > &plane, const std::vector< double > &line, geometry_msgs::Point32 &point)
 Get the intersection of a plane and a line in 3D space as a point.
bool planeWithCubeIntersection (const std::vector< double > &plane, const std::vector< double > &cube, geometry_msgs::Polygon &polygon)
 Obtain the intersection of a plane with an axis-aligned cube as a (sorted) 2D polygon.
bool planeWithPlaneIntersection (const std::vector< double > &plane_a, const std::vector< double > &plane_b, std::vector< double > &line)
 Get the intersection of two planes in 3D space as a 3D line.

Function Documentation

bool cloud_geometry::intersections::lineToBoxIntersection ( const std::vector< double > &  line,
const std::vector< double > &  cube 
)

Bounding box intersection modified from Graphics Gems Vol I. The method returns a non-zero value if the bounding box is hit.

Parameters:
linethe coefficients of the line (point, direction)
cubethe 6 bounds of the cube

Definition at line 242 of file intersections.cpp.

bool cloud_geometry::intersections::lineToCircleIntersection ( const std::vector< double > &  line,
const std::vector< double > &  circle 
)

Check the intersection between a line segment and a circle.

Parameters:
linethe coefficients of the line (point, direction)
circlethe coefficients of the circle (center, radius)

Definition at line 312 of file intersections.cpp.

bool cloud_geometry::intersections::lineWithLineIntersection ( const std::vector< double > &  line_a,
const std::vector< double > &  line_b,
geometry_msgs::Point32 &  point,
double  sqr_eps 
)

Get the intersection of a two 3D lines in space as a 3D point.

Parameters:
line_athe coefficients of the first line (point, direction)
line_bthe coefficients of the second line (point, direction)
pointholder for the computed 3D point
sqr_epsmaximum allowable squared distance to the true solution

Definition at line 127 of file intersections.cpp.

bool cloud_geometry::intersections::lineWithPlaneIntersection ( const std::vector< double > &  plane,
const std::vector< double > &  line,
geometry_msgs::Point32 &  point 
)

Get the intersection of a plane and a line in 3D space as a point.

Note:
if the line is parallel to the plane, point is returned empty
Parameters:
planethe coefficients of the plane (a,b,c,d)
linethe coefficients of the line (point, direction)
pointholder for the computed 3D point

Definition at line 96 of file intersections.cpp.

bool cloud_geometry::intersections::planeWithCubeIntersection ( const std::vector< double > &  plane,
const std::vector< double > &  cube,
geometry_msgs::Polygon &  polygon 
)

Obtain the intersection of a plane with an axis-aligned cube as a (sorted) 2D polygon.

Parameters:
planethe coefficients of the plane (a,b,c,d)
cubethe 6 bounds of the cube
polygonthe resulting polygon

Definition at line 154 of file intersections.cpp.

bool cloud_geometry::intersections::planeWithPlaneIntersection ( const std::vector< double > &  plane_a,
const std::vector< double > &  plane_b,
std::vector< double > &  line 
)

Get the intersection of two planes in 3D space as a 3D line.

Note:
if the planes are parallel, the method retunrns false, and line is zero-ed
Parameters:
plane_athe coefficients of the first plane (a,b,c,d)
plane_bthe coefficients of the second plane (a,b,c,d)
lineholder for the computed line coefficients (point, direction)

Definition at line 52 of file intersections.cpp.



door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Wed Dec 11 2013 14:17:01