$search
00001 /* 00002 * Copyright (c) 2008 Radu Bogdan Rusu <rusu -=- cs.tum.edu> 00003 * 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions are met: 00008 * 00009 * * Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * * Redistributions in binary form must reproduce the above copyright 00012 * notice, this list of conditions and the following disclaimer in the 00013 * documentation and/or other materials provided with the distribution. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 00026 * 00027 * $Id$ 00028 * 00029 */ 00030 00043 // ROS core 00044 #include <ros/node.h> 00045 // ROS messages 00046 #include <sensor_msgs/PointCloud.h> 00047 #include <geometry_msgs/Polygon.h> 00048 #include <mapping_msgs/PolygonalMap.h> 00049 00050 // Sample Consensus 00051 #include <point_cloud_mapping/sample_consensus/sac.h> 00052 #include <point_cloud_mapping/sample_consensus/msac.h> 00053 #include <point_cloud_mapping/sample_consensus/sac_model_plane.h> 00054 00055 #include <tf/transform_listener.h> 00056 #include <angles/angles.h> 00057 00058 // Cloud geometry 00059 #include <point_cloud_mapping/geometry/areas.h> 00060 #include <point_cloud_mapping/geometry/point.h> 00061 #include <point_cloud_mapping/geometry/distances.h> 00062 #include <point_cloud_mapping/geometry/nearest.h> 00063 #include <point_cloud_mapping/geometry/statistics.h> 00064 00065 #include <sys/time.h> 00066 00067 using namespace std; 00068 00069 class SemanticPointAnnotator 00070 { 00071 protected: 00072 ros::NodeHandle& node_; 00073 00074 public: 00075 00076 // ROS messages 00077 PointCloud cloud_, cloud_annotated_; 00078 Point32 z_axis_; 00079 00080 ros::Publisher cloud_publisher_; 00081 ros::Subscriber cloud_normal_subscriber_; 00082 00083 tf::TransformListener tf_; 00084 00085 // Parameters 00086 int sac_min_points_per_model_, sac_min_points_left_; 00087 double sac_distance_threshold_, eps_angle_; 00088 00089 double rule_floor_, rule_ceiling_, rule_wall_; 00090 double rule_table_min_, rule_table_max_; 00091 00093 SemanticPointAnnotator (ros::NodeHandle& anode) : node_ (anode) 00094 { 00095 node_.param ("rule_floor", rule_floor_, 0.1); // Rule for FLOOR 00096 node_.param ("rule_ceiling", rule_ceiling_, 2.0); // Rule for CEILING 00097 node_.param ("rule_table_min", rule_table_min_, 0.5); // Rule for MIN TABLE 00098 node_.param ("rule_table_max", rule_table_max_, 1.5); // Rule for MIN TABLE 00099 node_.param ("rule_wall", rule_wall_, 2.0); // Rule for WALL 00100 00101 node_.param ("p_sac_min_points_left", sac_min_points_left_, 500); 00102 node_.param ("p_sac_min_points_per_model", sac_min_points_per_model_, 100); // 100 points at high resolution 00103 node_.param ("p_sac_distance_threshold", sac_distance_threshold_, 0.03); // 3 cm 00104 node_.param ("p_eps_angle_", eps_angle_, 10.0); // 10 degrees 00105 eps_angle_ = angles::from_degrees (eps_angle_); // convert to radians 00106 00107 cloud_normal_subscriber_ = node_.subscribe ("cloud_normals",1,&SemanticPointAnnotator::cloud_cb,this);//cloud_, 00108 cloud_publisher_ = node_.advertise<PointCloud> ("cloud_annotated", 1); 00109 00110 z_axis_.x = 0; z_axis_.y = 0; z_axis_.z = 1; 00111 00112 cloud_annotated_.channels.resize (3); 00113 //cloud_annotated_.channels[0].name = "intensities"; 00114 cloud_annotated_.channels[0].name = "r"; 00115 cloud_annotated_.channels[1].name = "g"; 00116 cloud_annotated_.channels[2].name = "b"; 00117 } 00118 00120 void 00121 fitSACPlane (PointCloud *points, vector<int> *indices, vector<vector<int> > &inliers, vector<vector<double> > &coeff) 00122 { 00123 if ((int)indices->size () < sac_min_points_per_model_) 00124 return; 00125 00126 // Create and initialize the SAC model 00127 sample_consensus::SACModelPlane *model = new sample_consensus::SACModelPlane (); 00128 sample_consensus::SAC *sac = new sample_consensus::MSAC (model, sac_distance_threshold_); 00129 sac->setMaxIterations (100); 00130 sac->setProbability (0.95); 00131 model->setDataSet (points, *indices); 00132 00133 PointCloud pts (*points); 00134 int nr_points_left = indices->size (); 00135 while (nr_points_left > sac_min_points_left_) 00136 { 00137 // Search for the best plane 00138 if (sac->computeModel ()) 00139 { 00140 // Obtain the inliers and the planar model coefficients 00141 if ((int)sac->getInliers ().size () < sac_min_points_per_model_) 00142 break; 00143 inliers.push_back (sac->getInliers ()); 00144 coeff.push_back (sac->computeCoefficients ()); 00145 fprintf (stderr, "> Found a model supported by %d inliers: [%g, %g, %g, %g]\n", sac->getInliers ().size (), 00146 coeff[coeff.size () - 1][0], coeff[coeff.size () - 1][1], coeff[coeff.size () - 1][2], coeff[coeff.size () - 1][3]); 00147 00148 // Project the inliers onto the model 00149 //model->projectPointsInPlace (sac->getInliers (), coeff[coeff.size () - 1]); 00150 00151 // Remove the current inliers in the model 00152 nr_points_left = sac->removeInliers (); 00153 } 00154 } 00155 } 00156 00157 // void pathCallback(const manipulation_msgs::JointTrajConstPtr &path_msg); 00158 00160 // Callback 00161 void cloud_cb (const PointCloudConstPtr &cloud_in) 00162 { 00163 cloud_ = *cloud_in; 00164 PointStamped base_link_origin, map_origin; 00165 base_link_origin.point.x = base_link_origin.point.y = base_link_origin.point.z = 0.0; 00166 base_link_origin.header.frame_id = "base_link"; 00167 00168 tf_.transformPoint ("base_link", base_link_origin, map_origin); 00169 00170 ROS_INFO ("Received %d data points. Current robot pose is %g, %g, %g", cloud_.points.size (), map_origin.point.x, map_origin.point.y, map_origin.point.z); 00171 00172 cloud_annotated_.header = cloud_.header; 00173 00174 int nx = cloud_geometry::getChannelIndex (&cloud_, "nx"); 00175 int ny = cloud_geometry::getChannelIndex (&cloud_, "ny"); 00176 int nz = cloud_geometry::getChannelIndex (&cloud_, "nz"); 00177 00178 if ( (cloud_.channels.size () < 3) || (nx == -1) || (ny == -1) || (nz == -1) ) 00179 { 00180 ROS_ERROR ("This PointCloud message does not contain normal information!"); 00181 return; 00182 } 00183 00184 timeval t1, t2; 00185 gettimeofday (&t1, NULL); 00186 00187 // Select points whose normals are parallel with the Z-axis 00188 vector<int> z_axis_indices, xy_axis_indices; 00189 cloud_geometry::getPointIndicesAxisParallelNormals (&cloud_, nx, ny, nz, eps_angle_, &z_axis_, z_axis_indices); 00190 cloud_geometry::getPointIndicesAxisPerpendicularNormals (&cloud_, nx, ny, nz, eps_angle_, &z_axis_, xy_axis_indices); 00191 00192 // Find the dominant planes 00193 vector<vector<int> > inliers_parallel, inliers_perpendicular; 00194 vector<vector<double> > coeff; 00195 // Find all planes parallel with XY 00196 fitSACPlane (&cloud_, &z_axis_indices, inliers_parallel, coeff); 00197 // Find all planes perpendicular to XY 00198 fitSACPlane (&cloud_, &xy_axis_indices, inliers_perpendicular, coeff); 00199 00200 // Mark points in the output cloud 00201 int total_p = 0, nr_p = 0; 00202 for (unsigned int i = 0; i < inliers_parallel.size (); i++) 00203 total_p += inliers_parallel[i].size (); 00204 for (unsigned int i = 0; i < inliers_perpendicular.size (); i++) 00205 total_p += inliers_perpendicular[i].size (); 00206 00207 cloud_annotated_.points.resize (total_p); 00208 cloud_annotated_.channels[0].values.resize (total_p); 00209 cloud_annotated_.channels[1].values.resize (total_p); 00210 cloud_annotated_.channels[2].values.resize (total_p); 00211 00212 // Get all planes parallel to the floor (perpendicular to Z) 00213 Point32 robot_origin; 00214 robot_origin.x = map_origin.point.x; 00215 robot_origin.y = map_origin.point.y; 00216 robot_origin.z = map_origin.point.z; 00217 for (unsigned int i = 0; i < inliers_parallel.size (); i++) 00218 { 00219 // Compute a distance from 0,0,0 to the plane 00220 double distance = cloud_geometry::distances::pointToPlaneDistance (&robot_origin, coeff[i]); 00221 00222 double r = 1.0, g = 1.0, b = 1.0; 00223 // Test for floor 00224 if (distance < rule_floor_) 00225 { 00226 r = 0.6; g = 0.67; b = 0.01; 00227 } 00228 // Test for ceiling 00229 if (distance > rule_ceiling_) 00230 { 00231 r = 0.8; g = 0.63; b = 0.33; 00232 } 00233 // Test for tables 00234 if (distance > rule_table_min_ && distance < rule_table_max_) 00235 { 00236 r = 0.0; g = 1.0; b = 0.0; 00237 } 00238 00239 for (unsigned int j = 0; j < inliers_parallel[i].size (); j++) 00240 { 00241 cloud_annotated_.points[nr_p].x = cloud_.points.at (inliers_parallel[i].at (j)).x; 00242 cloud_annotated_.points[nr_p].y = cloud_.points.at (inliers_parallel[i].at (j)).y; 00243 cloud_annotated_.points[nr_p].z = cloud_.points.at (inliers_parallel[i].at (j)).z; 00244 //cloud_annotated_.channels[0].values[i] = intensity_value; 00245 cloud_annotated_.channels[0].values[nr_p] = r; 00246 cloud_annotated_.channels[1].values[nr_p] = g; 00247 cloud_annotated_.channels[2].values[nr_p] = b; 00248 nr_p++; 00249 } 00250 } 00251 00252 // Get all planes perpendicular to the floor (parallel to XY) 00253 for (unsigned int i = 0; i < inliers_perpendicular.size (); i++) 00254 { 00255 // Get the minimum and maximum bounds of the plane 00256 Point32 minP, maxP; 00257 cloud_geometry::statistics::getMinMax (&cloud_, &inliers_perpendicular[i], minP, maxP); 00258 00259 double r, g, b; 00260 r = g = b = 1.0; 00261 00262 // Test for wall 00263 if (maxP.z > rule_wall_) 00264 { 00265 r = rand () / (RAND_MAX + 1.0); 00266 g = rand () / (RAND_MAX + 1.0); 00267 b = rand () / (RAND_MAX + 1.0); 00268 r = r * .3; 00269 b = b * .3 + .7; 00270 g = g * .3; 00271 } 00272 for (unsigned int j = 0; j < inliers_perpendicular[i].size (); j++) 00273 { 00274 cloud_annotated_.points[nr_p].x = cloud_.points.at (inliers_perpendicular[i].at (j)).x; 00275 cloud_annotated_.points[nr_p].y = cloud_.points.at (inliers_perpendicular[i].at (j)).y; 00276 cloud_annotated_.points[nr_p].z = cloud_.points.at (inliers_perpendicular[i].at (j)).z; 00277 //cloud_annotated_.channels[0].values[i] = intensity_value; 00278 cloud_annotated_.channels[0].values[nr_p] = r; 00279 cloud_annotated_.channels[1].values[nr_p] = g; 00280 cloud_annotated_.channels[2].values[nr_p] = b; 00281 nr_p++; 00282 } 00283 } 00284 00285 gettimeofday (&t2, NULL); 00286 double time_spent = t2.tv_sec + (double)t2.tv_usec / 1000000.0 - (t1.tv_sec + (double)t1.tv_usec / 1000000.0); 00287 ROS_INFO ("Number of points with normals approximately parallel to the Z axis: %d (%g seconds).", z_axis_indices.size (), time_spent); 00288 00289 cloud_publisher_.publish (cloud_annotated_); 00290 } 00291 }; 00292 00293 /* ---[ */ 00294 int 00295 main (int argc, char** argv) 00296 { 00297 ros::init (argc, argv, "semantic_point_annotator"); 00298 ros::NodeHandle ros_node("~"); 00299 SemanticPointAnnotator p (ros_node); 00300 ros::spin(); 00301 00302 return (0); 00303 } 00304 /* ]--- */ 00305