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 sensor_msgs::PointCloud &points, const std::vector< double > &normal) |
| Compute the area of a 2D planar polygon patch - using a given normal. | |
| 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 geometry_msgs::Polygon &polygon) |
| Compute the area of a 2D planar polygon patch. The normal is computed automatically. | |
| bool | compute2DPolygonNormal (const geometry_msgs::Polygon &poly, std::vector< double > &normal) |
| 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. | |
| void | convexHull2D (const std::vector< geometry_msgs::Point32 > &points, geometry_msgs::Polygon &hull) |
| Compute a 2D convex hull 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. | |
| bool cloud_geometry::areas::comparePoint2D | ( | const geometry_msgs::Point32 & | p1, |
| const geometry_msgs::Point32 & | p2 | ||
| ) | [inline] |
| bool cloud_geometry::areas::comparePoint3D | ( | const geometry_msgs::Point32 & | p1, |
| const geometry_msgs::Point32 & | p2 | ||
| ) | [inline] |
| double cloud_geometry::areas::compute2DPolygonalArea | ( | const sensor_msgs::PointCloud & | points, |
| const std::vector< double > & | normal | ||
| ) |
| double cloud_geometry::areas::compute2DPolygonalArea | ( | const geometry_msgs::Polygon & | polygon, |
| const std::vector< double > & | normal | ||
| ) |
| double cloud_geometry::areas::compute2DPolygonalArea | ( | const geometry_msgs::Polygon & | polygon | ) |
| bool cloud_geometry::areas::compute2DPolygonNormal | ( | const geometry_msgs::Polygon & | poly, |
| std::vector< double > & | normal | ||
| ) |
| 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.
| 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 |
| 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.
| points | the 2D projected point cloud representing a planar model |
| hull | the resultant 2D convex hull model as a Polygon |
| 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.
| point | a 3D point projected onto the same plane as the polygon |
| polygon | a polygon |