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;
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;
32 Segmenter::Segmenter() : private_node_(
"~"), tf2_(tf_buffer_)
37 string point_cloud_topic(
"/head_camera/depth_registered/points");
60 "segmented_objects", 1, true
63 "segmented_table", 1, true
75 #ifdef YAMLCPP_GT_0_5_0 77 YAML::Node zones_config = YAML::LoadFile(zones_file);
78 for (
size_t i = 0; i < zones_config.size(); i++)
80 YAML::Node cur = zones_config[i];
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>());
87 if (cur[
"remove_surface"].IsDefined())
93 if (cur[
"require_surface"].IsDefined())
99 if (cur[
"roll_min"].IsDefined())
101 zone.
setRollMin(cur[
"roll_min"].as<double>());
103 if (cur[
"roll_max"].IsDefined())
105 zone.
setRollMax(cur[
"roll_max"].as<double>());
107 if (cur[
"pitch_min"].IsDefined())
111 if (cur[
"pitch_max"].IsDefined())
115 if (cur[
"yaw_min"].IsDefined())
117 zone.
setYawMin(cur[
"yaw_min"].as<double>());
119 if (cur[
"yaw_max"].IsDefined())
121 zone.
setYawMax(cur[
"yaw_max"].as<double>());
123 if (cur[
"x_min"].IsDefined())
125 zone.
setXMin(cur[
"x_min"].as<double>());
127 if (cur[
"x_max"].IsDefined())
129 zone.
setXMax(cur[
"x_max"].as<double>());
131 if (cur[
"y_min"].IsDefined())
133 zone.
setYMin(cur[
"y_min"].as<double>());
135 if (cur[
"y_max"].IsDefined())
137 zone.
setYMax(cur[
"y_max"].as<double>());
139 if (cur[
"z_min"].IsDefined())
141 zone.
setZMin(cur[
"z_min"].as<double>());
143 if (cur[
"z_max"].IsDefined())
145 zone.
setZMax(cur[
"z_max"].as<double>());
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++)
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;
167 SegmentationZone zone(name, parent_frame_id, child_frame_id, bounding_frame_id, segmentation_frame_id);
170 if (zones_config[i].FindValue(
"remove_surface") != NULL)
173 zones_config[i][
"remove_surface"] >> remove_surface;
176 if (zones_config[i].FindValue(
"require_surface") != NULL)
178 bool require_surface;
179 zones_config[i][
"require_surface"] >> require_surface;
184 if (zones_config[i].FindValue(
"roll_min") != NULL)
187 zones_config[i][
"roll_min"] >> roll_min;
190 if (zones_config[i].FindValue(
"roll_max") != NULL)
193 zones_config[i][
"roll_max"] >> roll_max;
196 if (zones_config[i].FindValue(
"pitch_min") != NULL)
199 zones_config[i][
"pitch_min"] >> pitch_min;
202 if (zones_config[i].FindValue(
"pitch_max") != NULL)
205 zones_config[i][
"pitch_max"] >> pitch_max;
208 if (zones_config[i].FindValue(
"yaw_min") != NULL)
211 zones_config[i][
"yaw_min"] >> yaw_min;
214 if (zones_config[i].FindValue(
"yaw_max") != NULL)
217 zones_config[i][
"yaw_max"] >> yaw_max;
220 if (zones_config[i].FindValue(
"x_min") != NULL)
223 zones_config[i][
"x_min"] >> x_min;
226 if (zones_config[i].FindValue(
"x_max") != NULL)
229 zones_config[i][
"x_max"] >> x_max;
232 if (zones_config[i].FindValue(
"y_min") != NULL)
235 zones_config[i][
"y_min"] >> y_min;
238 if (zones_config[i].FindValue(
"y_max") != NULL)
241 zones_config[i][
"y_max"] >> y_max;
244 if (zones_config[i].FindValue(
"z_min") != NULL)
247 zones_config[i][
"z_min"] >> z_min;
250 if (zones_config[i].FindValue(
"z_max") != NULL)
253 zones_config[i][
"z_max"] >> z_max;
265 ROS_INFO(
"Segmenter Successfully Initialized");
269 ROS_ERROR(
"No valid segmenation zones defined. Check %s.", zones_file.c_str());
282 for (
size_t i = 0; i <
zones_.size(); i++)
290 tf.transform.rotation.w));
291 double roll, pitch, yaw;
292 mat.
getRPY(roll, pitch, yaw);
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())
302 ROS_WARN(
"Current state not in a valid segmentation zone. Defaulting to first zone.");
307 rail_segmentation::RemoveObject::Response &res)
323 markers_.markers[req.index].action = visualization_msgs::Marker::DELETE;
326 text_markers_.markers[req.index].action = visualization_msgs::Marker::DELETE;
331 visualization_msgs::MarkerArray marker_list;
333 marker_list.markers.insert(marker_list.markers.end(),
markers_.markers.begin(),
markers_.markers.end());
350 ROS_ERROR(
"Attempted to remove index %d from list of size %ld.", req.index,
object_list_.objects.size());
368 for (
size_t i = 0; i <
markers_.markers.size(); i++)
370 markers_.markers[i].action = visualization_msgs::Marker::DELETE;
376 text_markers_.markers[i].action = visualization_msgs::Marker::DELETE;
382 visualization_msgs::MarkerArray marker_list;
384 marker_list.markers.insert(marker_list.markers.end(),
markers_.markers.begin(),
markers_.markers.end());
406 rail_manipulation_msgs::SegmentedObjectList objects;
411 rail_manipulation_msgs::SegmentObjects::Response &res)
417 rail_manipulation_msgs::SegmentObjectsFromPointCloud::Response &res)
420 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc(
new pcl::PointCloud<pcl::PointXYZRGB>);
430 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc(
new pcl::PointCloud<pcl::PointXYZRGB>);
433 while (point_cloud_time < request_time)
435 pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr pc_msg =
437 ros::Duration(10.0));
440 ROS_INFO(
"No point cloud received for segmentation.");
454 rail_manipulation_msgs::SegmentedObjectList &objects)
457 std_srvs::Empty empty;
465 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_pc(
new pcl::PointCloud<pcl::PointXYZRGB>);
467 *transformed_pc,
tf_);
469 transformed_pc->header.seq = pc->header.seq;
470 transformed_pc->header.stamp = pc->header.stamp;
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++)
477 filter_indices->at(i) = i;
486 bool surface_found = this->
findSurface(transformed_pc, filter_indices, zone, filter_indices,
table_);
489 objects.objects.clear();
490 ROS_INFO(
"Could not find a surface within the segmentation zone. Exiting segmentation with no objects found.");
493 double z_surface =
table_.centroid.z;
500 pcl::ConditionOr<pcl::PointXYZRGB>::Ptr bounds(
new pcl::ConditionOr<pcl::PointXYZRGB>);
501 if (z_min > -numeric_limits<double>::infinity())
503 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
504 new pcl::FieldComparison<pcl::PointXYZRGB>(
"z", pcl::ComparisonOps::LE, z_min))
507 if (zone.
getZMax() < numeric_limits<double>::infinity())
509 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
510 new pcl::FieldComparison<pcl::PointXYZRGB>(
"z", pcl::ComparisonOps::GE, zone.
getZMax()))
513 if (zone.
getYMin() > -numeric_limits<double>::infinity())
515 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
516 new pcl::FieldComparison<pcl::PointXYZRGB>(
"y", pcl::ComparisonOps::LE, zone.
getYMin()))
519 if (zone.
getYMax() < numeric_limits<double>::infinity())
521 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
522 new pcl::FieldComparison<pcl::PointXYZRGB>(
"y", pcl::ComparisonOps::GE, zone.
getYMax()))
525 if (zone.
getXMin() > -numeric_limits<double>::infinity())
527 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
528 new pcl::FieldComparison<pcl::PointXYZRGB>(
"x", pcl::ComparisonOps::LE, zone.
getXMin()))
531 if (zone.
getXMax() < numeric_limits<double>::infinity())
533 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
534 new pcl::FieldComparison<pcl::PointXYZRGB>(
"x", pcl::ComparisonOps::GE, zone.
getXMax()))
539 this->
inverseBound(transformed_pc, filter_indices, bounds, filter_indices);
545 bool surface_found = this->
findSurface(transformed_pc, filter_indices, zone, filter_indices,
table_);
548 objects.objects.clear();
549 ROS_INFO(
"Could not find a surface within the segmentation zone. Exiting segmentation with no objects found.");
552 double z_surface =
table_.centroid.z;
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))
564 if (zone.
getZMax() < numeric_limits<double>::infinity())
566 table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
567 new pcl::FieldComparison<pcl::PointXYZRGB>(
"z", pcl::ComparisonOps::GE, zone.
getZMax()))
570 if (zone.
getYMin() > -numeric_limits<double>::infinity())
572 table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
573 new pcl::FieldComparison<pcl::PointXYZRGB>(
"y", pcl::ComparisonOps::LE, zone.
getYMin()))
576 if (zone.
getYMax() < numeric_limits<double>::infinity())
578 table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
579 new pcl::FieldComparison<pcl::PointXYZRGB>(
"y", pcl::ComparisonOps::GE, zone.
getYMax()))
582 if (zone.
getXMin() > -numeric_limits<double>::infinity())
584 table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
585 new pcl::FieldComparison<pcl::PointXYZRGB>(
"x", pcl::ComparisonOps::LE, zone.
getXMin()))
588 if (zone.
getXMax() < numeric_limits<double>::infinity())
590 table_bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
591 new pcl::FieldComparison<pcl::PointXYZRGB>(
"x", pcl::ComparisonOps::GE, zone.
getXMax()))
596 this->
inverseBound(transformed_pc, filter_indices, table_bounds, filter_indices);
603 pcl::PointCloud<pcl::PointXYZRGB>::Ptr debug_pc(
new pcl::PointCloud<pcl::PointXYZRGB>);
604 this->
extract(transformed_pc, filter_indices, debug_pc);
609 vector<pcl::PointIndices> clusters;
615 if (clusters.size() > 0)
620 for (
size_t i = 0; i < clusters.size(); i++)
623 vector<int> cluster_indices;
625 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cluster(
new pcl::PointCloud<pcl::PointXYZRGB>);
626 for (
size_t j = 0; j < clusters[i].indices.size(); j++)
628 cluster->points.push_back(transformed_pc->points[clusters[i].indices[j]]);
629 cluster_indices.push_back(clusters[i].indices[j]);
631 cluster->width = cluster->points.size();
633 cluster->is_dense =
true;
634 cluster->header.frame_id = transformed_pc->header.frame_id;
637 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_cluster(
new pcl::PointCloud<pcl::PointXYZRGB>);
638 pcl::PCLPointCloud2::Ptr converted(
new pcl::PCLPointCloud2);
643 *transformed_cluster,
tf_);
645 transformed_cluster->header.seq = cluster->header.seq;
646 transformed_cluster->header.stamp = cluster->header.stamp;
647 pcl::toPCLPointCloud2(*transformed_cluster, *converted);
650 pcl::toPCLPointCloud2(*cluster, *converted);
654 rail_manipulation_msgs::SegmentedObject segmented_object;
655 segmented_object.recognized =
false;
657 segmented_object.image_indices = cluster_indices;
660 segmented_object.image = this->
createImage(transformed_pc, clusters[i]);
672 segmented_object.marker = this->
createMarker(converted);
673 segmented_object.marker.id = i;
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;
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];
691 Eigen::Vector4f centroid;
694 pcl::compute3DCentroid(*transformed_cluster, centroid);
697 pcl::compute3DCentroid(*cluster, centroid);
699 segmented_object.centroid.x = centroid[0];
700 segmented_object.centroid.y = centroid[1];
701 segmented_object.centroid.z = centroid[2];
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];
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;
719 pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(
new pcl::PointCloud<pcl::PointXYZRGB>);
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);
731 proj.setInputCloud(transformed_cluster);
734 proj.setInputCloud(cluster);
736 proj.setModelCoefficients(coefficients);
737 proj.filter(*projected_cluster);
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));
748 const Eigen::Quaternionf qfinal(eigen_vectors);
752 tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
756 double angle = r + y;
757 while (angle < -M_PI)
768 objects.objects.push_back(segmented_object);
770 markers_.markers.push_back(segmented_object.marker);
775 visualization_msgs::Marker text_marker;
776 text_marker.header = segmented_object.marker.header;
777 text_marker.ns =
"segmentation_labels";
779 text_marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
780 text_marker.action = visualization_msgs::Marker::ADD;
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;
786 text_marker.scale.x = .1;
787 text_marker.scale.y = .1;
788 text_marker.scale.z = .1;
790 text_marker.color.r = 1;
791 text_marker.color.g = 1;
792 text_marker.color.b = 1;
793 text_marker.color.a = 1;
795 stringstream marker_label;
796 marker_label <<
"i:" << i;
797 text_marker.text = marker_label.str();
804 objects.header.seq++;
807 objects.cleared =
false;
816 visualization_msgs::MarkerArray marker_list;
818 marker_list.markers.insert(marker_list.markers.end(),
markers_.markers.begin(),
markers_.markers.end());
837 ROS_WARN(
"No segmented objects found.");
844 rail_manipulation_msgs::ProcessSegmentedObjects::Response &res)
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());
850 for (
size_t i = 0; i < res.segmented_objects.objects.size(); i ++)
853 res.segmented_objects.objects[i].recognized = req.segmented_objects.objects[i].recognized;
856 res.segmented_objects.objects[i].image = req.segmented_objects.objects[i].image;
859 res.segmented_objects.objects[i].image_indices = req.segmented_objects.objects[i].image_indices;
862 res.segmented_objects.objects[i].point_cloud = req.segmented_objects.objects[i].point_cloud;
865 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcl_cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
866 pcl::PCLPointCloud2::Ptr temp_cloud(
new pcl::PCLPointCloud2);
868 pcl::fromPCLPointCloud2(*temp_cloud, *pcl_cloud);
871 res.segmented_objects.objects[i].marker = this->
createMarker(temp_cloud);
872 res.segmented_objects.objects[i].marker.id = i;
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;
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];
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];
897 res.segmented_objects.objects[i].bounding_volume =
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];
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;
913 pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(
new pcl::PointCloud<pcl::PointXYZRGB>);
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);
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));
936 const Eigen::Quaternionf qfinal(eigen_vectors);
940 tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
944 double angle = r + y;
945 while (angle < -M_PI)
960 const pcl::IndicesConstPtr &indices_in,
const SegmentationZone &zone,
const pcl::IndicesPtr &indices_out,
961 rail_manipulation_msgs::SegmentedObject &table_out)
const 964 pcl::SACSegmentation<pcl::PointXYZRGB> plane_seg;
966 plane_seg.setOptimizeCoefficients(
true);
967 plane_seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
968 plane_seg.setAxis(Eigen::Vector3f(0, 0, 1));
970 plane_seg.setMethodType(pcl::SAC_RANSAC);
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);
983 pcl::PointIndices::Ptr inliers_ptr(
new pcl::PointIndices);
986 pcl::ModelCoefficients coefficients;
987 plane_seg.segment(*inliers_ptr, coefficients);
990 if (inliers_ptr->indices.size() == 0)
993 *indices_out = *indices_in;
994 table_out.centroid.z = -numeric_limits<double>::infinity();
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());
1009 double height = this->
averageZ(plane.points);
1012 ROS_INFO(
"Surface found at %fm.", height);
1013 *indices_out = *plane_seg.getIndices();
1016 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_pc(
new pcl::PointCloud<pcl::PointXYZRGB>);
1017 pcl::PCLPointCloud2::Ptr converted(
new pcl::PCLPointCloud2);
1022 *transformed_pc,
tf_);
1024 transformed_pc->header.seq = plane.header.seq;
1025 transformed_pc->header.stamp = plane.header.stamp;
1026 pcl::toPCLPointCloud2(*transformed_pc, *converted);
1029 pcl::toPCLPointCloud2(plane, *converted);
1033 table_out.recognized =
false;
1036 table_out.image = this->
createImage(pc_copy, *inliers_ptr);
1049 table_out.marker.id = 0;
1052 Eigen::Vector4f centroid;
1055 pcl::compute3DCentroid(*transformed_pc, centroid);
1058 pcl::compute3DCentroid(plane, centroid);
1060 table_out.centroid.x = centroid[0];
1061 table_out.centroid.y = centroid[1];
1062 table_out.centroid.z = centroid[2];
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];
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;
1078 pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(
new pcl::PointCloud<pcl::PointXYZRGB>);
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);
1090 proj.setInputCloud(transformed_pc);
1093 pcl::PointCloud<pcl::PointXYZRGB>::Ptr plane_ptr(
new pcl::PointCloud<pcl::PointXYZRGB>(plane));
1094 proj.setInputCloud(plane_ptr);
1096 proj.setModelCoefficients(coefficients);
1097 proj.filter(*projected_cluster);
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));
1108 const Eigen::Quaternionf qfinal(eigen_vectors);
1112 tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
1116 double angle = r + y;
1117 while (angle < -M_PI)
1121 while (angle > M_PI)
1133 const pcl::IndicesConstPtr &indices_in, vector<pcl::PointIndices> &clusters)
const 1136 pcl::IndicesPtr valid(
new vector<int>);
1137 for (
size_t i = 0; i < indices_in->size(); i++)
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))
1142 valid->push_back(indices_in->at(i));
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);
1152 seg.setSearchMethod(kd_tree);
1153 seg.setInputCloud(in);
1154 seg.setIndices(valid);
1155 seg.extract(clusters);
1159 const pcl::IndicesConstPtr &indices_in, vector<pcl::PointIndices> &clusters)
const 1162 pcl::IndicesPtr valid(
new vector<int>);
1163 for (
size_t i = 0; i < indices_in->size(); i++)
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))
1168 valid->push_back(indices_in->at(i));
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);
1179 seg.setSearchMethod(kd_tree);
1180 seg.setInputCloud(in);
1181 seg.setIndices(valid);
1182 seg.extract(clusters);
1186 const pcl::PointIndices &cluster)
const 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();
1194 for (
size_t i = 0; i < cluster.indices.size(); i++)
1197 int row = cluster.indices[i] / in->width;
1198 int col = cluster.indices[i] - (row * in->width);
1203 }
else if (row > row_max)
1210 }
else if (col > col_max)
1217 sensor_msgs::Image msg;
1220 msg.header.frame_id = in->header.frame_id;
1222 msg.width = col_max - col_min;
1223 msg.height = row_max - row_min;
1225 msg.step = 3 * msg.width;
1226 msg.data.resize(msg.step * msg.height);
1230 for (
int h = 0; h < msg.height; h++)
1232 for (
int w = 0; w < msg.width; w++)
1235 const pcl::PointXYZRGB &point = in->at(col_min + w, row_min + h);
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;
1249 visualization_msgs::Marker marker;
1251 marker.header.frame_id = pc->header.frame_id;
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;
1268 marker.type = visualization_msgs::Marker::CUBE_LIST;
1269 marker.color.a = 1.0;
1272 pcl::PCLPointCloud2 downsampled;
1273 pcl::VoxelGrid<pcl::PCLPointCloud2> voxel_grid;
1274 voxel_grid.setInputCloud(pc);
1276 voxel_grid.filter(downsampled);
1279 sensor_msgs::PointCloud2 pc2_msg;
1281 sensor_msgs::PointCloud pc_msg;
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++)
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;
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);
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;
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 1312 pcl::ExtractIndices<pcl::PointXYZRGB>
extract;
1313 extract.setInputCloud(in);
1314 extract.setIndices(indices_in);
1315 extract.filter(*out);
1319 const pcl::IndicesConstPtr &indices_in,
1320 const pcl::ConditionBase<pcl::PointXYZRGB>::Ptr &conditions,
1321 const pcl::IndicesPtr &indices_out)
const 1324 pcl::PointCloud<pcl::PointXYZRGB> tmp;
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();
1334 double Segmenter::averageZ(
const vector<pcl::PointXYZRGB, Eigen::aligned_allocator<pcl::PointXYZRGB> > &v)
const 1337 for (
size_t i = 0; i < v.size(); i++)
1341 return (avg / (
double) v.size());
1345 Eigen::Vector3f
RGB2Lab (
const Eigen::Vector3f& colorRGB)
1350 double R, G, B, X, Y, Z;
1358 R = pow ( (R + 0.055) / 1.055, 2.4);
1363 G = pow ( (G + 0.055) / 1.055, 2.4);
1368 B = pow ( (B + 0.055) / 1.055, 2.4);
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;
1389 X = pow (X, 1.0 / 3.0);
1391 X = 7.787 * X + 16.0 / 116.0;
1394 Y = pow (Y, 1.0 / 3.0);
1396 Y = 7.787 * Y + 16.0 / 116.0;
1399 Z = pow (Z, 1.0 / 3.0);
1401 Z = 7.787 * Z + 16.0 / 116.0;
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));
std::string point_cloud_topic_
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.
static const double POINT_COLOR_THRESHOLD
ros::ServiceServer remove_object_srv_
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.
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.
visualization_msgs::Marker table_marker_
const std::string & getBoundingFrameID() const
Segmentation frame ID value accessor.
rail_manipulation_msgs::SegmentedObjectList object_list_
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.
void setYawMax(const double yaw_max)
Yaw max value mutator.
ros::Publisher debug_img_pub_
static const double SAC_EPS_ANGLE
visualization_msgs::Marker createMarker(const pcl::PCLPointCloud2::ConstPtr &pc) const
Create a Marker from the given point cloud.
ros::ServiceServer segment_objects_srv_
bool segmentCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Callback for the main segmentation request.
static const int DEFAULT_MAX_CLUSTER_SIZE
double getXMax() const
X max value accessor.
tf::TransformListener tf_
double getXMin() const
X min value accessor.
ros::NodeHandle private_node_
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.
void setPitchMin(const double pitch_min)
Pitch min value mutator.
ros::Publisher table_pub_
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.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
static const float DOWNSAMPLE_LEAF_SIZE
bool okay() const
A check for a valid Segmenter.
static const bool DEFAULT_DEBUG
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.
visualization_msgs::MarkerArray markers_
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
bool param(const std::string ¶m_name, T ¶m_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.
std::vector< SegmentationZone > zones_
double averageZ(const std::vector< pcl::PointXYZRGB, Eigen::aligned_allocator< pcl::PointXYZRGB > > &v) const
Find the average Z value of the point vector.
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.
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
ros::Publisher markers_pub_
void setZMax(const double z_max)
Z max value mutator.
ros::Publisher segmented_objects_pub_
static const int DEFAULT_MIN_CLUSTER_SIZE
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
visualization_msgs::MarkerArray text_markers_
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)
ros::ServiceServer calculate_features_srv_
static const double REGION_COLOR_THRESHOLD
ROSLIB_DECL std::string getPath(const std::string &package_name)
static const double MARKER_SCALE
bool segmentObjectsFromPointCloudCallback(rail_manipulation_msgs::SegmentObjectsFromPointCloud::Request &req, rail_manipulation_msgs::SegmentObjectsFromPointCloud::Response &res)
Callback for the main segmentation request.
The main segmentation node object.
ros::ServiceServer segment_objects_from_point_cloud_srv_
double getZMax() const
Z max value accessor.
static const double CLUSTER_TOLERANCE
ros::Publisher table_marker_pub_
static const double SAC_DISTANCE_THRESHOLD
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.
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.
ros::Publisher debug_pc_pub_
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
rail_manipulation_msgs::SegmentedObject table_
void setXMin(const double x_min)
X min value mutator.
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.
Eigen::Vector3f RGB2Lab(const Eigen::Vector3f &colorRGB)
void setRollMax(const double roll_max)
Roll max value mutator.
ros::ServiceServer segment_srv_
double cluster_tolerance_
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_
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_