$search
00001 /* 00002 * Copyright (c) 2011, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 * Author: Michael Ferguson, Helen Oleynikova 00030 */ 00031 00032 #include <ros/ros.h> 00033 #include <sensor_msgs/PointCloud2.h> 00034 #include <actionlib/server/simple_action_server.h> 00035 #include <turtlebot_block_manipulation/BlockDetectionAction.h> 00036 00037 #include <tf/transform_listener.h> 00038 00039 #include <pcl/ros/conversions.h> 00040 #include <pcl/point_cloud.h> 00041 #include <pcl/point_types.h> 00042 #include <pcl/filters/passthrough.h> 00043 #include <pcl/segmentation/extract_clusters.h> 00044 #include <pcl/filters/extract_indices.h> 00045 #include <pcl/kdtree/kdtree_flann.h> 00046 #include <pcl/sample_consensus/method_types.h> 00047 #include <pcl/sample_consensus/model_types.h> 00048 #include <pcl/segmentation/sac_segmentation.h> 00049 #include <pcl/segmentation/extract_clusters.h> 00050 00051 00052 #include <pcl_ros/point_cloud.h> 00053 #include <pcl_ros/transforms.h> 00054 00055 #include <cmath> 00056 #include <algorithm> 00057 00058 namespace turtlebot_block_manipulation 00059 { 00060 00061 class BlockDetectionServer 00062 { 00063 private: 00064 00065 ros::NodeHandle nh_; 00066 actionlib::SimpleActionServer<turtlebot_block_manipulation::BlockDetectionAction> as_; 00067 std::string action_name_; 00068 turtlebot_block_manipulation::BlockDetectionFeedback feedback_; 00069 turtlebot_block_manipulation::BlockDetectionResult result_; 00070 turtlebot_block_manipulation::BlockDetectionGoalConstPtr goal_; 00071 ros::Subscriber sub_; 00072 ros::Publisher pub_; 00073 00074 tf::TransformListener tf_listener_; 00075 00076 // Parameters from goal 00077 std::string arm_link; 00078 double block_size; 00079 double table_height; 00080 00081 ros::Publisher block_pub_; 00082 00083 // Parameters from node 00084 00085 public: 00086 BlockDetectionServer(const std::string name) : 00087 nh_("~"), as_(name, false), action_name_(name) 00088 { 00089 // Load parameters from the server. 00090 00091 00092 00093 // Register the goal and feeback callbacks. 00094 as_.registerGoalCallback(boost::bind(&BlockDetectionServer::goalCB, this)); 00095 as_.registerPreemptCallback(boost::bind(&BlockDetectionServer::preemptCB, this)); 00096 00097 as_.start(); 00098 00099 // Subscribe to point cloud 00100 sub_ = nh_.subscribe("/camera/depth_registered/points", 1, &BlockDetectionServer::cloudCb, this); 00101 pub_ = nh_.advertise< pcl::PointCloud<pcl::PointXYZRGB> >("block_output", 1); 00102 00103 block_pub_ = nh_.advertise< geometry_msgs::PoseArray >("/turtlebot_blocks", 1, true); 00104 } 00105 00106 void goalCB() 00107 { 00108 ROS_INFO("[block detection] Received goal!"); 00109 // accept the new goal 00110 result_.blocks.poses.clear(); 00111 00112 goal_ = as_.acceptNewGoal(); 00113 00114 block_size = goal_->block_size; 00115 table_height = goal_->table_height; 00116 arm_link = goal_->frame; 00117 00118 result_.blocks.header.frame_id = arm_link; 00119 } 00120 00121 void preemptCB() 00122 { 00123 ROS_INFO("%s: Preempted", action_name_.c_str()); 00124 // set the action state to preempted 00125 as_.setPreempted(); 00126 } 00127 00128 void cloudCb ( const sensor_msgs::PointCloud2ConstPtr& msg ) 00129 { 00130 // Only do this if we're actually actively working on a goal. 00131 if (!as_.isActive()) return; 00132 00133 result_.blocks.header.stamp = msg->header.stamp; 00134 00135 // convert to PCL 00136 pcl::PointCloud<pcl::PointXYZRGB> cloud; 00137 pcl::fromROSMsg (*msg, cloud); 00138 00139 // transform to whatever frame we're working in, probably the arm frame. 00140 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_transformed (new pcl::PointCloud<pcl::PointXYZRGB>); 00141 00142 tf_listener_.waitForTransform(std::string(arm_link), cloud.header.frame_id, cloud.header.stamp, ros::Duration(1.0)); 00143 if (!pcl_ros::transformPointCloud (std::string(arm_link), cloud, *cloud_transformed, tf_listener_)) 00144 { 00145 ROS_ERROR ("Error converting to desired frame"); 00146 return; 00147 } 00148 00149 // Create the segmentation object for the planar model and set all the parameters 00150 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZRGB>); 00151 pcl::SACSegmentation<pcl::PointXYZRGB> seg; 00152 pcl::PointIndices::Ptr inliers (new pcl::PointIndices); 00153 pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients); 00154 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_plane (new pcl::PointCloud<pcl::PointXYZRGB> ()); 00155 seg.setOptimizeCoefficients (true); 00156 seg.setModelType (pcl::SACMODEL_PLANE); 00157 seg.setMethodType (pcl::SAC_RANSAC); 00158 seg.setMaxIterations (200); 00159 seg.setDistanceThreshold (0.005); 00160 00161 // Limit to things we think are roughly at the table height. 00162 pcl::PassThrough<pcl::PointXYZRGB> pass; 00163 pass.setInputCloud(cloud_transformed); 00164 pass.setFilterFieldName("z"); 00165 00166 pass.setFilterLimits(table_height - 0.05, table_height + block_size + 0.05); 00167 pass.filter(*cloud_filtered); 00168 if( cloud_filtered->points.size() == 0 ){ 00169 ROS_ERROR("0 points left"); 00170 return; 00171 }else 00172 ROS_INFO("Filtered, %d points left", (int) cloud_filtered->points.size()); 00173 00174 int nr_points = cloud_filtered->points.size (); 00175 while (cloud_filtered->points.size () > 0.3 * nr_points) 00176 { 00177 // Segment the largest planar component from the remaining cloud 00178 seg.setInputCloud(cloud_filtered); 00179 seg.segment (*inliers, *coefficients); 00180 if (inliers->indices.size () == 0) 00181 { 00182 std::cout << "Could not estimate a planar model for the given dataset." << std::endl; 00183 return; 00184 } 00185 00186 std::cout << "Inliers: " << (inliers->indices.size ()) << std::endl; 00187 00188 // Extract the planar inliers from the input cloud 00189 pcl::ExtractIndices<pcl::PointXYZRGB> extract; 00190 extract.setInputCloud (cloud_filtered); 00191 extract.setIndices (inliers); 00192 extract.setNegative (false); 00193 00194 // Write the planar inliers to disk 00195 extract.filter (*cloud_plane); 00196 std::cout << "PointCloud representing the planar component: " << cloud_plane->points.size () << " data points." << std::endl; 00197 00198 // Remove the planar inliers, extract the rest 00199 extract.setNegative (true); 00200 extract.filter (*cloud_filtered); 00201 } 00202 00203 // Creating the KdTree object for the search method of the extraction 00204 pcl::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::KdTreeFLANN<pcl::PointXYZRGB>); 00205 tree->setInputCloud (cloud_filtered); 00206 00207 std::vector<pcl::PointIndices> cluster_indices; 00208 pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> ec; 00209 ec.setClusterTolerance (0.005); 00210 ec.setMinClusterSize (100); 00211 ec.setMaxClusterSize (25000); 00212 ec.setSearchMethod (tree); 00213 ec.setInputCloud( cloud_filtered); 00214 ec.extract (cluster_indices); 00215 00216 pub_.publish(cloud_filtered); 00217 00218 // for each cluster, see if it is a block 00219 for (size_t c = 0; c < cluster_indices.size (); ++c) 00220 { 00221 // find the outer dimensions of the cluster 00222 float xmin = 0; float xmax = 0; float ymin = 0; float ymax = 0; 00223 float zmin = 0; float zmax = 0; 00224 for (size_t i = 0; i < cluster_indices[c].indices.size(); i++) 00225 { 00226 int j = cluster_indices[c].indices[i]; 00227 float x = cloud_filtered->points[j].x; 00228 float y = cloud_filtered->points[j].y; 00229 float z = cloud_filtered->points[j].z; 00230 if (i == 0) 00231 { 00232 xmin = xmax = x; 00233 ymin = ymax = y; 00234 zmin = zmax = z; 00235 } 00236 else 00237 { 00238 xmin = std::min(xmin, x); 00239 xmax = std::max(xmax, x); 00240 ymin = std::min(ymin, y); 00241 ymax = std::max(ymax, y); 00242 zmin = std::min(zmin, z); 00243 zmax = std::max(zmax, z); 00244 } 00245 } 00246 00247 // Check if these dimensions make sense for the block size specified 00248 float xside = xmax-xmin; 00249 float yside = ymax-ymin; 00250 float zside = zmax-zmin; 00251 00252 const float tol = 0.01; // 1 cm error tolerance 00253 // In order to be part of the block, xside and yside must be between 00254 // blocksize and blocksize*sqrt(2) 00255 // z must be equal to or smaller than blocksize 00256 if (xside > block_size-tol && xside < block_size*sqrt(2)+tol && 00257 yside > block_size-tol && yside < block_size*sqrt(2)+tol && 00258 zside > tol && zside < block_size+tol) 00259 { 00260 // If so, then figure out the position and the orientation of the block 00261 float angle = atan(block_size/((xside+yside)/2)); 00262 00263 if (yside < block_size) 00264 angle = 0.0; 00265 00266 ROS_INFO_STREAM("xside: " << xside << " yside: " << yside << " zside " << zside << " angle: " << angle); 00267 // Then add it to our set 00268 ROS_INFO("Adding a new block!"); 00269 addBlock( xmin+(xside)/2.0, ymin+(yside)/2.0, zmax - block_size/2.0, angle); 00270 } 00271 } 00272 00273 if (result_.blocks.poses.size() > 0) 00274 { 00275 as_.setSucceeded(result_); 00276 block_pub_.publish(result_.blocks); 00277 ROS_INFO("[block detection] Set as succeeded!"); 00278 } 00279 else 00280 ROS_INFO("[block detection] Couldn't find any blocks this iteration!"); 00281 // as_.setAborted(result_); 00282 } 00283 00284 void addBlock(float x, float y, float z, float angle) 00285 { 00286 geometry_msgs::Pose block_pose; 00287 block_pose.position.x = x; 00288 block_pose.position.y = y; 00289 block_pose.position.z = z; 00290 00291 Eigen::Quaternionf quat(Eigen::AngleAxis<float>(angle, Eigen::Vector3f(0,0,1))); 00292 00293 block_pose.orientation.x = quat.x(); 00294 block_pose.orientation.y = quat.y(); 00295 block_pose.orientation.z = quat.z(); 00296 block_pose.orientation.w = quat.w(); 00297 00298 result_.blocks.poses.push_back(block_pose); 00299 } 00300 00301 }; 00302 00303 }; 00304 00305 int main(int argc, char** argv) 00306 { 00307 ros::init(argc, argv, "block_detection_action_server"); 00308 00309 turtlebot_block_manipulation::BlockDetectionServer server("block_detection"); 00310 ros::spin(); 00311 00312 return 0; 00313 } 00314