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
00031
00032
00033
00034
00035
00036 #include <string>
00037 #include <ros/ros.h>
00038 #include <tf/tf.h>
00039 #include <tf/transform_listener.h>
00040 #include <sensor_msgs/PointCloud2.h>
00041 #include <pcl/filters/passthrough.h>
00042 #include <pcl/kdtree/kdtree_flann.h>
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/point_types.h>
00045 #include <pcl/filters/passthrough.h>
00046 #include <pcl/io/io.h>
00047 #include "pcl/io/pcd_io.h"
00048 #include <pcl/filters/extract_indices.h>
00049 #include <pcl/segmentation/extract_clusters.h>
00050 #include <pcl_ros/transforms.h>
00051
00052 #include "tabletop_object_detector/SegmentObjectInHand.h"
00053
00054 namespace tabletop_object_detector {
00055
00056 class ObjectInHandSegmenter
00057 {
00058 typedef pcl::PointXYZ Point;
00059 typedef pcl::KdTree<Point>::Ptr KdTreePtr;
00060
00061 public:
00062 ObjectInHandSegmenter(ros::NodeHandle nh) : nh_(nh), priv_nh_("~")
00063 {
00064
00065 double box_w = 0.3;
00066 priv_nh_.param<double>("x_filter_min", x_filter_min_, -(box_w - 0.185));
00067 priv_nh_.param<double>("x_filter_max", x_filter_max_, box_w + 0.185);
00068 priv_nh_.param<double>("y_filter_min", y_filter_min_, -box_w);
00069 priv_nh_.param<double>("y_filter_max", y_filter_max_, box_w);
00070 priv_nh_.param<double>("z_filter_min", z_filter_min_, -box_w);
00071 priv_nh_.param<double>("z_filter_max", z_filter_max_, box_w);
00072
00073
00074 priv_nh_.param<double>("object_center_x", object_center_x_, 0.185);
00075 priv_nh_.param<double>("object_center_y", object_center_y_, 0);
00076 priv_nh_.param<double>("object_center_z", object_center_z_, 0);
00077 priv_nh_.param<double>("max_dist_from_center", max_dist_from_center_, 0.15);
00078
00079
00080 priv_nh_.param<double>("cluster_distance", cluster_distance_, 0.025);
00081 priv_nh_.param<double>("min_cluster_size", min_cluster_size_, 0.025);
00082 priv_nh_.param<std::string>("self_filtered_cloud_name", self_filtered_cloud_name_,
00083 std::string("/narrow_stereo_textured/points_filtered2"));
00084
00085
00086 priv_nh_.param<std::string>("visualization_topic", visualization_topic_, "segment_object_in_hand_output_cluster");
00087 pub_cloud_ = nh_.advertise<sensor_msgs::PointCloud2>(visualization_topic_, 1);
00088
00089
00090 segmentation_srv_ = nh_.advertiseService(nh_.resolveName("segment_object_in_hand_srv"),
00091 &ObjectInHandSegmenter::serviceCallback, this);
00092
00093 }
00094
00095 private:
00096
00097 ros::NodeHandle nh_, priv_nh_;
00098 tf::TransformListener listener_;
00099
00100
00101 double x_filter_min_, x_filter_max_;
00102 double y_filter_min_, y_filter_max_;
00103 double z_filter_min_, z_filter_max_;
00104
00105
00106 ros::Subscriber sub_cloud_;
00107 ros::Publisher pub_cloud_;
00108 std::string visualization_topic_;
00109
00110
00111 double cluster_distance_;
00112 double min_cluster_size_;
00113 std::string self_filtered_cloud_name_;
00114
00115
00116 double object_center_x_, object_center_y_, object_center_z_;
00117 double max_dist_from_center_;
00118
00119
00120 ros::ServiceServer segmentation_srv_;
00121
00125 bool serviceCallback(SegmentObjectInHand::Request &request,
00126 SegmentObjectInHand::Response &response)
00127 {
00128 ROS_DEBUG("Got service request for segment_object_in_hand");
00129 int result = segmentObject(request.wrist_frame, response.cluster);
00130 if(result == 0) response.result = response.SUCCESS;
00131 else if(result == 1) response.result = response.NO_CLOUD_RECEIVED;
00132 else if(result == 2) response.result = response.TF_ERROR;
00133 else response.result = response.OTHER_ERROR;
00134 return true;
00135 }
00136
00137
00141 int segmentObject(std::string wrist_frame, sensor_msgs::PointCloud2 &output_cluster)
00142 {
00143 ROS_DEBUG("waiting for self-filtered point cloud");
00144 pcl::PointCloud<Point> input_cloud;
00145
00146
00147 sensor_msgs::PointCloud2ConstPtr cloud_msg =
00148 ros::topic::waitForMessage<sensor_msgs::PointCloud2>(self_filtered_cloud_name_,
00149 nh_, ros::Duration(5.0));
00150 if(!cloud_msg)
00151 {
00152 ROS_ERROR("No point cloud received!");
00153 return 1;
00154 }
00155
00156 ROS_DEBUG("Point cloud received; processing");
00157 pcl::PointCloud<Point> wrist_frame_cloud;
00158
00159 if (!wrist_frame.empty())
00160 {
00161
00162 pcl::fromROSMsg(*cloud_msg, input_cloud);
00163
00164
00165 try
00166 {
00167 pcl_ros::transformPointCloud(wrist_frame, input_cloud, wrist_frame_cloud, listener_);
00168 }
00169 catch (tf::TransformException ex)
00170 {
00171 ROS_ERROR("Failed to transform cloud from frame %s into frame %s",
00172 input_cloud.header.frame_id.c_str(), wrist_frame.c_str());
00173 return 2;
00174 }
00175 ROS_DEBUG("Input cloud converted to %s frame", wrist_frame.c_str());
00176 }
00177 else
00178 {
00179 ROS_ERROR("no wrist_frame specified!");
00180 return 3;
00181 }
00182
00183
00184 pcl::PassThrough<Point> pass_;
00185 pcl::PointCloud<Point> cloud_filtered;
00186 pcl::PointCloud<Point>::ConstPtr cloud_ptr = boost::make_shared<const pcl::PointCloud<Point> > (wrist_frame_cloud);
00187 pass_.setInputCloud (cloud_ptr);
00188 pass_.setFilterFieldName ("z");
00189 pass_.setFilterLimits (z_filter_min_, z_filter_max_);
00190 pass_.filter (wrist_frame_cloud);
00191 cloud_ptr = boost::make_shared<const pcl::PointCloud<Point> > (wrist_frame_cloud);
00192 pass_.setInputCloud (cloud_ptr);
00193 pass_.setFilterFieldName ("y");
00194 pass_.setFilterLimits (y_filter_min_, y_filter_max_);
00195 pass_.filter (wrist_frame_cloud);
00196 cloud_ptr = boost::make_shared<const pcl::PointCloud<Point> > (wrist_frame_cloud);
00197 pass_.setInputCloud (cloud_ptr);
00198 pass_.setFilterFieldName ("x");
00199 pass_.setFilterLimits (x_filter_min_, x_filter_max_);
00200 pass_.filter (wrist_frame_cloud);
00201 cloud_ptr = boost::make_shared<const pcl::PointCloud<Point> > (wrist_frame_cloud);
00202
00203 if(wrist_frame_cloud.points.size() == 0){
00204 ROS_INFO("no points left after passthrough!");
00205 return 3;
00206 }
00207
00208
00209
00210
00211
00212
00213 pcl::EuclideanClusterExtraction<Point> pcl_cluster_;
00214 KdTreePtr clusters_tree_;
00215 std::vector<pcl::PointIndices> clusters;
00216 clusters_tree_ = boost::make_shared<pcl::KdTreeFLANN<Point> > ();
00217 pcl_cluster_.setClusterTolerance (cluster_distance_);
00218 pcl_cluster_.setMinClusterSize (min_cluster_size_);
00219 pcl_cluster_.setSearchMethod (clusters_tree_);
00220 pcl_cluster_.setInputCloud (cloud_ptr);
00221 pcl_cluster_.extract (clusters);
00222
00223
00224 pcl::PointCloud<Point> output_cluster_pcl;
00225 if(clusters.size() != 0)
00226 {
00227 combineClustersNearPoint(clusters, wrist_frame_cloud, wrist_frame, object_center_x_, object_center_y_, object_center_z_, max_dist_from_center_, output_cluster_pcl);
00228 if(output_cluster_pcl.points.size() == 0)
00229 {
00230 ROS_WARN("No points in resulting object cloud!");
00231 }
00232
00233
00234 pcl::toROSMsg(output_cluster_pcl, output_cluster);
00235 output_cluster.header.frame_id = wrist_frame;
00236 output_cluster.header.stamp = ros::Time::now();
00237
00238
00239 pub_cloud_.publish(output_cluster);
00240
00241 }
00242 else
00243 {
00244 ROS_WARN("No clusters detected!");
00245 }
00246 return 0;
00247 }
00248
00252 void combineClustersNearPoint(std::vector<pcl::PointIndices> clusters, pcl::PointCloud<Point> input_cloud, std::string wrist_frame, double x, double y, double z, double dist, pcl::PointCloud<Point> &output_cluster)
00253 {
00254 output_cluster.header.stamp = ros::Time(0);
00255 for(size_t cluster_ind=0; cluster_ind < clusters.size(); cluster_ind++)
00256 {
00257 ROS_DEBUG("cluster_ind: %d, size: %d\n", (int)cluster_ind, (int)clusters[cluster_ind].indices.size());
00258
00259
00260 double point_dist;
00261 double xdiff, ydiff, zdiff;
00262 bool cluster_good = 0;
00263 for (size_t j = 0; j < clusters[cluster_ind].indices.size(); ++j)
00264 {
00265 xdiff = x - input_cloud.points[clusters[cluster_ind].indices[j]].x;
00266 ydiff = y - input_cloud.points[clusters[cluster_ind].indices[j]].y;
00267 zdiff = z - input_cloud.points[clusters[cluster_ind].indices[j]].z;
00268 point_dist = sqrt(xdiff*xdiff + ydiff*ydiff + zdiff*zdiff);
00269 if(point_dist < dist)
00270 {
00271 ROS_DEBUG("keeping cluster\n");
00272 cluster_good = 1;
00273 break;
00274 }
00275 }
00276
00277
00278 if(cluster_good)
00279 {
00280 double current_size = output_cluster.points.size();
00281 output_cluster.points.resize(current_size + clusters[cluster_ind].indices.size());
00282 for (size_t k= 0; k < clusters[cluster_ind].indices.size(); ++k)
00283 {
00284 output_cluster.points[current_size + k].x = input_cloud.points[clusters[cluster_ind].indices[k]].x;
00285 output_cluster.points[current_size + k].y = input_cloud.points[clusters[cluster_ind].indices[k]].y;
00286 output_cluster.points[current_size + k].z = input_cloud.points[clusters[cluster_ind].indices[k]].z;
00287 }
00288 }
00289 }
00290 ROS_DEBUG("output_cluster size: %d\n", (int)output_cluster.points.size());
00291 }
00292
00293 };
00294
00295 }
00296
00297 int main(int argc, char **argv)
00298 {
00299 ros::init(argc, argv, "segment_object_in_hand_node");
00300 ros::NodeHandle nh;
00301
00302 tabletop_object_detector::ObjectInHandSegmenter node(nh);
00303 ROS_INFO("Segment object in hand ready for service requests");
00304 ros::spin();
00305 return 0;
00306 }