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


rail_segmentation
Author(s): Russell Toris , David Kent
autogenerated on Sat Jun 8 2019 19:54:19