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
00044
00045 #include <ros/ros.h>
00046 #include <roslib/Header.h>
00047 #include <mapping_msgs/PolygonalMap.h>
00048
00049
00050 #include <door_handle_detector/geometric_helper.h>
00051
00052
00053 #include "door_handle_detector/DoorsDetector.h"
00054 #include "door_handle_detector/DoorsDetectorCloud.h"
00055
00056 #include <angles/angles.h>
00057
00058 namespace door_handle_detector{
00059
00060 class HandleDetector
00061 {
00062 public:
00063 HandleDetector ();
00064 ~HandleDetector (){};
00065
00067 bool detectHandleSrv (door_handle_detector::DoorsDetector::Request &req,
00068 door_handle_detector::DoorsDetector::Response &resp);
00069 bool detectHandleCloudSrv (door_handle_detector::DoorsDetectorCloud::Request &req,
00070 door_handle_detector::DoorsDetectorCloud::Response &resp);
00071
00072 ros::ServiceServer detect_srv_, detect_cloud_srv_;
00073 ros::Publisher vis_marker_pub_, handle_pol_pub_, handle_reg_pub_, door_outliers_pub_;
00074
00075
00076 private:
00089 void refineHandleCandidatesWithDoorOutliers (std::vector<int> &handle_indices, std::vector<int> &outliers,
00090 const geometry_msgs::Polygon &polygon,
00091 const std::vector<double> &coeff, const geometry_msgs::Point32 &door_axis,
00092 const door_msgs::Door& door_prior,
00093 sensor_msgs::PointCloud& pointcloud) const;
00094
00110 void getHandleCandidates (const std::vector<int> &indices, const std::vector<double> &coeff,
00111 const geometry_msgs::Polygon &polygon, const geometry_msgs::Polygon &polygon_tr,
00112 Eigen::Matrix4d transformation, std::vector<int> &handle_indices,
00113 sensor_msgs::PointCloud& pointcloud, geometry_msgs::PointStamped& viewpoint_cloud) const;
00114
00130 void getDoorOutliers (const std::vector<int> &indices, const std::vector<int> &inliers,
00131 const std::vector<double> &coeff, const geometry_msgs::Polygon &polygon,
00132 const geometry_msgs::Polygon &polygon_tr, Eigen::Matrix4d transformation,
00133 std::vector<int> &outliers, sensor_msgs::PointCloud& pointcloud) const;
00134
00136 void cloud_cb (const sensor_msgs::PointCloudConstPtr& cloud);
00137
00138
00139
00140 bool detectHandle (const door_msgs::Door& door, sensor_msgs::PointCloud pointcloud,
00141 std::vector<door_msgs::Door>& result) const;
00142
00143 ros::NodeHandle node_tilde_, node_;
00144
00145
00146 sensor_msgs::PointCloud pointcloud_;
00147 geometry_msgs::Point32 z_axis_;
00148
00149
00150 tf::TransformListener tf_;
00151
00152 std::string input_cloud_topic_, parameter_frame_, fixed_frame_;
00153 unsigned int num_clouds_received_;
00154
00155 int k_search_;
00156
00157
00158 double handle_distance_door_max_threshold_;
00159
00160
00161 double handle_max_height_, handle_min_height_;
00162
00163
00164 double euclidean_cluster_angle_tolerance_, euclidean_cluster_distance_tolerance_;
00165 int euclidean_cluster_min_pts_;
00166
00167 double distance_from_door_margin_, min_plane_pts_, sac_distance_threshold_;
00168
00169 int global_marker_id_;
00170
00171 };
00172 }