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 _DOOR_HANDLE_GEOMETRIC_HELPER_H_
00034 #define _DOOR_HANDLE_GEOMETRIC_HELPER_H_
00035
00036 #include <math.h>
00037 #include <vector>
00038
00039
00040 #include <ros/ros.h>
00041
00042 #include <sensor_msgs/PointCloud.h>
00043 #include <geometry_msgs/Polygon.h>
00044 #include <geometry_msgs/Point32.h>
00045 #include <geometry_msgs/PointStamped.h>
00046 #include <visualization_msgs/Marker.h>
00047 #include <door_msgs/Door.h>
00048
00049 #include <tf/transform_listener.h>
00050
00051
00052
00053 #include <door_handle_detector/geometry/angles.h>
00054 #include <door_handle_detector/geometry/areas.h>
00055 #include <door_handle_detector/geometry/distances.h>
00056 #include <door_handle_detector/geometry/intersections.h>
00057 #include <door_handle_detector/geometry/nearest.h>
00058 #include <door_handle_detector/geometry/transforms.h>
00059 #include <door_handle_detector/geometry/point.h>
00060 #include <door_handle_detector/geometry/projections.h>
00061 #include <door_handle_detector/geometry/statistics.h>
00062 #include <door_handle_detector/geometry/transforms.h>
00063 #include <door_handle_detector/kdtree/kdtree_ann.h>
00064
00065 #include <door_handle_detector/sample_consensus/sac.h>
00066 #include <door_handle_detector/sample_consensus/msac.h>
00067 #include <door_handle_detector/sample_consensus/ransac.h>
00068 #include <door_handle_detector/sample_consensus/lmeds.h>
00069 #include <door_handle_detector/sample_consensus/sac_model_plane.h>
00070 #include <door_handle_detector/sample_consensus/sac_model_oriented_line.h>
00071
00072
00074
00080 inline void
00081 transformPoint (const tf::TransformListener *tf, const std::string &target_frame,
00082 const tf::Stamped< geometry_msgs::Point32 > &stamped_in, tf::Stamped< geometry_msgs::Point32 > &stamped_out)
00083 {
00084 tf::Stamped<tf::Point> tmp;
00085 tmp.stamp_ = stamped_in.stamp_;
00086 tmp.frame_id_ = stamped_in.frame_id_;
00087 tmp[0] = stamped_in.x;
00088 tmp[1] = stamped_in.y;
00089 tmp[2] = stamped_in.z;
00090
00091 tf->transformPoint (target_frame, tmp, tmp);
00092
00093 stamped_out.stamp_ = tmp.stamp_;
00094 stamped_out.frame_id_ = tmp.frame_id_;
00095 stamped_out.x = tmp[0];
00096 stamped_out.y = tmp[1];
00097 stamped_out.z = tmp[2];
00098 }
00099
00101
00108 inline double
00109 transformDoubleValueTF (double val, std::string src_frame, std::string tgt_frame, ros::Time stamp, tf::TransformListener *tf)
00110 {
00111 geometry_msgs::Point32 temp;
00112 temp.x = temp.y = 0;
00113 temp.z = val;
00114 tf::Stamped<geometry_msgs::Point32> temp_stamped (temp, stamp, src_frame);
00115 transformPoint (tf, tgt_frame, temp_stamped, temp_stamped);
00116 return (temp_stamped.z);
00117 }
00118
00119
00121
00122 inline bool
00123 compareRegions (const std::vector<int> &a, const std::vector<int> &b)
00124 {
00125 return (a.size () < b.size ());
00126 }
00127
00129
00130 inline bool
00131 compareDoorsWeight (const door_msgs::Door &a, const door_msgs::Door &b)
00132 {
00133 return (a.weight < b.weight);
00134 }
00136
00141 inline double
00142 getRGB (float r, float g, float b)
00143 {
00144 int res = (int(r * 255) << 16) | (int(g*255) << 8) | int(b*255);
00145 double rgb = *(float*)(&res);
00146 return (rgb);
00147 }
00148
00150
00156 inline void
00157 sendMarker (float px, float py, float pz, std::string frame_id, ros::Publisher& pub, int &id,
00158 int r, int g, int b, double radius = 0.03)
00159 {
00160 visualization_msgs::Marker mk;
00161 mk.header.stamp = ros::Time::now ();
00162
00163 mk.header.frame_id = frame_id;
00164
00165 mk.id = id++;
00166 mk.ns = "geometric_helper";
00167 mk.type = visualization_msgs::Marker::SPHERE;
00168 mk.action = visualization_msgs::Marker::ADD;
00169 mk.pose.position.x = px;
00170 mk.pose.position.y = py;
00171 mk.pose.position.z = pz;
00172 mk.pose.orientation.w = 1.0;
00173 mk.scale.x = mk.scale.y = mk.scale.z = radius * 2.0;
00174 mk.color.a = 1.0;
00175 mk.color.r = r;
00176 mk.color.g = g;
00177 mk.color.b = b;
00178
00179 pub.publish (mk);
00180 }
00181
00182 void obtainCloudIndicesSet (sensor_msgs::PointCloud *points, std::vector<int> &indices, door_msgs::Door& door,
00183 tf::TransformListener *tf, std::string fixed_param_frame, double min_z_bounds, double max_z_bounds, double frame_multiplier);
00184
00185
00186 int fitSACOrientedLine (sensor_msgs::PointCloud &points, const std::vector<int> &indices, double dist_thresh, const geometry_msgs::Point32 &axis, double eps_angle, std::vector<int> &line_inliers);
00187 int fitSACOrientedLine (sensor_msgs::PointCloud &points, double dist_thresh, const geometry_msgs::Point32 &axis, double eps_angle, std::vector<int> &line_inliers);
00188
00189 void get3DBounds (geometry_msgs::Point32 *p1, geometry_msgs::Point32 *p2, geometry_msgs::Point32 &min_b, geometry_msgs::Point32 &max_b,
00190 double min_z_bounds, double max_z_bounds, int multiplier);
00191
00192 void getCloudViewPoint (const std::string cloud_frame, geometry_msgs::PointStamped &viewpoint_cloud, const tf::TransformListener *tf);
00193
00194 bool checkDoorEdges (const geometry_msgs::Polygon &poly, const geometry_msgs::Point32 &z_axis, double min_height, double eps_angle,
00195 double &door_frame1, double &door_frame2);
00196
00197 void selectBestDistributionStatistics (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, int d_idx, std::vector<int> &inliers);
00198 void selectBestDualDistributionStatistics (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, int d_idx_1, int d_idx_2, std::vector<int> &inliers);
00199
00200 bool checkIfClusterPerpendicular (sensor_msgs::PointCloud *points, std::vector<int> *indices, geometry_msgs::PointStamped *viewpoint,
00201 std::vector<double> *coeff, double eps_angle);
00202 void findClusters (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, double tolerance, std::vector<std::vector<int> > &clusters,
00203 int nx_idx, int ny_idx, int nz_idx, double eps_angle, unsigned int min_pts_per_cluster = 1);
00204
00205 bool fitSACPlane (sensor_msgs::PointCloud &points, std::vector<int> indices, std::vector<int> &inliers, std::vector<double> &coeff,
00206 const geometry_msgs::PointStamped &viewpoint_cloud, double dist_thresh, int min_pts);
00207
00208 void estimatePointNormals (const sensor_msgs::PointCloud &points, const std::vector<int> &point_indices, sensor_msgs::PointCloud &points_down, int k, const geometry_msgs::PointStamped &viewpoint_cloud);
00209 void estimatePointNormals (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_down, int k, const geometry_msgs::PointStamped &viewpoint_cloud);
00210 void estimatePointNormals (sensor_msgs::PointCloud &points, const std::vector<int> &point_indices, int k, const geometry_msgs::PointStamped &viewpoint_cloud);
00211
00212 void growCurrentCluster (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, const std::vector<int> &cluster,
00213 std::vector<int> &inliers, double dist_thresh);
00214
00215 #endif