Segmenter.cpp
Go to the documentation of this file.
00001 
00013 // RAIL Segmentation
00014 #include "rail_segmentation/Segmenter.h"
00015 
00016 // ROS
00017 #include <pcl_ros/transforms.h>
00018 #include <ros/package.h>
00019 #include <sensor_msgs/point_cloud_conversion.h>
00020 #include <sensor_msgs/image_encodings.h>
00021 #include <tf2/LinearMath/Matrix3x3.h>
00022 
00023 // PCL
00024 #include <pcl/common/common.h>
00025 #include <pcl/filters/extract_indices.h>
00026 #include <pcl/filters/passthrough.h>
00027 #include <pcl/filters/project_inliers.h>
00028 #include <pcl/filters/voxel_grid.h>
00029 #include <pcl/ModelCoefficients.h>
00030 #include <pcl/segmentation/sac_segmentation.h>
00031 #include <pcl/segmentation/extract_clusters.h>
00032 
00033 // YAML
00034 #include <yaml-cpp/yaml.h>
00035 
00036 // C++ Standard Library
00037 #include <fstream>
00038 
00039 using namespace std;
00040 using namespace rail::segmentation;
00041 
00042 Segmenter::Segmenter() : private_node_("~"), tf2_(tf_buffer_)
00043 {
00044   // flag for the first point cloud coming in
00045   first_pc_in_ = false;
00046 
00047   // set defaults
00048   debug_ = DEFAULT_DEBUG;
00049   string point_cloud_topic("/camera/depth_registered/points");
00050   string zones_file(ros::package::getPath("rail_segmentation") + "/config/zones.yaml");
00051   min_cluster_size_ = DEFAULT_MIN_CLUSTER_SIZE;
00052   max_cluster_size_ = DEFAULT_MAX_CLUSTER_SIZE;
00053 
00054   // grab any parameters we need
00055   private_node_.getParam("debug", debug_);
00056   private_node_.getParam("point_cloud_topic", point_cloud_topic);
00057   private_node_.getParam("zones_config", zones_file);
00058   private_node_.getParam("min_cluster_size", min_cluster_size_);
00059   private_node_.getParam("max_cluster_size", max_cluster_size_);
00060 
00061   // setup publishers/subscribers we need
00062   segment_srv_ = private_node_.advertiseService("segment", &Segmenter::segmentCallback, this);
00063   clear_srv_ = private_node_.advertiseService("clear", &Segmenter::clearCallback, this);
00064   remove_object_srv_ = private_node_.advertiseService("remove_object", &Segmenter::removeObjectCallback, this);
00065   segmented_objects_pub_ = private_node_.advertise<rail_manipulation_msgs::SegmentedObjectList>(
00066       "segmented_objects", 1, true
00067   );
00068   table_pub_ = private_node_.advertise<rail_manipulation_msgs::SegmentedObject>(
00069       "segmented_table", 1, true
00070   );
00071   markers_pub_ = private_node_.advertise<visualization_msgs::MarkerArray>("markers", 1, true);
00072   table_marker_pub_ = private_node_.advertise<visualization_msgs::Marker>("table_marker", 1, true);
00073   point_cloud_sub_ = node_.subscribe(point_cloud_topic, 1, &Segmenter::pointCloudCallback, this);
00074   // setup a debug publisher if we need it
00075   if (debug_)
00076   {
00077     debug_pc_pub_ = private_node_.advertise<pcl::PointCloud<pcl::PointXYZRGB> >("debug_pc", 1, true);
00078     debug_img_pub_ = private_node_.advertise<sensor_msgs::Image>("debug_img", 1, true);
00079   }
00080 
00081   // check the YAML version
00082 #ifdef YAMLCPP_GT_0_5_0
00083   // parse the segmentation zones
00084   YAML::Node zones_config = YAML::LoadFile(zones_file);
00085   for (size_t i = 0; i < zones_config.size(); i++)
00086   {
00087     YAML::Node cur = zones_config[i];
00088     // create a zone with the frame ID information
00089     SegmentationZone zone(cur["name"].as<string>(), cur["parent_frame_id"].as<string>(),
00090                           cur["child_frame_id"].as<string>(), cur["bounding_frame_id"].as<string>(),
00091                           cur["segmentation_frame_id"].as<string>());
00092 
00093     // check for the remove surface flag
00094     if (cur["remove_surface"].IsDefined())
00095     {
00096       zone.setRemoveSurface(cur["remove_surface"].as<bool>());
00097     }
00098 
00099     // check for any set limits
00100     if (cur["roll_min"].IsDefined())
00101     {
00102       zone.setRollMin(cur["roll_min"].as<double>());
00103     }
00104     if (cur["roll_max"].IsDefined())
00105     {
00106       zone.setRollMax(cur["roll_max"].as<double>());
00107     }
00108     if (cur["pitch_min"].IsDefined())
00109     {
00110       zone.setPitchMin(cur["pitch_min"].as<double>());
00111     }
00112     if (cur["pitch_max"].IsDefined())
00113     {
00114       zone.setPitchMax(cur["pitch_max"].as<double>());
00115     }
00116     if (cur["yaw_min"].IsDefined())
00117     {
00118       zone.setYawMin(cur["yaw_min"].as<double>());
00119     }
00120     if (cur["yaw_max"].IsDefined())
00121     {
00122       zone.setYawMax(cur["yaw_max"].as<double>());
00123     }
00124     if (cur["x_min"].IsDefined())
00125     {
00126       zone.setXMin(cur["x_min"].as<double>());
00127     }
00128     if (cur["x_max"].IsDefined())
00129     {
00130       zone.setXMax(cur["x_max"].as<double>());
00131     }
00132     if (cur["y_min"].IsDefined())
00133     {
00134       zone.setYMin(cur["y_min"].as<double>());
00135     }
00136     if (cur["y_max"].IsDefined())
00137     {
00138       zone.setYMax(cur["y_max"].as<double>());
00139     }
00140     if (cur["z_min"].IsDefined())
00141     {
00142       zone.setZMin(cur["z_min"].as<double>());
00143     }
00144     if (cur["z_max"].IsDefined())
00145     {
00146       zone.setZMax(cur["z_max"].as<double>());
00147     }
00148 
00149     zones_.push_back(zone);
00150   }
00151 #else
00152   // parse the segmentation zones
00153   ifstream fin(zones_file.c_str());
00154   YAML::Parser zones_parser(fin);
00155   YAML::Node zones_config;
00156   zones_parser.GetNextDocument(zones_config);
00157   for (size_t i = 0; i < zones_config.size(); i++)
00158   {
00159     // parse the required information
00160     string name, parent_frame_id, child_frame_id, bounding_frame_id, segmentation_frame_id;
00161     zones_config[i]["name"] >> name;
00162     zones_config[i]["parent_frame_id"] >> parent_frame_id;
00163     zones_config[i]["child_frame_id"] >> child_frame_id;
00164     zones_config[i]["bounding_frame_id"] >> bounding_frame_id;
00165     zones_config[i]["segmentation_frame_id"] >> segmentation_frame_id;
00166 
00167     // create a zone with the frame ID information
00168     SegmentationZone zone(name, parent_frame_id, child_frame_id, bounding_frame_id, segmentation_frame_id);
00169 
00170     // check for the remove surface flag
00171     if (zones_config[i].FindValue("remove_surface") != NULL)
00172     {
00173       bool remove_surface;
00174       zones_config[i]["remove_surface"] >> remove_surface;
00175       zone.setRemoveSurface(remove_surface);
00176     }
00177 
00178     // check for any set limits
00179     if (zones_config[i].FindValue("roll_min") != NULL)
00180     {
00181       double roll_min;
00182       zones_config[i]["roll_min"] >> roll_min;
00183       zone.setRollMin(roll_min);
00184     }
00185     if (zones_config[i].FindValue("roll_max") != NULL)
00186     {
00187       double roll_max;
00188       zones_config[i]["roll_max"] >> roll_max;
00189       zone.setRollMax(roll_max);
00190     }
00191     if (zones_config[i].FindValue("pitch_min") != NULL)
00192     {
00193       double pitch_min;
00194       zones_config[i]["pitch_min"] >> pitch_min;
00195       zone.setPitchMin(pitch_min);
00196     }
00197     if (zones_config[i].FindValue("pitch_max") != NULL)
00198     {
00199       double pitch_max;
00200       zones_config[i]["pitch_max"] >> pitch_max;
00201       zone.setPitchMax(pitch_max);
00202     }
00203     if (zones_config[i].FindValue("yaw_min") != NULL)
00204     {
00205       double yaw_min;
00206       zones_config[i]["yaw_min"] >> yaw_min;
00207       zone.setYawMin(yaw_min);
00208     }
00209     if (zones_config[i].FindValue("yaw_max") != NULL)
00210     {
00211       double yaw_max;
00212       zones_config[i]["yaw_max"] >> yaw_max;
00213       zone.setYawMax(yaw_max);
00214     }
00215     if (zones_config[i].FindValue("x_min") != NULL)
00216     {
00217       double x_min;
00218       zones_config[i]["x_min"] >> x_min;
00219       zone.setXMin(x_min);
00220     }
00221     if (zones_config[i].FindValue("x_max") != NULL)
00222     {
00223       double x_max;
00224       zones_config[i]["x_max"] >> x_max;
00225       zone.setXMax(x_max);
00226     }
00227     if (zones_config[i].FindValue("y_min") != NULL)
00228     {
00229       double y_min;
00230       zones_config[i]["y_min"] >> y_min;
00231       zone.setYMin(y_min);
00232     }
00233     if (zones_config[i].FindValue("y_max") != NULL)
00234     {
00235       double y_max;
00236       zones_config[i]["y_max"] >> y_max;
00237       zone.setYMax(y_max);
00238     }
00239     if (zones_config[i].FindValue("z_min") != NULL)
00240     {
00241       double z_min;
00242       zones_config[i]["z_min"] >> z_min;
00243       zone.setZMin(z_min);
00244     }
00245     if (zones_config[i].FindValue("z_max") != NULL)
00246     {
00247       double z_max;
00248       zones_config[i]["z_max"] >> z_max;
00249       zone.setZMax(z_max);
00250     }
00251 
00252     zones_.push_back(zone);
00253   }
00254 #endif
00255 
00256   // check how many zones we have
00257   if (zones_.size() > 0)
00258   {
00259     ROS_INFO("%d segmenation zone(s) parsed.", (int) zones_.size());
00260     ROS_INFO("Segmenter Successfully Initialized");
00261     okay_ = true;
00262   } else
00263   {
00264     ROS_ERROR("No valid segmenation zones defined. Check %s.", zones_file.c_str());
00265     okay_ = false;
00266   }
00267 }
00268 
00269 bool Segmenter::okay() const
00270 {
00271   return okay_;
00272 }
00273 
00274 void Segmenter::pointCloudCallback(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &pc)
00275 {
00276   // lock for the point cloud
00277   boost::mutex::scoped_lock lock(pc_mutex_);
00278   // simply store the latest point cloud
00279   first_pc_in_ = true;
00280   pc_ = pc;
00281 }
00282 
00283 const SegmentationZone &Segmenter::getCurrentZone() const
00284 {
00285   // check each zone
00286   for (size_t i = 0; i < zones_.size(); i++)
00287   {
00288     // get the current TF information
00289     geometry_msgs::TransformStamped tf = tf_buffer_.lookupTransform(zones_[i].getParentFrameID(),
00290                                                                     zones_[i].getChildFrameID(), ros::Time(0));
00291 
00292     // convert to a Matrix3x3 to get RPY
00293     tf2::Matrix3x3 mat(tf2::Quaternion(tf.transform.rotation.x, tf.transform.rotation.y, tf.transform.rotation.z,
00294                                        tf.transform.rotation.w));
00295     double roll, pitch, yaw;
00296     mat.getRPY(roll, pitch, yaw);
00297 
00298     // check if all the bounds meet
00299     if (roll >= zones_[i].getRollMin() && pitch >= zones_[i].getPitchMin() && yaw >= zones_[i].getYawMin() &&
00300         roll <= zones_[i].getRollMax() && pitch <= zones_[i].getPitchMax() && yaw <= zones_[i].getYawMax())
00301     {
00302       return zones_[i];
00303     }
00304   }
00305 
00306   ROS_WARN("Current state not in a valid segmentation zone. Defaulting to first zone.");
00307   return zones_[0];
00308 }
00309 
00310 bool Segmenter::removeObjectCallback(rail_segmentation::RemoveObject::Request &req,
00311     rail_segmentation::RemoveObject::Response &res)
00312 {
00313   // lock for the messages
00314   boost::mutex::scoped_lock lock(msg_mutex_);
00315   // check the index
00316   if (req.index < object_list_.objects.size() && req.index < markers_.markers.size())
00317   {
00318     // remove
00319     object_list_.objects.erase(object_list_.objects.begin() + req.index);
00320     // set header information
00321     object_list_.header.seq++;
00322     object_list_.header.stamp = ros::Time::now();
00323     object_list_.cleared = false;
00324     // republish
00325     segmented_objects_pub_.publish(object_list_);
00326     // delete marker
00327     markers_.markers[req.index].action = visualization_msgs::Marker::DELETE;
00328     markers_pub_.publish(markers_);
00329     markers_.markers.erase(markers_.markers.begin() + req.index);
00330     return true;
00331   } else
00332   {
00333     ROS_ERROR("Attempted to remove index %d from list of size %ld.", req.index, object_list_.objects.size());
00334     return false;
00335   }
00336 }
00337 
00338 bool Segmenter::clearCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
00339 {
00340   // lock for the messages
00341   boost::mutex::scoped_lock lock(msg_mutex_);
00342   // empty the list
00343   object_list_.objects.clear();
00344   object_list_.cleared = true;
00345   // set header information
00346   object_list_.header.seq++;
00347   object_list_.header.stamp = ros::Time::now();
00348   // republish
00349   segmented_objects_pub_.publish(object_list_);
00350   // delete markers
00351   for (size_t i = 0; i < markers_.markers.size(); i++)
00352   {
00353     markers_.markers[i].action = visualization_msgs::Marker::DELETE;
00354   }
00355   markers_pub_.publish(markers_);
00356   markers_.markers.clear();
00357 
00358   table_marker_.action = visualization_msgs::Marker::DELETE;
00359   table_marker_pub_.publish(table_marker_);
00360   return true;
00361 }
00362 
00363 bool Segmenter::segmentCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
00364 {
00365   // check if we have a point cloud first
00366   {
00367     boost::mutex::scoped_lock lock(pc_mutex_);
00368     if (!first_pc_in_)
00369     {
00370       ROS_WARN("No point cloud received yet. Ignoring segmentation request.");
00371       return false;
00372     }
00373   }
00374 
00375   // clear the objects first
00376   this->clearCallback(req, res);
00377 
00378   // determine the correct segmentation zone
00379   const SegmentationZone &zone = this->getCurrentZone();
00380   ROS_INFO("Segmenting in zone '%s'.", zone.getName().c_str());
00381 
00382   // transform the point cloud to the fixed frame
00383   pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_pc(new pcl::PointCloud<pcl::PointXYZRGB>);
00384   // lock on the point cloud
00385   {
00386     boost::mutex::scoped_lock lock(pc_mutex_);
00387     // perform the copy/transform using TF
00388     pcl_ros::transformPointCloud(zone.getBoundingFrameID(), ros::Time(0), *pc_, pc_->header.frame_id,
00389                                  *transformed_pc, tf_);
00390     transformed_pc->header.frame_id = zone.getBoundingFrameID();
00391     transformed_pc->header.seq = pc_->header.seq;
00392     transformed_pc->header.stamp = pc_->header.stamp;
00393   }
00394 
00395   // start with every index
00396   pcl::IndicesPtr filter_indices(new vector<int>);
00397   filter_indices->resize(transformed_pc->points.size());
00398   for (size_t i = 0; i < transformed_pc->points.size(); i++)
00399   {
00400     filter_indices->at(i) = i;
00401   }
00402 
00403   // check if we need to remove a surface
00404   double z_min = zone.getZMin();
00405   if (zone.getRemoveSurface())
00406   {
00407     table_ = this->findSurface(transformed_pc, filter_indices, zone, filter_indices);
00408     double z_surface = table_.centroid.z;
00409     // check the new bound for Z
00410     z_min = max(zone.getZMin(), z_surface + SURFACE_REMOVAL_PADDING);
00411   }
00412 
00413   // check bounding areas (bound the inverse of what we want since PCL will return the removed indicies)
00414   pcl::ConditionOr<pcl::PointXYZRGB>::Ptr bounds(new pcl::ConditionOr<pcl::PointXYZRGB>);
00415   if (z_min > -numeric_limits<double>::infinity())
00416   {
00417     bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
00418         new pcl::FieldComparison<pcl::PointXYZRGB>("z", pcl::ComparisonOps::LE, z_min))
00419     );
00420   }
00421   if (zone.getZMax() < numeric_limits<double>::infinity())
00422   {
00423     bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
00424         new pcl::FieldComparison<pcl::PointXYZRGB>("z", pcl::ComparisonOps::GE, zone.getZMax()))
00425     );
00426   }
00427   if (zone.getYMin() > -numeric_limits<double>::infinity())
00428   {
00429     bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
00430         new pcl::FieldComparison<pcl::PointXYZRGB>("y", pcl::ComparisonOps::LE, zone.getYMin()))
00431     );
00432   }
00433   if (zone.getYMax() < numeric_limits<double>::infinity())
00434   {
00435     bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
00436         new pcl::FieldComparison<pcl::PointXYZRGB>("y", pcl::ComparisonOps::GE, zone.getYMax()))
00437     );
00438   }
00439   if (zone.getXMin() > -numeric_limits<double>::infinity())
00440   {
00441     bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
00442         new pcl::FieldComparison<pcl::PointXYZRGB>("x", pcl::ComparisonOps::LE, zone.getXMin()))
00443     );
00444   }
00445   if (zone.getXMax() < numeric_limits<double>::infinity())
00446   {
00447     bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
00448         new pcl::FieldComparison<pcl::PointXYZRGB>("x", pcl::ComparisonOps::GE, zone.getXMax()))
00449     );
00450   }
00451 
00452   // remove past the given bounds
00453   this->inverseBound(transformed_pc, filter_indices, bounds, filter_indices);
00454 
00455   // publish the filtered and bounded PC pre-segmentation
00456   if (debug_)
00457   {
00458     pcl::PointCloud<pcl::PointXYZRGB>::Ptr debug_pc(new pcl::PointCloud<pcl::PointXYZRGB>);
00459     this->extract(transformed_pc, filter_indices, debug_pc);
00460     debug_pc_pub_.publish(debug_pc);
00461   }
00462 
00463   // extract clusters
00464   vector<pcl::PointIndices> clusters;
00465   this->extractClusters(transformed_pc, filter_indices, clusters);
00466 
00467   if (clusters.size() > 0)
00468   {
00469     // lock for the messages
00470     boost::mutex::scoped_lock lock(msg_mutex_);
00471     // check each cluster
00472     for (size_t i = 0; i < clusters.size(); i++)
00473     {
00474       // grab the points we need
00475       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
00476       for (size_t j = 0; j < clusters[i].indices.size(); j++)
00477       {
00478         cluster->points.push_back(transformed_pc->points[clusters[i].indices[j]]);
00479       }
00480       cluster->width = cluster->points.size();
00481       cluster->height = 1;
00482       cluster->is_dense = true;
00483       cluster->header.frame_id = transformed_pc->header.frame_id;
00484 
00485       // check if we need to transform to a different frame
00486       pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
00487       pcl::PCLPointCloud2::Ptr converted(new pcl::PCLPointCloud2);
00488       if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
00489       {
00490         // perform the copy/transform using TF
00491         pcl_ros::transformPointCloud(zone.getSegmentationFrameID(), ros::Time(0), *cluster, cluster->header.frame_id,
00492                                      *transformed_cluster, tf_);
00493         transformed_cluster->header.frame_id = zone.getSegmentationFrameID();
00494         transformed_cluster->header.seq = cluster->header.seq;
00495         transformed_cluster->header.stamp = cluster->header.stamp;
00496         pcl::toPCLPointCloud2(*transformed_cluster, *converted);
00497       } else
00498       {
00499         pcl::toPCLPointCloud2(*cluster, *converted);
00500       }
00501 
00502       // convert to a SegmentedObject message
00503       rail_manipulation_msgs::SegmentedObject segmented_object;
00504       segmented_object.recognized = false;
00505 
00506       // set the RGB image
00507       segmented_object.image = this->createImage(transformed_pc, clusters[i]);
00508 
00509       // check if we want to publish the image
00510       if (debug_)
00511       {
00512         debug_img_pub_.publish(segmented_object.image);
00513       }
00514 
00515       // set the point cloud
00516       pcl_conversions::fromPCL(*converted, segmented_object.point_cloud);
00517       segmented_object.point_cloud.header.stamp = ros::Time::now();
00518       // create a marker and set the extra fields
00519       segmented_object.marker = this->createMarker(converted);
00520       segmented_object.marker.id = i;
00521 
00522       // set the centroid
00523       Eigen::Vector4f centroid;
00524       if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
00525       {
00526         pcl::compute3DCentroid(*transformed_cluster, centroid);
00527       } else
00528       {
00529         pcl::compute3DCentroid(*cluster, centroid);
00530       }
00531       segmented_object.centroid.x = centroid[0];
00532       segmented_object.centroid.y = centroid[1];
00533       segmented_object.centroid.z = centroid[2];
00534 
00535       // calculate the bounding box
00536       Eigen::Vector4f min_pt, max_pt;
00537       pcl::getMinMax3D(*cluster, min_pt, max_pt);
00538       segmented_object.width = max_pt[0] - min_pt[0];
00539       segmented_object.depth = max_pt[1] - min_pt[1];
00540       segmented_object.height = max_pt[2] - min_pt[2];
00541 
00542       // calculate the center
00543       segmented_object.center.x = (max_pt[0] + min_pt[0]) / 2.0;
00544       segmented_object.center.y = (max_pt[1] + min_pt[1]) / 2.0;
00545       segmented_object.center.z = (max_pt[2] + min_pt[2]) / 2.0;
00546 
00547       // calculate the orientation
00548       pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
00549       // project point cloud onto the xy plane
00550       pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
00551       coefficients->values.resize(4);
00552       coefficients->values[0] = 0;
00553       coefficients->values[1] = 0;
00554       coefficients->values[2] = 1.0;
00555       coefficients->values[3] = 0;
00556       pcl::ProjectInliers<pcl::PointXYZRGB> proj;
00557       proj.setModelType(pcl::SACMODEL_PLANE);
00558       if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
00559       {
00560         proj.setInputCloud(transformed_cluster);
00561       } else
00562       {
00563         proj.setInputCloud(cluster);
00564       }
00565       proj.setModelCoefficients(coefficients);
00566       proj.filter(*projected_cluster);
00567 
00568       //calculate the Eigen vectors of the projected point cloud's covariance matrix, used to determine orientation
00569       Eigen::Vector4f projected_centroid;
00570       Eigen::Matrix3f covariance_matrix;
00571       pcl::compute3DCentroid(*projected_cluster, projected_centroid);
00572       pcl::computeCovarianceMatrixNormalized(*projected_cluster, projected_centroid, covariance_matrix);
00573       Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance_matrix, Eigen::ComputeEigenvectors);
00574       Eigen::Matrix3f eigen_vectors = eigen_solver.eigenvectors();
00575       eigen_vectors.col(2) = eigen_vectors.col(0).cross(eigen_vectors.col(1));
00576       //calculate rotation from eigenvectors
00577       const Eigen::Quaternionf qfinal(eigen_vectors);
00578 
00579       //convert orientation to a single angle on the 2D plane defined by the segmentation coordinate frame
00580       tf::Quaternion tf_quat;
00581       tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
00582       double r, p, y;
00583       tf::Matrix3x3 m(tf_quat);
00584       m.getRPY(r, p, y);
00585       double angle = r + y;
00586       while (angle < -M_PI)
00587       {
00588         angle += 2 * M_PI;
00589       }
00590       while (angle > M_PI)
00591       {
00592         angle -= 2 * M_PI;
00593       }
00594       segmented_object.orientation = tf::createQuaternionMsgFromYaw(angle);
00595 
00596       // add to the final list
00597       object_list_.objects.push_back(segmented_object);
00598       // add to the markers
00599       markers_.markers.push_back(segmented_object.marker);
00600     }
00601 
00602     // publish the new list
00603     object_list_.header.seq++;
00604     object_list_.header.stamp = ros::Time::now();
00605     object_list_.header.frame_id = zone.getSegmentationFrameID();
00606     object_list_.cleared = false;
00607     segmented_objects_pub_.publish(object_list_);
00608 
00609     // publish the new marker array
00610     markers_pub_.publish(markers_);
00611 
00612     // add to the markers
00613     table_marker_ = table_.marker;
00614 
00615     // publish the new list
00616     table_pub_.publish(table_);
00617 
00618     // publish the new marker array
00619     table_marker_pub_.publish(table_marker_);
00620 
00621   } else
00622   {
00623     ROS_WARN("No segmented objects found.");
00624   }
00625 
00626   return true;
00627 }
00628 
00629 rail_manipulation_msgs::SegmentedObject Segmenter::findSurface(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
00630     const pcl::IndicesConstPtr &indices_in, const SegmentationZone &zone,
00631     const pcl::IndicesPtr &indices_out) const
00632 {
00633   rail_manipulation_msgs::SegmentedObject table;
00634 
00635   // use a plane (SAC) segmenter
00636   pcl::SACSegmentation<pcl::PointXYZRGB> plane_seg;
00637   // set the segmenation parameters
00638   plane_seg.setOptimizeCoefficients(true);
00639   plane_seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
00640   plane_seg.setAxis(Eigen::Vector3f(0, 0, 1));
00641   plane_seg.setEpsAngle(SAC_EPS_ANGLE);
00642   plane_seg.setMethodType(pcl::SAC_RANSAC);
00643   plane_seg.setMaxIterations(SAC_MAX_ITERATIONS);
00644   plane_seg.setDistanceThreshold(SAC_DISTANCE_THRESHOLD);
00645 
00646   // create a copy to work with
00647   pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc_copy(new pcl::PointCloud<pcl::PointXYZRGB>(*in));
00648   plane_seg.setInputCloud(pc_copy);
00649   plane_seg.setIndices(indices_in);
00650 
00651   // Check point height -- if the plane is too low or high, extract another
00652   while (true)
00653   {
00654     // points included in the plane (surface)
00655     pcl::PointIndices::Ptr inliers_ptr(new pcl::PointIndices);
00656 
00657     // segment the the current cloud
00658     pcl::ModelCoefficients coefficients;
00659     plane_seg.segment(*inliers_ptr, coefficients);
00660 
00661     // check if we found a surface
00662     if (inliers_ptr->indices.size() == 0)
00663     {
00664       ROS_WARN("Could not find a surface above %fm and below %fm.", zone.getZMin(), zone.getZMax());
00665       *indices_out = *indices_in;
00666       table.centroid.z = -numeric_limits<double>::infinity();
00667       return table;
00668     }
00669 
00670     // remove the plane
00671     pcl::PointCloud<pcl::PointXYZRGB> plane;
00672     pcl::ExtractIndices<pcl::PointXYZRGB> extract(true);
00673     extract.setInputCloud(pc_copy);
00674     extract.setIndices(inliers_ptr);
00675     extract.setNegative(false);
00676     extract.filter(plane);
00677     extract.setKeepOrganized(true);
00678     plane_seg.setIndices(extract.getRemovedIndices());
00679 
00680     // check the height
00681     double height = this->averageZ(plane.points);
00682     if (height >= zone.getZMin() && height <= zone.getZMax())
00683     {
00684       ROS_INFO("Surface found at %fm.", height);
00685       *indices_out = *plane_seg.getIndices();
00686 
00687       // check if we need to transform to a different frame
00688       pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_pc(new pcl::PointCloud<pcl::PointXYZRGB>);
00689       pcl::PCLPointCloud2::Ptr converted(new pcl::PCLPointCloud2);
00690       if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
00691       {
00692         // perform the copy/transform using TF
00693         pcl_ros::transformPointCloud(zone.getSegmentationFrameID(), ros::Time(0), plane, plane.header.frame_id,
00694                                      *transformed_pc, tf_);
00695         transformed_pc->header.frame_id = zone.getSegmentationFrameID();
00696         transformed_pc->header.seq = plane.header.seq;
00697         transformed_pc->header.stamp = plane.header.stamp;
00698         pcl::toPCLPointCloud2(*transformed_pc, *converted);
00699       } else
00700       {
00701         pcl::toPCLPointCloud2(plane, *converted);
00702       }
00703 
00704       // convert to a SegmentedObject message
00705       table.recognized = false;
00706 
00707       // set the RGB image
00708       table.image = this->createImage(pc_copy, *inliers_ptr);
00709 
00710       // check if we want to publish the image
00711       if (debug_)
00712       {
00713         debug_img_pub_.publish(table.image);
00714       }
00715 
00716       // set the point cloud
00717       pcl_conversions::fromPCL(*converted, table.point_cloud);
00718       table.point_cloud.header.stamp = ros::Time::now();
00719       // create a marker and set the extra fields
00720       table.marker = this->createMarker(converted);
00721       table.marker.id = 0;
00722 
00723       // set the centroid
00724       Eigen::Vector4f centroid;
00725       if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
00726       {
00727         pcl::compute3DCentroid(*transformed_pc, centroid);
00728       } else
00729       {
00730         pcl::compute3DCentroid(plane, centroid);
00731       }
00732       table.centroid.x = centroid[0];
00733       table.centroid.y = centroid[1];
00734       table.centroid.z = centroid[2];
00735 
00736       // calculate the bounding box
00737       Eigen::Vector4f min_pt, max_pt;
00738       pcl::getMinMax3D(plane, min_pt, max_pt);
00739       table.width = max_pt[0] - min_pt[0];
00740       table.depth = max_pt[1] - min_pt[1];
00741       table.height = max_pt[2] - min_pt[2];
00742 
00743       // calculate the center
00744       table.center.x = (max_pt[0] + min_pt[0]) / 2.0;
00745       table.center.y = (max_pt[1] + min_pt[1]) / 2.0;
00746       table.center.z = (max_pt[2] + min_pt[2]) / 2.0;
00747 
00748 
00749       // calculate the orientation
00750       pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
00751       // project point cloud onto the xy plane
00752       pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
00753       coefficients->values.resize(4);
00754       coefficients->values[0] = 0;
00755       coefficients->values[1] = 0;
00756       coefficients->values[2] = 1.0;
00757       coefficients->values[3] = 0;
00758       pcl::ProjectInliers<pcl::PointXYZRGB> proj;
00759       proj.setModelType(pcl::SACMODEL_PLANE);
00760       if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
00761       {
00762         proj.setInputCloud(transformed_pc);
00763       } else
00764       {
00765         pcl::PointCloud<pcl::PointXYZRGB>::Ptr plane_ptr(new pcl::PointCloud<pcl::PointXYZRGB>(plane));
00766         proj.setInputCloud(plane_ptr);
00767       }
00768       proj.setModelCoefficients(coefficients);
00769       proj.filter(*projected_cluster);
00770 
00771       //calculate the Eigen vectors of the projected point cloud's covariance matrix, used to determine orientation
00772       Eigen::Vector4f projected_centroid;
00773       Eigen::Matrix3f covariance_matrix;
00774       pcl::compute3DCentroid(*projected_cluster, projected_centroid);
00775       pcl::computeCovarianceMatrixNormalized(*projected_cluster, projected_centroid, covariance_matrix);
00776       Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance_matrix, Eigen::ComputeEigenvectors);
00777       Eigen::Matrix3f eigen_vectors = eigen_solver.eigenvectors();
00778       eigen_vectors.col(2) = eigen_vectors.col(0).cross(eigen_vectors.col(1));
00779       //calculate rotation from eigenvectors
00780       const Eigen::Quaternionf qfinal(eigen_vectors);
00781 
00782       //convert orientation to a single angle on the 2D plane defined by the segmentation coordinate frame
00783       tf::Quaternion tf_quat;
00784       tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
00785       double r, p, y;
00786       tf::Matrix3x3 m(tf_quat);
00787       m.getRPY(r, p, y);
00788       double angle = r + y;
00789       while (angle < -M_PI)
00790       {
00791         angle += 2 * M_PI;
00792       }
00793       while (angle > M_PI)
00794       {
00795         angle -= 2 * M_PI;
00796       }
00797       table.orientation = tf::createQuaternionMsgFromYaw(angle);
00798 
00799       return table;
00800     }
00801   }
00802 }
00803 
00804 void Segmenter::extractClusters(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
00805     const pcl::IndicesConstPtr &indices_in, vector<pcl::PointIndices> &clusters) const
00806 {
00807   // ignore NaN and infinite values
00808   pcl::IndicesPtr valid(new vector<int>);
00809   for (size_t i = 0; i < indices_in->size(); i++)
00810   {
00811     if (pcl_isfinite(in->points[indices_in->at(i)].x) & pcl_isfinite(in->points[indices_in->at(i)].y) &
00812         pcl_isfinite(in->points[indices_in->at(i)].z))
00813     {
00814       valid->push_back(indices_in->at(i));
00815     }
00816   }
00817 
00818   pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> seg;
00819   pcl::search::KdTree<pcl::PointXYZRGB>::Ptr kd_tree(new pcl::search::KdTree<pcl::PointXYZRGB>);
00820   kd_tree->setInputCloud(in);
00821   seg.setClusterTolerance(CLUSTER_TOLERANCE);
00822   seg.setMinClusterSize(min_cluster_size_);
00823   seg.setMaxClusterSize(max_cluster_size_);
00824   seg.setSearchMethod(kd_tree);
00825   seg.setInputCloud(in);
00826   seg.setIndices(valid);
00827   seg.extract(clusters);
00828 }
00829 
00830 sensor_msgs::Image Segmenter::createImage(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
00831     const pcl::PointIndices &cluster) const
00832 {
00833   // determine the bounds of the cluster
00834   int row_min = numeric_limits<int>::max();
00835   int row_max = numeric_limits<int>::min();
00836   int col_min = numeric_limits<int>::max();
00837   int col_max = numeric_limits<int>::min();
00838 
00839   for (size_t i = 0; i < cluster.indices.size(); i++)
00840   {
00841     // calculate row and column of this point
00842     int row = cluster.indices[i] / in->width;
00843     int col = cluster.indices[i] - (row * in->width);
00844 
00845     if (row < row_min)
00846     {
00847       row_min = row;
00848     } else if (row > row_max)
00849     {
00850       row_max = row;
00851     }
00852     if (col < col_min)
00853     {
00854       col_min = col;
00855     } else if (col > col_max)
00856     {
00857       col_max = col;
00858     }
00859   }
00860 
00861   // create a ROS image
00862   sensor_msgs::Image msg;
00863 
00864   // set basic information
00865   msg.header.frame_id = in->header.frame_id;
00866   msg.header.stamp = ros::Time::now();
00867   msg.width = col_max - col_min;
00868   msg.height = row_max - row_min;
00869   // RGB data
00870   msg.step = 3 * msg.width;
00871   msg.data.resize(msg.step * msg.height);
00872   msg.encoding = sensor_msgs::image_encodings::BGR8;
00873 
00874   // extract the points
00875   for (int h = 0; h < msg.height; h++)
00876   {
00877     for (int w = 0; w < msg.width; w++)
00878     {
00879       // extract RGB information
00880       const pcl::PointXYZRGB &point = in->at(col_min + w, row_min + h);
00881       // set RGB data
00882       int index = (msg.step * h) + (w * 3);
00883       msg.data[index] = point.b;
00884       msg.data[index + 1] = point.g;
00885       msg.data[index + 2] = point.r;
00886     }
00887   }
00888 
00889   return msg;
00890 }
00891 
00892 visualization_msgs::Marker Segmenter::createMarker(const pcl::PCLPointCloud2::ConstPtr &pc) const
00893 {
00894   visualization_msgs::Marker marker;
00895   // set header field
00896   marker.header.frame_id = pc->header.frame_id;
00897 
00898   // default position
00899   marker.pose.position.x = 0.0;
00900   marker.pose.position.y = 0.0;
00901   marker.pose.position.z = 0.0;
00902   marker.pose.orientation.x = 0.0;
00903   marker.pose.orientation.y = 0.0;
00904   marker.pose.orientation.z = 0.0;
00905   marker.pose.orientation.w = 1.0;
00906 
00907   // default scale
00908   marker.scale.x = MARKER_SCALE;
00909   marker.scale.y = MARKER_SCALE;
00910   marker.scale.z = MARKER_SCALE;
00911 
00912   // set the type of marker and our color of choice
00913   marker.type = visualization_msgs::Marker::CUBE_LIST;
00914   marker.color.a = 1.0;
00915 
00916   // downsample point cloud for visualization
00917   pcl::PCLPointCloud2 downsampled;
00918   pcl::VoxelGrid<pcl::PCLPointCloud2> voxel_grid;
00919   voxel_grid.setInputCloud(pc);
00920   voxel_grid.setLeafSize(DOWNSAMPLE_LEAF_SIZE, DOWNSAMPLE_LEAF_SIZE, DOWNSAMPLE_LEAF_SIZE);
00921   voxel_grid.filter(downsampled);
00922 
00923   // convert to an easy to use point cloud message
00924   sensor_msgs::PointCloud2 pc2_msg;
00925   pcl_conversions::fromPCL(downsampled, pc2_msg);
00926   sensor_msgs::PointCloud pc_msg;
00927   sensor_msgs::convertPointCloud2ToPointCloud(pc2_msg, pc_msg);
00928 
00929   // place in the marker message
00930   marker.points.resize(pc_msg.points.size());
00931   int r = 0, g = 0, b = 0;
00932   for (size_t j = 0; j < pc_msg.points.size(); j++)
00933   {
00934     marker.points[j].x = pc_msg.points[j].x;
00935     marker.points[j].y = pc_msg.points[j].y;
00936     marker.points[j].z = pc_msg.points[j].z;
00937 
00938     // use average RGB
00939     uint32_t rgb = *reinterpret_cast<int *>(&pc_msg.channels[0].values[j]);
00940     r += (int) ((rgb >> 16) & 0x0000ff);
00941     g += (int) ((rgb >> 8) & 0x0000ff);
00942     b += (int) ((rgb) & 0x0000ff);
00943   }
00944 
00945   // set average RGB
00946   marker.color.r = ((float) r / (float) pc_msg.points.size()) / 255.0;
00947   marker.color.g = ((float) g / (float) pc_msg.points.size()) / 255.0;
00948   marker.color.b = ((float) b / (float) pc_msg.points.size()) / 255.0;
00949   marker.color.a = 1.0;
00950 
00951   return marker;
00952 }
00953 
00954 void Segmenter::extract(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in, const pcl::IndicesConstPtr &indices_in,
00955     const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &out) const
00956 {
00957   pcl::ExtractIndices<pcl::PointXYZRGB> extract;
00958   extract.setInputCloud(in);
00959   extract.setIndices(indices_in);
00960   extract.filter(*out);
00961 }
00962 
00963 void Segmenter::inverseBound(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
00964     const pcl::IndicesConstPtr &indices_in,
00965     const pcl::ConditionBase<pcl::PointXYZRGB>::Ptr &conditions,
00966     const pcl::IndicesPtr &indices_out) const
00967 {
00968   // use a temp point cloud to extract the indices
00969   pcl::PointCloud<pcl::PointXYZRGB> tmp;
00970   pcl::ConditionalRemoval<pcl::PointXYZRGB> removal(conditions, true);
00971   removal.setInputCloud(in);
00972   removal.setIndices(indices_in);
00973   removal.filter(tmp);
00974   *indices_out = *removal.getRemovedIndices();
00975 }
00976 
00977 double Segmenter::averageZ(const vector<pcl::PointXYZRGB, Eigen::aligned_allocator<pcl::PointXYZRGB> > &v) const
00978 {
00979   double avg = 0.0;
00980   for (size_t i = 0; i < v.size(); i++)
00981   {
00982     avg += v[i].z;
00983   }
00984   return (avg / (double) v.size());
00985 }


rail_segmentation
Author(s): Russell Toris , David Kent
autogenerated on Tue Sep 20 2016 03:52:24