cloud_geometry::areas Namespace Reference

Functions

bool comparePoint2D (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Sort the Point32 points in vector structures according to their .x/.y values.
bool comparePoint3D (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Sort 3d points in vector structures according to their .x/.y/.z values.
double compute2DPolygonalArea (const geometry_msgs::Polygon &polygon)
 Compute the area of a 2D planar polygon patch. The normal is computed automatically.
double compute2DPolygonalArea (const geometry_msgs::Polygon &polygon, const std::vector< double > &normal)
 Compute the area of a 2D planar polygon patch - using a given normal.
double compute2DPolygonalArea (const sensor_msgs::PointCloud &points, const std::vector< double > &normal)
 Compute the area of a 2D planar polygon patch - using a given normal.
bool compute2DPolygonNormal (const geometry_msgs::Polygon &poly, std::vector< double > &normal)
void convexHull2D (const std::vector< geometry_msgs::Point32 > &points, geometry_msgs::Polygon &hull)
 Compute a 2D convex hull using Andrew's monotone chain algorithm.
void convexHull2D (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, const std::vector< double > &coeff, geometry_msgs::Polygon &hull)
 Compute a 2D convex hull in 3D space using Andrew's monotone chain algorithm.
bool isPointIn2DPolygon (const geometry_msgs::Point32 &point, const geometry_msgs::Polygon &polygon)
 Check if a 2d point (X and Y coordinates considered only!) is inside or outisde a given polygon.

Function Documentation

bool cloud_geometry::areas::comparePoint2D ( const geometry_msgs::Point32 &  p1,
const geometry_msgs::Point32 &  p2 
) [inline]

Sort the Point32 points in vector structures according to their .x/.y values.

Parameters:
p1 the first Point32 point
p2 the second Point32 point

Definition at line 55 of file areas.h.

bool cloud_geometry::areas::comparePoint3D ( const geometry_msgs::Point32 &  p1,
const geometry_msgs::Point32 &  p2 
) [inline]

Sort 3d points in vector structures according to their .x/.y/.z values.

Parameters:
p1 the first 3d point
p2 the second 3d point

Definition at line 69 of file areas.h.

double cloud_geometry::areas::compute2DPolygonalArea ( const geometry_msgs::Polygon &  polygon  ) 

Compute the area of a 2D planar polygon patch. The normal is computed automatically.

Parameters:
polygon the planar polygon
normal the plane normal

Definition at line 154 of file areas.cpp.

double cloud_geometry::areas::compute2DPolygonalArea ( const geometry_msgs::Polygon &  polygon,
const std::vector< double > &  normal 
)

Compute the area of a 2D planar polygon patch - using a given normal.

Parameters:
polygon the planar polygon
normal the plane normal

Definition at line 83 of file areas.cpp.

double cloud_geometry::areas::compute2DPolygonalArea ( const sensor_msgs::PointCloud &  points,
const std::vector< double > &  normal 
)

Compute the area of a 2D planar polygon patch - using a given normal.

Parameters:
points the point cloud (planar)
normal the plane normal

Definition at line 48 of file areas.cpp.

bool cloud_geometry::areas::compute2DPolygonNormal ( const geometry_msgs::Polygon &  poly,
std::vector< double > &  normal 
)

Definition at line 113 of file areas.cpp.

void cloud_geometry::areas::convexHull2D ( const std::vector< geometry_msgs::Point32 > &  points,
geometry_msgs::Polygon &  hull 
)

Compute a 2D convex hull using Andrew's monotone chain algorithm.

Note:
(code snippet inspired from http://www.softsurfer.com/Archive/algorithm_0109/algorithm_0109.htm) Copyright 2001, softSurfer (www.softsurfer.com)
Parameters:
points the 2D projected point cloud representing a planar model
hull the resultant 2D convex hull model as a Polygon

Definition at line 261 of file areas.cpp.

void cloud_geometry::areas::convexHull2D ( const sensor_msgs::PointCloud &  points,
const std::vector< int > &  indices,
const std::vector< double > &  coeff,
geometry_msgs::Polygon &  hull 
)

Compute a 2D convex hull in 3D space using Andrew's monotone chain algorithm.

Parameters:
points the point cloud
indices the point indices to use from the cloud (they must form a planar model)
coeff the *normalized* planar model coefficients
hull the resultant convex hull model as a Polygon3D

Definition at line 172 of file areas.cpp.

bool cloud_geometry::areas::isPointIn2DPolygon ( const geometry_msgs::Point32 &  point,
const geometry_msgs::Polygon &  polygon 
)

Check if a 2d point (X and Y coordinates considered only!) is inside or outisde a given polygon.

Note:
(This is highly optimized code taken from http://www.visibone.com/inpoly/) Copyright (c) 1995-1996 Galacticomm, Inc. Freeware source code.
Parameters:
point a 3D point projected onto the same plane as the polygon
polygon a polygon

Definition at line 398 of file areas.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


stereo_wall_detection
Author(s): Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:37:23 2013