Segmenter.cpp
Go to the documentation of this file.
1 
13 // RAIL Segmentation
15 
16 using namespace std;
17 using namespace rail::segmentation;
18 
19 //constant definitions (to use in functions with reference parameters, e.g. param())
20 #if __cplusplus >= 201103L
21  constexpr bool Segmenter::DEFAULT_DEBUG;
22  constexpr int Segmenter::DEFAULT_MIN_CLUSTER_SIZE;
23  constexpr int Segmenter::DEFAULT_MAX_CLUSTER_SIZE;
24  constexpr double Segmenter::CLUSTER_TOLERANCE;
25 #else
26  const bool Segmenter::DEFAULT_DEBUG;
27  const int Segmenter::DEFAULT_MIN_CLUSTER_SIZE;
28  const int Segmenter::DEFAULT_MAX_CLUSTER_SIZE;
29  const double Segmenter::CLUSTER_TOLERANCE;
30 #endif
31 
32 Segmenter::Segmenter() : private_node_("~"), tf2_(tf_buffer_)
33 {
34  // flag for using the provided point cloud
35 
36  // set defaults
37  string point_cloud_topic("/head_camera/depth_registered/points");
38  string zones_file(ros::package::getPath("rail_segmentation") + "/config/zones.yaml");
39 
40  // grab any parameters we need
45  private_node_.param("use_color", use_color_, false);
46  private_node_.param("crop_first", crop_first_, false);
47  private_node_.param("label_markers", label_markers_, false);
48  private_node_.param<string>("point_cloud_topic", point_cloud_topic_, "/head_camera/depth_registered/points");
49  private_node_.getParam("zones_config", zones_file);
50 
51  // setup publishers/subscribers we need
58  this);
59  segmented_objects_pub_ = private_node_.advertise<rail_manipulation_msgs::SegmentedObjectList>(
60  "segmented_objects", 1, true
61  );
62  table_pub_ = private_node_.advertise<rail_manipulation_msgs::SegmentedObject>(
63  "segmented_table", 1, true
64  );
65  markers_pub_ = private_node_.advertise<visualization_msgs::MarkerArray>("markers", 1, true);
66  table_marker_pub_ = private_node_.advertise<visualization_msgs::Marker>("table_marker", 1, true);
67  // setup a debug publisher if we need it
68  if (debug_)
69  {
70  debug_pc_pub_ = private_node_.advertise<pcl::PointCloud<pcl::PointXYZRGB> >("debug_pc", 1, true);
71  debug_img_pub_ = private_node_.advertise<sensor_msgs::Image>("debug_img", 1, true);
72  }
73 
74  // check the YAML version
75 #ifdef YAMLCPP_GT_0_5_0
76  // parse the segmentation zones
77  YAML::Node zones_config = YAML::LoadFile(zones_file);
78  for (size_t i = 0; i < zones_config.size(); i++)
79  {
80  YAML::Node cur = zones_config[i];
81  // create a zone with the frame ID information
82  SegmentationZone zone(cur["name"].as<string>(), cur["parent_frame_id"].as<string>(),
83  cur["child_frame_id"].as<string>(), cur["bounding_frame_id"].as<string>(),
84  cur["segmentation_frame_id"].as<string>());
85 
86  // check for the remove surface flag
87  if (cur["remove_surface"].IsDefined())
88  {
89  zone.setRemoveSurface(cur["remove_surface"].as<bool>());
90  }
91 
92  // check for the remove surface flag
93  if (cur["require_surface"].IsDefined())
94  {
95  zone.setRequireSurface(cur["require_surface"].as<bool>());
96  }
97 
98  // check for any set limits
99  if (cur["roll_min"].IsDefined())
100  {
101  zone.setRollMin(cur["roll_min"].as<double>());
102  }
103  if (cur["roll_max"].IsDefined())
104  {
105  zone.setRollMax(cur["roll_max"].as<double>());
106  }
107  if (cur["pitch_min"].IsDefined())
108  {
109  zone.setPitchMin(cur["pitch_min"].as<double>());
110  }
111  if (cur["pitch_max"].IsDefined())
112  {
113  zone.setPitchMax(cur["pitch_max"].as<double>());
114  }
115  if (cur["yaw_min"].IsDefined())
116  {
117  zone.setYawMin(cur["yaw_min"].as<double>());
118  }
119  if (cur["yaw_max"].IsDefined())
120  {
121  zone.setYawMax(cur["yaw_max"].as<double>());
122  }
123  if (cur["x_min"].IsDefined())
124  {
125  zone.setXMin(cur["x_min"].as<double>());
126  }
127  if (cur["x_max"].IsDefined())
128  {
129  zone.setXMax(cur["x_max"].as<double>());
130  }
131  if (cur["y_min"].IsDefined())
132  {
133  zone.setYMin(cur["y_min"].as<double>());
134  }
135  if (cur["y_max"].IsDefined())
136  {
137  zone.setYMax(cur["y_max"].as<double>());
138  }
139  if (cur["z_min"].IsDefined())
140  {
141  zone.setZMin(cur["z_min"].as<double>());
142  }
143  if (cur["z_max"].IsDefined())
144  {
145  zone.setZMax(cur["z_max"].as<double>());
146  }
147 
148  zones_.push_back(zone);
149  }
150 #else
151  // parse the segmentation zones
152  ifstream fin(zones_file.c_str());
153  YAML::Parser zones_parser(fin);
154  YAML::Node zones_config;
155  zones_parser.GetNextDocument(zones_config);
156  for (size_t i = 0; i < zones_config.size(); i++)
157  {
158  // parse the required information
159  string name, parent_frame_id, child_frame_id, bounding_frame_id, segmentation_frame_id;
160  zones_config[i]["name"] >> name;
161  zones_config[i]["parent_frame_id"] >> parent_frame_id;
162  zones_config[i]["child_frame_id"] >> child_frame_id;
163  zones_config[i]["bounding_frame_id"] >> bounding_frame_id;
164  zones_config[i]["segmentation_frame_id"] >> segmentation_frame_id;
165 
166  // create a zone with the frame ID information
167  SegmentationZone zone(name, parent_frame_id, child_frame_id, bounding_frame_id, segmentation_frame_id);
168 
169  // check for the remove surface flag
170  if (zones_config[i].FindValue("remove_surface") != NULL)
171  {
172  bool remove_surface;
173  zones_config[i]["remove_surface"] >> remove_surface;
174  zone.setRemoveSurface(remove_surface);
175  }
176  if (zones_config[i].FindValue("require_surface") != NULL)
177  {
178  bool require_surface;
179  zones_config[i]["require_surface"] >> require_surface;
180  zone.setRequireSurface(require_surface);
181  }
182 
183  // check for any set limits
184  if (zones_config[i].FindValue("roll_min") != NULL)
185  {
186  double roll_min;
187  zones_config[i]["roll_min"] >> roll_min;
188  zone.setRollMin(roll_min);
189  }
190  if (zones_config[i].FindValue("roll_max") != NULL)
191  {
192  double roll_max;
193  zones_config[i]["roll_max"] >> roll_max;
194  zone.setRollMax(roll_max);
195  }
196  if (zones_config[i].FindValue("pitch_min") != NULL)
197  {
198  double pitch_min;
199  zones_config[i]["pitch_min"] >> pitch_min;
200  zone.setPitchMin(pitch_min);
201  }
202  if (zones_config[i].FindValue("pitch_max") != NULL)
203  {
204  double pitch_max;
205  zones_config[i]["pitch_max"] >> pitch_max;
206  zone.setPitchMax(pitch_max);
207  }
208  if (zones_config[i].FindValue("yaw_min") != NULL)
209  {
210  double yaw_min;
211  zones_config[i]["yaw_min"] >> yaw_min;
212  zone.setYawMin(yaw_min);
213  }
214  if (zones_config[i].FindValue("yaw_max") != NULL)
215  {
216  double yaw_max;
217  zones_config[i]["yaw_max"] >> yaw_max;
218  zone.setYawMax(yaw_max);
219  }
220  if (zones_config[i].FindValue("x_min") != NULL)
221  {
222  double x_min;
223  zones_config[i]["x_min"] >> x_min;
224  zone.setXMin(x_min);
225  }
226  if (zones_config[i].FindValue("x_max") != NULL)
227  {
228  double x_max;
229  zones_config[i]["x_max"] >> x_max;
230  zone.setXMax(x_max);
231  }
232  if (zones_config[i].FindValue("y_min") != NULL)
233  {
234  double y_min;
235  zones_config[i]["y_min"] >> y_min;
236  zone.setYMin(y_min);
237  }
238  if (zones_config[i].FindValue("y_max") != NULL)
239  {
240  double y_max;
241  zones_config[i]["y_max"] >> y_max;
242  zone.setYMax(y_max);
243  }
244  if (zones_config[i].FindValue("z_min") != NULL)
245  {
246  double z_min;
247  zones_config[i]["z_min"] >> z_min;
248  zone.setZMin(z_min);
249  }
250  if (zones_config[i].FindValue("z_max") != NULL)
251  {
252  double z_max;
253  zones_config[i]["z_max"] >> z_max;
254  zone.setZMax(z_max);
255  }
256 
257  zones_.push_back(zone);
258  }
259 #endif
260 
261  // check how many zones we have
262  if (zones_.size() > 0)
263  {
264  ROS_INFO("%d segmenation zone(s) parsed.", (int) zones_.size());
265  ROS_INFO("Segmenter Successfully Initialized");
266  okay_ = true;
267  } else
268  {
269  ROS_ERROR("No valid segmenation zones defined. Check %s.", zones_file.c_str());
270  okay_ = false;
271  }
272 }
273 
274 bool Segmenter::okay() const
275 {
276  return okay_;
277 }
278 
280 {
281  // check each zone
282  for (size_t i = 0; i < zones_.size(); i++)
283  {
284  // get the current TF information
285  geometry_msgs::TransformStamped tf = tf_buffer_.lookupTransform(zones_[i].getParentFrameID(),
286  zones_[i].getChildFrameID(), ros::Time(0));
287 
288  // convert to a Matrix3x3 to get RPY
289  tf2::Matrix3x3 mat(tf2::Quaternion(tf.transform.rotation.x, tf.transform.rotation.y, tf.transform.rotation.z,
290  tf.transform.rotation.w));
291  double roll, pitch, yaw;
292  mat.getRPY(roll, pitch, yaw);
293 
294  // check if all the bounds meet
295  if (roll >= zones_[i].getRollMin() && pitch >= zones_[i].getPitchMin() && yaw >= zones_[i].getYawMin() &&
296  roll <= zones_[i].getRollMax() && pitch <= zones_[i].getPitchMax() && yaw <= zones_[i].getYawMax())
297  {
298  return zones_[i];
299  }
300  }
301 
302  ROS_WARN("Current state not in a valid segmentation zone. Defaulting to first zone.");
303  return zones_[0];
304 }
305 
306 bool Segmenter::removeObjectCallback(rail_segmentation::RemoveObject::Request &req,
307  rail_segmentation::RemoveObject::Response &res)
308 {
309  // lock for the messages
310  boost::mutex::scoped_lock lock(msg_mutex_);
311  // check the index
312  if (req.index < object_list_.objects.size() && req.index < markers_.markers.size())
313  {
314  // remove
315  object_list_.objects.erase(object_list_.objects.begin() + req.index);
316  // set header information
317  object_list_.header.seq++;
318  object_list_.header.stamp = ros::Time::now();
319  object_list_.cleared = false;
320  // republish
322  // delete marker
323  markers_.markers[req.index].action = visualization_msgs::Marker::DELETE;
324  if (label_markers_)
325  {
326  text_markers_.markers[req.index].action = visualization_msgs::Marker::DELETE;
327  }
328 
329  if (label_markers_)
330  {
331  visualization_msgs::MarkerArray marker_list;
332  marker_list.markers.reserve(markers_.markers.size() + text_markers_.markers.size());
333  marker_list.markers.insert(marker_list.markers.end(), markers_.markers.begin(), markers_.markers.end());
334  marker_list.markers.insert(marker_list.markers.end(), text_markers_.markers.begin(), text_markers_.markers.end());
335  markers_pub_.publish(marker_list);
336  }
337  else
338  {
340  }
341 
342  if (label_markers_)
343  {
344  text_markers_.markers.erase(text_markers_.markers.begin() + req.index);
345  }
346  markers_.markers.erase(markers_.markers.begin() + req.index);
347  return true;
348  } else
349  {
350  ROS_ERROR("Attempted to remove index %d from list of size %ld.", req.index, object_list_.objects.size());
351  return false;
352  }
353 }
354 
355 bool Segmenter::clearCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
356 {
357  // lock for the messages
358  boost::mutex::scoped_lock lock(msg_mutex_);
359  // empty the list
360  object_list_.objects.clear();
361  object_list_.cleared = true;
362  // set header information
363  object_list_.header.seq++;
364  object_list_.header.stamp = ros::Time::now();
365  // republish
367  // delete markers
368  for (size_t i = 0; i < markers_.markers.size(); i++)
369  {
370  markers_.markers[i].action = visualization_msgs::Marker::DELETE;
371  }
372  if (label_markers_)
373  {
374  for (size_t i = 0; i < text_markers_.markers.size(); i++)
375  {
376  text_markers_.markers[i].action = visualization_msgs::Marker::DELETE;
377  }
378  }
379 
380  if (label_markers_)
381  {
382  visualization_msgs::MarkerArray marker_list;
383  marker_list.markers.reserve(markers_.markers.size() + text_markers_.markers.size());
384  marker_list.markers.insert(marker_list.markers.end(), markers_.markers.begin(), markers_.markers.end());
385  marker_list.markers.insert(marker_list.markers.end(), text_markers_.markers.begin(), text_markers_.markers.end());
386  markers_pub_.publish(marker_list);
387  } else
388  {
390  }
391 
392  markers_.markers.clear();
393 
394  if (label_markers_)
395  {
396  text_markers_.markers.clear();
397  }
398 
399  table_marker_.action = visualization_msgs::Marker::DELETE;
401  return true;
402 }
403 
404 bool Segmenter::segmentCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
405 {
406  rail_manipulation_msgs::SegmentedObjectList objects;
407  return segmentObjects(objects);
408 }
409 
410 bool Segmenter::segmentObjectsCallback(rail_manipulation_msgs::SegmentObjects::Request &req,
411  rail_manipulation_msgs::SegmentObjects::Response &res)
412 {
413  return segmentObjects(res.segmented_objects);
414 }
415 
416 bool Segmenter::segmentObjectsFromPointCloudCallback(rail_manipulation_msgs::SegmentObjectsFromPointCloud::Request &req,
417  rail_manipulation_msgs::SegmentObjectsFromPointCloud::Response &res)
418 {
419  // convert pc from sensor_msgs::PointCloud2 to pcl::PointCloud<pcl::PointXYZRGB>
420  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc(new pcl::PointCloud<pcl::PointXYZRGB>);
421 
422  pcl::fromROSMsg(req.point_cloud, *pc);
423 
424  return executeSegmentation(pc, res.segmented_objects);
425 }
426 
427 bool Segmenter::segmentObjects(rail_manipulation_msgs::SegmentedObjectList &objects)
428 {
429  // get the latest point cloud
430  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc(new pcl::PointCloud<pcl::PointXYZRGB>);
431  ros::Time request_time = ros::Time::now();
432  ros::Time point_cloud_time = request_time - ros::Duration(0.1);
433  while (point_cloud_time < request_time)
434  {
435  pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr pc_msg =
436  ros::topic::waitForMessage<pcl::PointCloud<pcl::PointXYZRGB> >(point_cloud_topic_, node_,
437  ros::Duration(10.0));
438  if (pc_msg == NULL)
439  {
440  ROS_INFO("No point cloud received for segmentation.");
441  return false;
442  }
443  else
444  {
445  *pc = *pc_msg;
446  }
447  point_cloud_time = pcl_conversions::fromPCL(pc->header.stamp);
448  }
449 
450  return executeSegmentation(pc, objects);
451 }
452 
453 bool Segmenter::executeSegmentation(pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc,
454  rail_manipulation_msgs::SegmentedObjectList &objects)
455 {
456  // clear the objects first
457  std_srvs::Empty empty;
458  this->clearCallback(empty.request, empty.response);
459 
460  // determine the correct segmentation zone
461  const SegmentationZone &zone = this->getCurrentZone();
462  ROS_INFO("Segmenting in zone '%s'.", zone.getName().c_str());
463 
464  // transform the point cloud to the fixed frame
465  pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_pc(new pcl::PointCloud<pcl::PointXYZRGB>);
466  pcl_ros::transformPointCloud(zone.getBoundingFrameID(), ros::Time(0), *pc, pc->header.frame_id,
467  *transformed_pc, tf_);
468  transformed_pc->header.frame_id = zone.getBoundingFrameID();
469  transformed_pc->header.seq = pc->header.seq;
470  transformed_pc->header.stamp = pc->header.stamp;
471 
472  // start with every index
473  pcl::IndicesPtr filter_indices(new vector<int>);
474  filter_indices->resize(transformed_pc->points.size());
475  for (size_t i = 0; i < transformed_pc->points.size(); i++)
476  {
477  filter_indices->at(i) = i;
478  }
479 
480  // check if we need to remove a surface
481  double z_min = zone.getZMin();
482  if (!crop_first_)
483  {
484  if (zone.getRemoveSurface())
485  {
486  bool surface_found = this->findSurface(transformed_pc, filter_indices, zone, filter_indices, table_);
487  if (zone.getRequireSurface() && !surface_found)
488  {
489  objects.objects.clear();
490  ROS_INFO("Could not find a surface within the segmentation zone. Exiting segmentation with no objects found.");
491  return true;
492  }
493  double z_surface = table_.centroid.z;
494  // check the new bound for Z
495  z_min = max(zone.getZMin(), z_surface + SURFACE_REMOVAL_PADDING);
496  }
497  }
498 
499  // check bounding areas (bound the inverse of what we want since PCL will return the removed indicies)
500  pcl::ConditionOr<pcl::PointXYZRGB>::Ptr bounds(new pcl::ConditionOr<pcl::PointXYZRGB>);
501  if (z_min > -numeric_limits<double>::infinity())
502  {
503  bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
504  new pcl::FieldComparison<pcl::PointXYZRGB>("z", pcl::ComparisonOps::LE, z_min))
505  );
506  }
507  if (zone.getZMax() < numeric_limits<double>::infinity())
508  {
509  bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
510  new pcl::FieldComparison<pcl::PointXYZRGB>("z", pcl::ComparisonOps::GE, zone.getZMax()))
511  );
512  }
513  if (zone.getYMin() > -numeric_limits<double>::infinity())
514  {
515  bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
516  new pcl::FieldComparison<pcl::PointXYZRGB>("y", pcl::ComparisonOps::LE, zone.getYMin()))
517  );
518  }
519  if (zone.getYMax() < numeric_limits<double>::infinity())
520  {
521  bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
522  new pcl::FieldComparison<pcl::PointXYZRGB>("y", pcl::ComparisonOps::GE, zone.getYMax()))
523  );
524  }
525  if (zone.getXMin() > -numeric_limits<double>::infinity())
526  {
527  bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
528  new pcl::FieldComparison<pcl::PointXYZRGB>("x", pcl::ComparisonOps::LE, zone.getXMin()))
529  );
530  }
531  if (zone.getXMax() < numeric_limits<double>::infinity())
532  {
533  bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
534  new pcl::FieldComparison<pcl::PointXYZRGB>("x", pcl::ComparisonOps::GE, zone.getXMax()))
535  );
536  }
537 
538  // remove past the given bounds
539  this->inverseBound(transformed_pc, filter_indices, bounds, filter_indices);
540 
541  if (crop_first_)
542  {
543  if (zone.getRemoveSurface())
544  {
545  bool surface_found = this->findSurface(transformed_pc, filter_indices, zone, filter_indices, table_);
546  if (zone.getRequireSurface() && !surface_found)
547  {
548  objects.objects.clear();
549  ROS_INFO("Could not find a surface within the segmentation zone. Exiting segmentation with no objects found.");
550  return true;
551  }
552  double z_surface = table_.centroid.z;
553  // check the new bound for Z
554  z_min = max(zone.getZMin(), z_surface + SURFACE_REMOVAL_PADDING);
555 
556  pcl::ConditionOr<pcl::PointXYZRGB>::Ptr table_bounds(new pcl::ConditionOr<pcl::PointXYZRGB>);
557  table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
558  new pcl::FieldComparison<pcl::PointXYZRGB>("z", pcl::ComparisonOps::LE, z_min))
559  );
560 
561  // plane segmentation does adds back in the filtered indices, so we need to re-add the old bounds (this should
562  // be faster than conditionally merging the two lists of indices, which would require a bunch of searches the
563  // length of the point cloud's number of points)
564  if (zone.getZMax() < numeric_limits<double>::infinity())
565  {
566  table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
567  new pcl::FieldComparison<pcl::PointXYZRGB>("z", pcl::ComparisonOps::GE, zone.getZMax()))
568  );
569  }
570  if (zone.getYMin() > -numeric_limits<double>::infinity())
571  {
572  table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
573  new pcl::FieldComparison<pcl::PointXYZRGB>("y", pcl::ComparisonOps::LE, zone.getYMin()))
574  );
575  }
576  if (zone.getYMax() < numeric_limits<double>::infinity())
577  {
578  table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
579  new pcl::FieldComparison<pcl::PointXYZRGB>("y", pcl::ComparisonOps::GE, zone.getYMax()))
580  );
581  }
582  if (zone.getXMin() > -numeric_limits<double>::infinity())
583  {
584  table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
585  new pcl::FieldComparison<pcl::PointXYZRGB>("x", pcl::ComparisonOps::LE, zone.getXMin()))
586  );
587  }
588  if (zone.getXMax() < numeric_limits<double>::infinity())
589  {
590  table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
591  new pcl::FieldComparison<pcl::PointXYZRGB>("x", pcl::ComparisonOps::GE, zone.getXMax()))
592  );
593  }
594 
595  // remove below the table bounds
596  this->inverseBound(transformed_pc, filter_indices, table_bounds, filter_indices);
597  }
598  }
599 
600  // publish the filtered and bounded PC pre-segmentation
601  if (debug_)
602  {
603  pcl::PointCloud<pcl::PointXYZRGB>::Ptr debug_pc(new pcl::PointCloud<pcl::PointXYZRGB>);
604  this->extract(transformed_pc, filter_indices, debug_pc);
605  debug_pc_pub_.publish(debug_pc);
606  }
607 
608  // extract clusters
609  vector<pcl::PointIndices> clusters;
610  if (use_color_)
611  this->extractClustersRGB(transformed_pc, filter_indices, clusters);
612  else
613  this->extractClustersEuclidean(transformed_pc, filter_indices, clusters);
614 
615  if (clusters.size() > 0)
616  {
617  // lock for the messages
618  boost::mutex::scoped_lock lock(msg_mutex_);
619  // check each cluster
620  for (size_t i = 0; i < clusters.size(); i++)
621  {
622  // Keep track of image indices of points in the cluster
623  vector<int> cluster_indices;
624  // grab the points we need
625  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
626  for (size_t j = 0; j < clusters[i].indices.size(); j++)
627  {
628  cluster->points.push_back(transformed_pc->points[clusters[i].indices[j]]);
629  cluster_indices.push_back(clusters[i].indices[j]);
630  }
631  cluster->width = cluster->points.size();
632  cluster->height = 1;
633  cluster->is_dense = true;
634  cluster->header.frame_id = transformed_pc->header.frame_id;
635 
636  // check if we need to transform to a different frame
637  pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
638  pcl::PCLPointCloud2::Ptr converted(new pcl::PCLPointCloud2);
639  if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
640  {
641  // perform the copy/transform using TF
642  pcl_ros::transformPointCloud(zone.getSegmentationFrameID(), ros::Time(0), *cluster, cluster->header.frame_id,
643  *transformed_cluster, tf_);
644  transformed_cluster->header.frame_id = zone.getSegmentationFrameID();
645  transformed_cluster->header.seq = cluster->header.seq;
646  transformed_cluster->header.stamp = cluster->header.stamp;
647  pcl::toPCLPointCloud2(*transformed_cluster, *converted);
648  } else
649  {
650  pcl::toPCLPointCloud2(*cluster, *converted);
651  }
652 
653  // convert to a SegmentedObject message
654  rail_manipulation_msgs::SegmentedObject segmented_object;
655  segmented_object.recognized = false;
656  // store the indices of the object
657  segmented_object.image_indices = cluster_indices;
658 
659  // set the RGB image
660  segmented_object.image = this->createImage(transformed_pc, clusters[i]);
661 
662  // check if we want to publish the image
663  if (debug_)
664  {
665  debug_img_pub_.publish(segmented_object.image);
666  }
667 
668  // set the point cloud
669  pcl_conversions::fromPCL(*converted, segmented_object.point_cloud);
670  segmented_object.point_cloud.header.stamp = ros::Time::now();
671  // create a marker and set the extra fields
672  segmented_object.marker = this->createMarker(converted);
673  segmented_object.marker.id = i;
674 
675  // calculate color features
676  Eigen::Vector3f rgb, lab;
677  rgb[0] = segmented_object.marker.color.r;
678  rgb[1] = segmented_object.marker.color.g;
679  rgb[2] = segmented_object.marker.color.b;
680  lab = RGB2Lab(rgb);
681  segmented_object.rgb.resize(3);
682  segmented_object.cielab.resize(3);
683  segmented_object.rgb[0] = rgb[0];
684  segmented_object.rgb[1] = rgb[1];
685  segmented_object.rgb[2] = rgb[2];
686  segmented_object.cielab[0] = lab[0];
687  segmented_object.cielab[1] = lab[1];
688  segmented_object.cielab[2] = lab[2];
689 
690  // set the centroid
691  Eigen::Vector4f centroid;
692  if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
693  {
694  pcl::compute3DCentroid(*transformed_cluster, centroid);
695  } else
696  {
697  pcl::compute3DCentroid(*cluster, centroid);
698  }
699  segmented_object.centroid.x = centroid[0];
700  segmented_object.centroid.y = centroid[1];
701  segmented_object.centroid.z = centroid[2];
702 
703  // calculate the minimum volume bounding box (assuming the object is resting on a flat surface)
704  segmented_object.bounding_volume = BoundingVolumeCalculator::computeBoundingVolume(segmented_object.point_cloud);
705 
706  // calculate the axis-aligned bounding box
707  Eigen::Vector4f min_pt, max_pt;
708  pcl::getMinMax3D(*cluster, min_pt, max_pt);
709  segmented_object.width = max_pt[0] - min_pt[0];
710  segmented_object.depth = max_pt[1] - min_pt[1];
711  segmented_object.height = max_pt[2] - min_pt[2];
712 
713  // calculate the center
714  segmented_object.center.x = (max_pt[0] + min_pt[0]) / 2.0;
715  segmented_object.center.y = (max_pt[1] + min_pt[1]) / 2.0;
716  segmented_object.center.z = (max_pt[2] + min_pt[2]) / 2.0;
717 
718  // calculate the orientation
719  pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
720  // project point cloud onto the xy plane
721  pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
722  coefficients->values.resize(4);
723  coefficients->values[0] = 0;
724  coefficients->values[1] = 0;
725  coefficients->values[2] = 1.0;
726  coefficients->values[3] = 0;
727  pcl::ProjectInliers<pcl::PointXYZRGB> proj;
728  proj.setModelType(pcl::SACMODEL_PLANE);
729  if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
730  {
731  proj.setInputCloud(transformed_cluster);
732  } else
733  {
734  proj.setInputCloud(cluster);
735  }
736  proj.setModelCoefficients(coefficients);
737  proj.filter(*projected_cluster);
738 
739  //calculate the Eigen vectors of the projected point cloud's covariance matrix, used to determine orientation
740  Eigen::Vector4f projected_centroid;
741  Eigen::Matrix3f covariance_matrix;
742  pcl::compute3DCentroid(*projected_cluster, projected_centroid);
743  pcl::computeCovarianceMatrixNormalized(*projected_cluster, projected_centroid, covariance_matrix);
744  Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance_matrix, Eigen::ComputeEigenvectors);
745  Eigen::Matrix3f eigen_vectors = eigen_solver.eigenvectors();
746  eigen_vectors.col(2) = eigen_vectors.col(0).cross(eigen_vectors.col(1));
747  //calculate rotation from eigenvectors
748  const Eigen::Quaternionf qfinal(eigen_vectors);
749 
750  //convert orientation to a single angle on the 2D plane defined by the segmentation coordinate frame
751  tf::Quaternion tf_quat;
752  tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
753  double r, p, y;
754  tf::Matrix3x3 m(tf_quat);
755  m.getRPY(r, p, y);
756  double angle = r + y;
757  while (angle < -M_PI)
758  {
759  angle += 2 * M_PI;
760  }
761  while (angle > M_PI)
762  {
763  angle -= 2 * M_PI;
764  }
765  segmented_object.orientation = tf::createQuaternionMsgFromYaw(angle);
766 
767  // add to the final list
768  objects.objects.push_back(segmented_object);
769  // add to the markers
770  markers_.markers.push_back(segmented_object.marker);
771 
772  if (label_markers_)
773  {
774  // create a text marker to label the current marker
775  visualization_msgs::Marker text_marker;
776  text_marker.header = segmented_object.marker.header;
777  text_marker.ns = "segmentation_labels";
778  text_marker.id = i;
779  text_marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
780  text_marker.action = visualization_msgs::Marker::ADD;
781 
782  text_marker.pose.position.x = segmented_object.center.x;
783  text_marker.pose.position.y = segmented_object.center.y;
784  text_marker.pose.position.z = segmented_object.center.z + 0.05 + segmented_object.height/2.0;
785 
786  text_marker.scale.x = .1;
787  text_marker.scale.y = .1;
788  text_marker.scale.z = .1;
789 
790  text_marker.color.r = 1;
791  text_marker.color.g = 1;
792  text_marker.color.b = 1;
793  text_marker.color.a = 1;
794 
795  stringstream marker_label;
796  marker_label << "i:" << i;
797  text_marker.text = marker_label.str();
798 
799  text_markers_.markers.push_back(text_marker);
800  }
801  }
802 
803  // create the new list
804  objects.header.seq++;
805  objects.header.stamp = ros::Time::now();
806  objects.header.frame_id = zone.getSegmentationFrameID();
807  objects.cleared = false;
808 
809  // update the new list and publish it
810  object_list_ = objects;
812 
813  // publish the new marker array
814  if (label_markers_)
815  {
816  visualization_msgs::MarkerArray marker_list;
817  marker_list.markers.reserve(markers_.markers.size() + text_markers_.markers.size());
818  marker_list.markers.insert(marker_list.markers.end(), markers_.markers.begin(), markers_.markers.end());
819  marker_list.markers.insert(marker_list.markers.end(), text_markers_.markers.begin(), text_markers_.markers.end());
820  markers_pub_.publish(marker_list);
821  } else
822  {
824  }
825 
826  // add to the markers
827  table_marker_ = table_.marker;
828 
829  // publish the new list
831 
832  // publish the new marker array
834 
835  } else
836  {
837  ROS_WARN("No segmented objects found.");
838  }
839 
840  return true;
841 }
842 
843 bool Segmenter::calculateFeaturesCallback(rail_manipulation_msgs::ProcessSegmentedObjects::Request &req,
844  rail_manipulation_msgs::ProcessSegmentedObjects::Response &res)
845 {
846  res.segmented_objects.header = req.segmented_objects.header;
847  res.segmented_objects.cleared = req.segmented_objects.cleared;
848  res.segmented_objects.objects.resize(req.segmented_objects.objects.size());
849 
850  for (size_t i = 0; i < res.segmented_objects.objects.size(); i ++)
851  {
852  // convert to a SegmentedObject message
853  res.segmented_objects.objects[i].recognized = req.segmented_objects.objects[i].recognized;
854 
855  // can't recalculate this after initial segmentation has already happened...
856  res.segmented_objects.objects[i].image = req.segmented_objects.objects[i].image;
857 
858  // can't recalculate this without the initial image...
859  res.segmented_objects.objects[i].image_indices = req.segmented_objects.objects[i].image_indices;
860 
861  // set the point cloud
862  res.segmented_objects.objects[i].point_cloud = req.segmented_objects.objects[i].point_cloud;
863 
864  // get point cloud as pcl point cloud
865  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcl_cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
866  pcl::PCLPointCloud2::Ptr temp_cloud(new pcl::PCLPointCloud2);
867  pcl_conversions::toPCL(res.segmented_objects.objects[i].point_cloud, *temp_cloud);
868  pcl::fromPCLPointCloud2(*temp_cloud, *pcl_cloud);
869 
870  // create a marker and set the extra fields
871  res.segmented_objects.objects[i].marker = this->createMarker(temp_cloud);
872  res.segmented_objects.objects[i].marker.id = i;
873 
874  // calculate color features
875  Eigen::Vector3f rgb, lab;
876  rgb[0] = res.segmented_objects.objects[i].marker.color.r;
877  rgb[1] = res.segmented_objects.objects[i].marker.color.g;
878  rgb[2] = res.segmented_objects.objects[i].marker.color.b;
879  lab = RGB2Lab(rgb);
880  res.segmented_objects.objects[i].rgb.resize(3);
881  res.segmented_objects.objects[i].cielab.resize(3);
882  res.segmented_objects.objects[i].rgb[0] = rgb[0];
883  res.segmented_objects.objects[i].rgb[1] = rgb[1];
884  res.segmented_objects.objects[i].rgb[2] = rgb[2];
885  res.segmented_objects.objects[i].cielab[0] = lab[0];
886  res.segmented_objects.objects[i].cielab[1] = lab[1];
887  res.segmented_objects.objects[i].cielab[2] = lab[2];
888 
889  // set the centroid
890  Eigen::Vector4f centroid;
891  pcl::compute3DCentroid(*pcl_cloud, centroid);
892  res.segmented_objects.objects[i].centroid.x = centroid[0];
893  res.segmented_objects.objects[i].centroid.y = centroid[1];
894  res.segmented_objects.objects[i].centroid.z = centroid[2];
895 
896  // calculate the minimum volume bounding box (assuming the object is resting on a flat surface)
897  res.segmented_objects.objects[i].bounding_volume =
898  BoundingVolumeCalculator::computeBoundingVolume(res.segmented_objects.objects[i].point_cloud);
899 
900  // calculate the axis-aligned bounding box
901  Eigen::Vector4f min_pt, max_pt;
902  pcl::getMinMax3D(*pcl_cloud, min_pt, max_pt);
903  res.segmented_objects.objects[i].width = max_pt[0] - min_pt[0];
904  res.segmented_objects.objects[i].depth = max_pt[1] - min_pt[1];
905  res.segmented_objects.objects[i].height = max_pt[2] - min_pt[2];
906 
907  // calculate the center
908  res.segmented_objects.objects[i].center.x = (max_pt[0] + min_pt[0]) / 2.0;
909  res.segmented_objects.objects[i].center.y = (max_pt[1] + min_pt[1]) / 2.0;
910  res.segmented_objects.objects[i].center.z = (max_pt[2] + min_pt[2]) / 2.0;
911 
912  // calculate the orientation
913  pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
914  // project point cloud onto the xy plane
915  pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
916  coefficients->values.resize(4);
917  coefficients->values[0] = 0;
918  coefficients->values[1] = 0;
919  coefficients->values[2] = 1.0;
920  coefficients->values[3] = 0;
921  pcl::ProjectInliers<pcl::PointXYZRGB> proj;
922  proj.setModelType(pcl::SACMODEL_PLANE);
923  proj.setInputCloud(pcl_cloud);
924  proj.setModelCoefficients(coefficients);
925  proj.filter(*projected_cluster);
926 
927  //calculate the Eigen vectors of the projected point cloud's covariance matrix, used to determine orientation
928  Eigen::Vector4f projected_centroid;
929  Eigen::Matrix3f covariance_matrix;
930  pcl::compute3DCentroid(*projected_cluster, projected_centroid);
931  pcl::computeCovarianceMatrixNormalized(*projected_cluster, projected_centroid, covariance_matrix);
932  Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance_matrix, Eigen::ComputeEigenvectors);
933  Eigen::Matrix3f eigen_vectors = eigen_solver.eigenvectors();
934  eigen_vectors.col(2) = eigen_vectors.col(0).cross(eigen_vectors.col(1));
935  //calculate rotation from eigenvectors
936  const Eigen::Quaternionf qfinal(eigen_vectors);
937 
938  //convert orientation to a single angle on the 2D plane defined by the segmentation coordinate frame
939  tf::Quaternion tf_quat;
940  tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
941  double r, p, y;
942  tf::Matrix3x3 m(tf_quat);
943  m.getRPY(r, p, y);
944  double angle = r + y;
945  while (angle < -M_PI)
946  {
947  angle += 2 * M_PI;
948  }
949  while (angle > M_PI)
950  {
951  angle -= 2 * M_PI;
952  }
953  res.segmented_objects.objects[i].orientation = tf::createQuaternionMsgFromYaw(angle);
954  }
955 
956  return true;
957 }
958 
959 bool Segmenter::findSurface(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
960  const pcl::IndicesConstPtr &indices_in, const SegmentationZone &zone, const pcl::IndicesPtr &indices_out,
961  rail_manipulation_msgs::SegmentedObject &table_out) const
962 {
963  // use a plane (SAC) segmenter
964  pcl::SACSegmentation<pcl::PointXYZRGB> plane_seg;
965  // set the segmenation parameters
966  plane_seg.setOptimizeCoefficients(true);
967  plane_seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
968  plane_seg.setAxis(Eigen::Vector3f(0, 0, 1));
969  plane_seg.setEpsAngle(SAC_EPS_ANGLE);
970  plane_seg.setMethodType(pcl::SAC_RANSAC);
971  plane_seg.setMaxIterations(SAC_MAX_ITERATIONS);
972  plane_seg.setDistanceThreshold(SAC_DISTANCE_THRESHOLD);
973 
974  // create a copy to work with
975  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc_copy(new pcl::PointCloud<pcl::PointXYZRGB>(*in));
976  plane_seg.setInputCloud(pc_copy);
977  plane_seg.setIndices(indices_in);
978 
979  // Check point height -- if the plane is too low or high, extract another
980  while (true)
981  {
982  // points included in the plane (surface)
983  pcl::PointIndices::Ptr inliers_ptr(new pcl::PointIndices);
984 
985  // segment the the current cloud
986  pcl::ModelCoefficients coefficients;
987  plane_seg.segment(*inliers_ptr, coefficients);
988 
989  // check if we found a surface
990  if (inliers_ptr->indices.size() == 0)
991  {
992  ROS_WARN("Could not find a surface above %fm and below %fm.", zone.getZMin(), zone.getZMax());
993  *indices_out = *indices_in;
994  table_out.centroid.z = -numeric_limits<double>::infinity();
995  return false;
996  }
997 
998  // remove the plane
999  pcl::PointCloud<pcl::PointXYZRGB> plane;
1000  pcl::ExtractIndices<pcl::PointXYZRGB> extract(true);
1001  extract.setInputCloud(pc_copy);
1002  extract.setIndices(inliers_ptr);
1003  extract.setNegative(false);
1004  extract.filter(plane);
1005  extract.setKeepOrganized(true);
1006  plane_seg.setIndices(extract.getRemovedIndices());
1007 
1008  // check the height
1009  double height = this->averageZ(plane.points);
1010  if (height >= zone.getZMin() && height <= zone.getZMax())
1011  {
1012  ROS_INFO("Surface found at %fm.", height);
1013  *indices_out = *plane_seg.getIndices();
1014 
1015  // check if we need to transform to a different frame
1016  pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_pc(new pcl::PointCloud<pcl::PointXYZRGB>);
1017  pcl::PCLPointCloud2::Ptr converted(new pcl::PCLPointCloud2);
1018  if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
1019  {
1020  // perform the copy/transform using TF
1021  pcl_ros::transformPointCloud(zone.getSegmentationFrameID(), ros::Time(0), plane, plane.header.frame_id,
1022  *transformed_pc, tf_);
1023  transformed_pc->header.frame_id = zone.getSegmentationFrameID();
1024  transformed_pc->header.seq = plane.header.seq;
1025  transformed_pc->header.stamp = plane.header.stamp;
1026  pcl::toPCLPointCloud2(*transformed_pc, *converted);
1027  } else
1028  {
1029  pcl::toPCLPointCloud2(plane, *converted);
1030  }
1031 
1032  // convert to a SegmentedObject message
1033  table_out.recognized = false;
1034 
1035  // set the RGB image
1036  table_out.image = this->createImage(pc_copy, *inliers_ptr);
1037 
1038  // check if we want to publish the image
1039  if (debug_)
1040  {
1041  debug_img_pub_.publish(table_out.image);
1042  }
1043 
1044  // set the point cloud
1045  pcl_conversions::fromPCL(*converted, table_out.point_cloud);
1046  table_out.point_cloud.header.stamp = ros::Time::now();
1047  // create a marker and set the extra fields
1048  table_out.marker = this->createMarker(converted);
1049  table_out.marker.id = 0;
1050 
1051  // set the centroid
1052  Eigen::Vector4f centroid;
1053  if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
1054  {
1055  pcl::compute3DCentroid(*transformed_pc, centroid);
1056  } else
1057  {
1058  pcl::compute3DCentroid(plane, centroid);
1059  }
1060  table_out.centroid.x = centroid[0];
1061  table_out.centroid.y = centroid[1];
1062  table_out.centroid.z = centroid[2];
1063 
1064  // calculate the bounding box
1065  Eigen::Vector4f min_pt, max_pt;
1066  pcl::getMinMax3D(plane, min_pt, max_pt);
1067  table_out.width = max_pt[0] - min_pt[0];
1068  table_out.depth = max_pt[1] - min_pt[1];
1069  table_out.height = max_pt[2] - min_pt[2];
1070 
1071  // calculate the center
1072  table_out.center.x = (max_pt[0] + min_pt[0]) / 2.0;
1073  table_out.center.y = (max_pt[1] + min_pt[1]) / 2.0;
1074  table_out.center.z = (max_pt[2] + min_pt[2]) / 2.0;
1075 
1076 
1077  // calculate the orientation
1078  pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
1079  // project point cloud onto the xy plane
1080  pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
1081  coefficients->values.resize(4);
1082  coefficients->values[0] = 0;
1083  coefficients->values[1] = 0;
1084  coefficients->values[2] = 1.0;
1085  coefficients->values[3] = 0;
1086  pcl::ProjectInliers<pcl::PointXYZRGB> proj;
1087  proj.setModelType(pcl::SACMODEL_PLANE);
1088  if (zone.getBoundingFrameID() != zone.getSegmentationFrameID())
1089  {
1090  proj.setInputCloud(transformed_pc);
1091  } else
1092  {
1093  pcl::PointCloud<pcl::PointXYZRGB>::Ptr plane_ptr(new pcl::PointCloud<pcl::PointXYZRGB>(plane));
1094  proj.setInputCloud(plane_ptr);
1095  }
1096  proj.setModelCoefficients(coefficients);
1097  proj.filter(*projected_cluster);
1098 
1099  //calculate the Eigen vectors of the projected point cloud's covariance matrix, used to determine orientation
1100  Eigen::Vector4f projected_centroid;
1101  Eigen::Matrix3f covariance_matrix;
1102  pcl::compute3DCentroid(*projected_cluster, projected_centroid);
1103  pcl::computeCovarianceMatrixNormalized(*projected_cluster, projected_centroid, covariance_matrix);
1104  Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance_matrix, Eigen::ComputeEigenvectors);
1105  Eigen::Matrix3f eigen_vectors = eigen_solver.eigenvectors();
1106  eigen_vectors.col(2) = eigen_vectors.col(0).cross(eigen_vectors.col(1));
1107  //calculate rotation from eigenvectors
1108  const Eigen::Quaternionf qfinal(eigen_vectors);
1109 
1110  //convert orientation to a single angle on the 2D plane defined by the segmentation coordinate frame
1111  tf::Quaternion tf_quat;
1112  tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
1113  double r, p, y;
1114  tf::Matrix3x3 m(tf_quat);
1115  m.getRPY(r, p, y);
1116  double angle = r + y;
1117  while (angle < -M_PI)
1118  {
1119  angle += 2 * M_PI;
1120  }
1121  while (angle > M_PI)
1122  {
1123  angle -= 2 * M_PI;
1124  }
1125  table_out.orientation = tf::createQuaternionMsgFromYaw(angle);
1126 
1127  return true;
1128  }
1129  }
1130 }
1131 
1132 void Segmenter::extractClustersEuclidean(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
1133  const pcl::IndicesConstPtr &indices_in, vector<pcl::PointIndices> &clusters) const
1134 {
1135  // ignore NaN and infinite values
1136  pcl::IndicesPtr valid(new vector<int>);
1137  for (size_t i = 0; i < indices_in->size(); i++)
1138  {
1139  if (pcl_isfinite(in->points[indices_in->at(i)].x) & pcl_isfinite(in->points[indices_in->at(i)].y) &
1140  pcl_isfinite(in->points[indices_in->at(i)].z))
1141  {
1142  valid->push_back(indices_in->at(i));
1143  }
1144  }
1145 
1146  pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> seg;
1147  pcl::search::KdTree<pcl::PointXYZRGB>::Ptr kd_tree(new pcl::search::KdTree<pcl::PointXYZRGB>);
1148  kd_tree->setInputCloud(in);
1149  seg.setClusterTolerance(cluster_tolerance_);
1150  seg.setMinClusterSize(min_cluster_size_);
1151  seg.setMaxClusterSize(max_cluster_size_);
1152  seg.setSearchMethod(kd_tree);
1153  seg.setInputCloud(in);
1154  seg.setIndices(valid);
1155  seg.extract(clusters);
1156 }
1157 
1158 void Segmenter::extractClustersRGB(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
1159  const pcl::IndicesConstPtr &indices_in, vector<pcl::PointIndices> &clusters) const
1160 {
1161  // ignore NaN and infinite values
1162  pcl::IndicesPtr valid(new vector<int>);
1163  for (size_t i = 0; i < indices_in->size(); i++)
1164  {
1165  if (pcl_isfinite(in->points[indices_in->at(i)].x) & pcl_isfinite(in->points[indices_in->at(i)].y) &
1166  pcl_isfinite(in->points[indices_in->at(i)].z))
1167  {
1168  valid->push_back(indices_in->at(i));
1169  }
1170  }
1171  pcl::RegionGrowingRGB<pcl::PointXYZRGB> seg;
1172  pcl::search::KdTree<pcl::PointXYZRGB>::Ptr kd_tree(new pcl::search::KdTree<pcl::PointXYZRGB>);
1173  kd_tree->setInputCloud(in);
1174  seg.setPointColorThreshold(POINT_COLOR_THRESHOLD);
1175  seg.setRegionColorThreshold(REGION_COLOR_THRESHOLD);
1176  seg.setDistanceThreshold(cluster_tolerance_);
1177  seg.setMinClusterSize(min_cluster_size_);
1178  seg.setMaxClusterSize(max_cluster_size_);
1179  seg.setSearchMethod(kd_tree);
1180  seg.setInputCloud(in);
1181  seg.setIndices(valid);
1182  seg.extract(clusters);
1183 }
1184 
1185 sensor_msgs::Image Segmenter::createImage(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
1186  const pcl::PointIndices &cluster) const
1187 {
1188  // determine the bounds of the cluster
1189  int row_min = numeric_limits<int>::max();
1190  int row_max = numeric_limits<int>::min();
1191  int col_min = numeric_limits<int>::max();
1192  int col_max = numeric_limits<int>::min();
1193 
1194  for (size_t i = 0; i < cluster.indices.size(); i++)
1195  {
1196  // calculate row and column of this point
1197  int row = cluster.indices[i] / in->width;
1198  int col = cluster.indices[i] - (row * in->width);
1199 
1200  if (row < row_min)
1201  {
1202  row_min = row;
1203  } else if (row > row_max)
1204  {
1205  row_max = row;
1206  }
1207  if (col < col_min)
1208  {
1209  col_min = col;
1210  } else if (col > col_max)
1211  {
1212  col_max = col;
1213  }
1214  }
1215 
1216  // create a ROS image
1217  sensor_msgs::Image msg;
1218 
1219  // set basic information
1220  msg.header.frame_id = in->header.frame_id;
1221  msg.header.stamp = ros::Time::now();
1222  msg.width = col_max - col_min;
1223  msg.height = row_max - row_min;
1224  // RGB data
1225  msg.step = 3 * msg.width;
1226  msg.data.resize(msg.step * msg.height);
1227  msg.encoding = sensor_msgs::image_encodings::BGR8;
1228 
1229  // extract the points
1230  for (int h = 0; h < msg.height; h++)
1231  {
1232  for (int w = 0; w < msg.width; w++)
1233  {
1234  // extract RGB information
1235  const pcl::PointXYZRGB &point = in->at(col_min + w, row_min + h);
1236  // set RGB data
1237  int index = (msg.step * h) + (w * 3);
1238  msg.data[index] = point.b;
1239  msg.data[index + 1] = point.g;
1240  msg.data[index + 2] = point.r;
1241  }
1242  }
1243 
1244  return msg;
1245 }
1246 
1247 visualization_msgs::Marker Segmenter::createMarker(const pcl::PCLPointCloud2::ConstPtr &pc) const
1248 {
1249  visualization_msgs::Marker marker;
1250  // set header field
1251  marker.header.frame_id = pc->header.frame_id;
1252 
1253  // default position
1254  marker.pose.position.x = 0.0;
1255  marker.pose.position.y = 0.0;
1256  marker.pose.position.z = 0.0;
1257  marker.pose.orientation.x = 0.0;
1258  marker.pose.orientation.y = 0.0;
1259  marker.pose.orientation.z = 0.0;
1260  marker.pose.orientation.w = 1.0;
1261 
1262  // default scale
1263  marker.scale.x = MARKER_SCALE;
1264  marker.scale.y = MARKER_SCALE;
1265  marker.scale.z = MARKER_SCALE;
1266 
1267  // set the type of marker and our color of choice
1268  marker.type = visualization_msgs::Marker::CUBE_LIST;
1269  marker.color.a = 1.0;
1270 
1271  // downsample point cloud for visualization
1272  pcl::PCLPointCloud2 downsampled;
1273  pcl::VoxelGrid<pcl::PCLPointCloud2> voxel_grid;
1274  voxel_grid.setInputCloud(pc);
1276  voxel_grid.filter(downsampled);
1277 
1278  // convert to an easy to use point cloud message
1279  sensor_msgs::PointCloud2 pc2_msg;
1280  pcl_conversions::fromPCL(downsampled, pc2_msg);
1281  sensor_msgs::PointCloud pc_msg;
1283 
1284  // place in the marker message
1285  marker.points.resize(pc_msg.points.size());
1286  int r = 0, g = 0, b = 0;
1287  for (size_t j = 0; j < pc_msg.points.size(); j++)
1288  {
1289  marker.points[j].x = pc_msg.points[j].x;
1290  marker.points[j].y = pc_msg.points[j].y;
1291  marker.points[j].z = pc_msg.points[j].z;
1292 
1293  // use average RGB
1294  uint32_t rgb = *reinterpret_cast<int *>(&pc_msg.channels[0].values[j]);
1295  r += (int) ((rgb >> 16) & 0x0000ff);
1296  g += (int) ((rgb >> 8) & 0x0000ff);
1297  b += (int) ((rgb) & 0x0000ff);
1298  }
1299 
1300  // set average RGB
1301  marker.color.r = ((float) r / (float) pc_msg.points.size()) / 255.0;
1302  marker.color.g = ((float) g / (float) pc_msg.points.size()) / 255.0;
1303  marker.color.b = ((float) b / (float) pc_msg.points.size()) / 255.0;
1304  marker.color.a = 1.0;
1305 
1306  return marker;
1307 }
1308 
1309 void Segmenter::extract(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in, const pcl::IndicesConstPtr &indices_in,
1310  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &out) const
1311 {
1312  pcl::ExtractIndices<pcl::PointXYZRGB> extract;
1313  extract.setInputCloud(in);
1314  extract.setIndices(indices_in);
1315  extract.filter(*out);
1316 }
1317 
1318 void Segmenter::inverseBound(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
1319  const pcl::IndicesConstPtr &indices_in,
1320  const pcl::ConditionBase<pcl::PointXYZRGB>::Ptr &conditions,
1321  const pcl::IndicesPtr &indices_out) const
1322 {
1323  // use a temp point cloud to extract the indices
1324  pcl::PointCloud<pcl::PointXYZRGB> tmp;
1325  //pcl::ConditionalRemoval<pcl::PointXYZRGB> removal(conditions, true);
1326  pcl::ConditionalRemoval<pcl::PointXYZRGB> removal(true);
1327  removal.setCondition(conditions);
1328  removal.setInputCloud(in);
1329  removal.setIndices(indices_in);
1330  removal.filter(tmp);
1331  *indices_out = *removal.getRemovedIndices();
1332 }
1333 
1334 double Segmenter::averageZ(const vector<pcl::PointXYZRGB, Eigen::aligned_allocator<pcl::PointXYZRGB> > &v) const
1335 {
1336  double avg = 0.0;
1337  for (size_t i = 0; i < v.size(); i++)
1338  {
1339  avg += v[i].z;
1340  }
1341  return (avg / (double) v.size());
1342 }
1343 
1344 //convert from RGB color space to CIELAB color space, adapted from pcl/registration/gicp6d
1345 Eigen::Vector3f RGB2Lab (const Eigen::Vector3f& colorRGB)
1346 {
1347  // for sRGB -> CIEXYZ see http://www.easyrgb.com/index.php?X=MATH&H=02#text2
1348  // for CIEXYZ -> CIELAB see http://www.easyrgb.com/index.php?X=MATH&H=07#text7
1349 
1350  double R, G, B, X, Y, Z;
1351 
1352  R = colorRGB[0];
1353  G = colorRGB[1];
1354  B = colorRGB[2];
1355 
1356  // linearize sRGB values
1357  if (R > 0.04045)
1358  R = pow ( (R + 0.055) / 1.055, 2.4);
1359  else
1360  R = R / 12.92;
1361 
1362  if (G > 0.04045)
1363  G = pow ( (G + 0.055) / 1.055, 2.4);
1364  else
1365  G = G / 12.92;
1366 
1367  if (B > 0.04045)
1368  B = pow ( (B + 0.055) / 1.055, 2.4);
1369  else
1370  B = B / 12.92;
1371 
1372  // postponed:
1373  // R *= 100.0;
1374  // G *= 100.0;
1375  // B *= 100.0;
1376 
1377  // linear sRGB -> CIEXYZ
1378  X = R * 0.4124 + G * 0.3576 + B * 0.1805;
1379  Y = R * 0.2126 + G * 0.7152 + B * 0.0722;
1380  Z = R * 0.0193 + G * 0.1192 + B * 0.9505;
1381 
1382  // *= 100.0 including:
1383  X /= 0.95047; //95.047;
1384  // Y /= 1;//100.000;
1385  Z /= 1.08883; //108.883;
1386 
1387  // CIEXYZ -> CIELAB
1388  if (X > 0.008856)
1389  X = pow (X, 1.0 / 3.0);
1390  else
1391  X = 7.787 * X + 16.0 / 116.0;
1392 
1393  if (Y > 0.008856)
1394  Y = pow (Y, 1.0 / 3.0);
1395  else
1396  Y = 7.787 * Y + 16.0 / 116.0;
1397 
1398  if (Z > 0.008856)
1399  Z = pow (Z, 1.0 / 3.0);
1400  else
1401  Z = 7.787 * Z + 16.0 / 116.0;
1402 
1403  Eigen::Vector3f colorLab;
1404  colorLab[0] = static_cast<float> (116.0 * Y - 16.0);
1405  colorLab[1] = static_cast<float> (500.0 * (X - Y));
1406  colorLab[2] = static_cast<float> (200.0 * (Y - Z));
1407 
1408  return colorLab;
1409 }
bool getRequireSurface() const
Remove surface value accessor.
static rail_manipulation_msgs::BoundingVolume computeBoundingVolume(sensor_msgs::PointCloud2 cloud)
Fit a z-axis-aligned bounding box to x-y plane principal direction of point cloud.
bool segmentObjectsCallback(rail_manipulation_msgs::SegmentObjects::Request &req, rail_manipulation_msgs::SegmentObjects::Response &res)
Callback for the main segmentation request.
Definition: Segmenter.cpp:410
static const double POINT_COLOR_THRESHOLD
Definition: Segmenter.h:124
ros::ServiceServer remove_object_srv_
Definition: Segmenter.h:362
double getYMax() const
Y max value accessor.
void setYawMin(const double yaw_min)
Yaw min value mutator.
bool getRemoveSurface() const
Remove surface value accessor.
double getZMin() const
Z min value accessor.
void setZMin(const double z_min)
Z min value mutator.
double getYMin() const
Y min value accessor.
bool executeSegmentation(pcl::PointCloud< pcl::PointXYZRGB >::Ptr pc, rail_manipulation_msgs::SegmentedObjectList &objects)
Main segmentation routine.
Definition: Segmenter.cpp:453
void inverseBound(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &in, const pcl::IndicesConstPtr &indices_in, const pcl::ConditionBase< pcl::PointXYZRGB >::Ptr &conditions, const pcl::IndicesPtr &indices_out) const
Bound a point cloud based on the inverse of a set of conditions.
Definition: Segmenter.cpp:1318
visualization_msgs::Marker table_marker_
Definition: Segmenter.h:385
const std::string & getBoundingFrameID() const
Segmentation frame ID value accessor.
rail_manipulation_msgs::SegmentedObjectList object_list_
Definition: Segmenter.h:377
void extractClustersEuclidean(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &in, const pcl::IndicesConstPtr &indices_in, std::vector< pcl::PointIndices > &clusters) const
Find clusters in a point cloud.
Definition: Segmenter.cpp:1132
void setYawMax(const double yaw_max)
Yaw max value mutator.
ros::Publisher debug_img_pub_
Definition: Segmenter.h:364
static const double SAC_EPS_ANGLE
Definition: Segmenter.h:110
visualization_msgs::Marker createMarker(const pcl::PCLPointCloud2::ConstPtr &pc) const
Create a Marker from the given point cloud.
Definition: Segmenter.cpp:1247
ros::ServiceServer segment_objects_srv_
Definition: Segmenter.h:362
bool segmentCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Callback for the main segmentation request.
Definition: Segmenter.cpp:404
static const int DEFAULT_MAX_CLUSTER_SIZE
Definition: Segmenter.h:120
double getXMax() const
X max value accessor.
tf::TransformListener tf_
Definition: Segmenter.h:368
double getXMin() const
X min value accessor.
ros::NodeHandle private_node_
Definition: Segmenter.h:360
void extract(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &in, const pcl::IndicesConstPtr &indices_in, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &out) const
Extract a new point cloud based on the given indices.
Definition: Segmenter.cpp:1309
void setPitchMin(const double pitch_min)
Pitch min value mutator.
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
static bool convertPointCloud2ToPointCloud(const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output)
bool clearCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Callback for the clear request.
Definition: Segmenter.cpp:355
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
static const float DOWNSAMPLE_LEAF_SIZE
Definition: Segmenter.h:128
bool okay() const
A check for a valid Segmenter.
Definition: Segmenter.cpp:274
#define ROS_WARN(...)
static const bool DEFAULT_DEBUG
Definition: Segmenter.h:108
void setPitchMax(const double pitch_max)
Pitch max value mutator.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
bool segmentObjects(rail_manipulation_msgs::SegmentedObjectList &objects)
Callback for the main segmentation request.
Definition: Segmenter.cpp:427
visualization_msgs::MarkerArray markers_
Definition: Segmenter.h:381
const std::string & getName() const
Name value accessor.
void setRollMin(const double roll_min)
Roll min value mutator.
void setYMin(const double y_min)
Y min value mutator.
static const double SURFACE_REMOVAL_PADDING
Definition: Segmenter.h:116
bool param(const std::string &param_name, T &param_val, const T &default_val) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
void publish(const boost::shared_ptr< M > &message) const
const SegmentationZone & getCurrentZone() const
Determine the current zone based on the latest state of the TF tree.
Definition: Segmenter.cpp:279
std::vector< SegmentationZone > zones_
Definition: Segmenter.h:351
double averageZ(const std::vector< pcl::PointXYZRGB, Eigen::aligned_allocator< pcl::PointXYZRGB > > &v) const
Find the average Z value of the point vector.
Definition: Segmenter.cpp:1334
void setRequireSurface(const bool require_surface)
Require surface value mutator.
bool removeObjectCallback(rail_segmentation::RemoveObject::Request &req, rail_segmentation::RemoveObject::Response &res)
Callback for the remove object request.
Definition: Segmenter.cpp:306
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
void setXMax(const double x_max)
X max value mutator.
static const int SAC_MAX_ITERATIONS
Definition: Segmenter.h:114
ros::Publisher markers_pub_
Definition: Segmenter.h:364
void setZMax(const double z_max)
Z max value mutator.
ros::Publisher segmented_objects_pub_
Definition: Segmenter.h:364
static const int DEFAULT_MIN_CLUSTER_SIZE
Definition: Segmenter.h:118
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
visualization_msgs::MarkerArray text_markers_
Definition: Segmenter.h:383
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool calculateFeaturesCallback(rail_manipulation_msgs::ProcessSegmentedObjects::Request &req, rail_manipulation_msgs::ProcessSegmentedObjects::Response &res)
Definition: Segmenter.cpp:843
ros::ServiceServer calculate_features_srv_
Definition: Segmenter.h:362
static const double REGION_COLOR_THRESHOLD
Definition: Segmenter.h:126
ROSLIB_DECL std::string getPath(const std::string &package_name)
static const double MARKER_SCALE
Definition: Segmenter.h:130
bool segmentObjectsFromPointCloudCallback(rail_manipulation_msgs::SegmentObjectsFromPointCloud::Request &req, rail_manipulation_msgs::SegmentObjectsFromPointCloud::Response &res)
Callback for the main segmentation request.
Definition: Segmenter.cpp:416
The main segmentation node object.
ros::ServiceServer segment_objects_from_point_cloud_srv_
Definition: Segmenter.h:362
double getZMax() const
Z max value accessor.
static const double CLUSTER_TOLERANCE
Definition: Segmenter.h:122
ros::Publisher table_marker_pub_
Definition: Segmenter.h:364
static const double SAC_DISTANCE_THRESHOLD
Definition: Segmenter.h:112
void extractClustersRGB(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &in, const pcl::IndicesConstPtr &indices_in, std::vector< pcl::PointIndices > &clusters) const
Find clusters in a point cloud.
Definition: Segmenter.cpp:1158
void getRPY(tf2Scalar &roll, tf2Scalar &pitch, tf2Scalar &yaw, unsigned int solution_number=1) const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
sensor_msgs::Image createImage(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &in, const pcl::PointIndices &cluster) const
Create a cropped image of the segmented object.
Definition: Segmenter.cpp:1185
ros::Publisher debug_pc_pub_
Definition: Segmenter.h:364
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
rail_manipulation_msgs::SegmentedObject table_
Definition: Segmenter.h:379
void setXMin(const double x_min)
X min value mutator.
static Time now()
bool findSurface(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &in, const pcl::IndicesConstPtr &indices_in, const SegmentationZone &zone, const pcl::IndicesPtr &indices_out, rail_manipulation_msgs::SegmentedObject &table_out) const
Find and remove a surface from the given point cloud.
Definition: Segmenter.cpp:959
Eigen::Vector3f RGB2Lab(const Eigen::Vector3f &colorRGB)
Definition: Segmenter.cpp:1345
void setRollMax(const double roll_max)
Roll max value mutator.
ros::ServiceServer segment_srv_
Definition: Segmenter.h:362
void setYMax(const double y_max)
Y max value mutator.
The criteria for a segmentation zone.
void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
ros::ServiceServer clear_srv_
Definition: Segmenter.h:362
#define ROS_ERROR(...)
const std::string & getSegmentationFrameID() const
Segmentation frame ID value accessor.
void setRemoveSurface(const bool remove_surface)
Remove surface value mutator.
tf2_ros::Buffer tf_buffer_
Definition: Segmenter.h:370


rail_segmentation
Author(s): Russell Toris , David Kent
autogenerated on Mon Feb 28 2022 23:23:51