00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00033 #ifndef _CLOUD_GEOMETRY_AREAS_H_
00034 #define _CLOUD_GEOMETRY_AREAS_H_
00035
00036
00037 #include <geometry_msgs/Point32.h>
00038 #include <sensor_msgs/PointCloud.h>
00039 #include <geometry_msgs/Polygon.h>
00040
00041 #include <door_handle_detector/geometry/nearest.h>
00042
00043 namespace cloud_geometry
00044 {
00045
00046 namespace areas
00047 {
00048
00050
00054 inline bool
00055 comparePoint2D (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
00056 {
00057 if (p1.x < p2.x) return (true);
00058 else if (p1.x > p2.x) return (false);
00059 else if (p1.y < p2.y) return (true);
00060 else return (false);
00061 }
00062
00064
00068 inline bool
00069 comparePoint3D (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
00070 {
00071 if (p1.x < p2.x) return (true);
00072 else if (p1.x > p2.x) return (false);
00073 else if (p1.y < p2.y) return (true);
00074 else if (p1.y > p2.y) return (false);
00075 else if (p1.z < p2.z) return (true);
00076 else return (false);
00077 }
00078
00079 bool compute2DPolygonNormal(const geometry_msgs::Polygon &poly, std::vector<double> &normal);
00080 double compute2DPolygonalArea (const sensor_msgs::PointCloud &points, const std::vector<double> &normal);
00081 double compute2DPolygonalArea (const geometry_msgs::Polygon &polygon, const std::vector<double> &normal);
00082 double compute2DPolygonalArea (const geometry_msgs::Polygon &polygon);
00083 void convexHull2D (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, const std::vector<double> &coeff, geometry_msgs::Polygon &hull);
00084 void convexHull2D (const std::vector<geometry_msgs::Point32> &points, geometry_msgs::Polygon &hull);
00085
00086 bool isPointIn2DPolygon (const geometry_msgs::Point32 &point, const geometry_msgs::Polygon &polygon);
00087 }
00088 }
00089
00090 #endif