20 const bool Segmenter::DEFAULT_DEBUG;
21 const int Segmenter::DEFAULT_MIN_CLUSTER_SIZE;
22 const int Segmenter::DEFAULT_MAX_CLUSTER_SIZE;
24 Segmenter::Segmenter() : private_node_(
"~"), tf2_(tf_buffer_)
30 string point_cloud_topic(
"/camera/depth_registered/points");
47 "segmented_objects", 1, true
50 "segmented_table", 1, true
63 #ifdef YAMLCPP_GT_0_5_0 65 YAML::Node zones_config = YAML::LoadFile(zones_file);
66 for (
size_t i = 0; i < zones_config.size(); i++)
68 YAML::Node cur = zones_config[i];
70 SegmentationZone zone(cur[
"name"].as<string>(), cur[
"parent_frame_id"].as<string>(),
71 cur[
"child_frame_id"].as<string>(), cur[
"bounding_frame_id"].as<string>(),
72 cur[
"segmentation_frame_id"].as<string>());
75 if (cur[
"remove_surface"].IsDefined())
81 if (cur[
"roll_min"].IsDefined())
85 if (cur[
"roll_max"].IsDefined())
89 if (cur[
"pitch_min"].IsDefined())
93 if (cur[
"pitch_max"].IsDefined())
97 if (cur[
"yaw_min"].IsDefined())
99 zone.
setYawMin(cur[
"yaw_min"].as<double>());
101 if (cur[
"yaw_max"].IsDefined())
103 zone.
setYawMax(cur[
"yaw_max"].as<double>());
105 if (cur[
"x_min"].IsDefined())
107 zone.
setXMin(cur[
"x_min"].as<double>());
109 if (cur[
"x_max"].IsDefined())
111 zone.
setXMax(cur[
"x_max"].as<double>());
113 if (cur[
"y_min"].IsDefined())
115 zone.
setYMin(cur[
"y_min"].as<double>());
117 if (cur[
"y_max"].IsDefined())
119 zone.
setYMax(cur[
"y_max"].as<double>());
121 if (cur[
"z_min"].IsDefined())
123 zone.
setZMin(cur[
"z_min"].as<double>());
125 if (cur[
"z_max"].IsDefined())
127 zone.
setZMax(cur[
"z_max"].as<double>());
134 ifstream fin(zones_file.c_str());
135 YAML::Parser zones_parser(fin);
136 YAML::Node zones_config;
137 zones_parser.GetNextDocument(zones_config);
138 for (
size_t i = 0; i < zones_config.size(); i++)
141 string name, parent_frame_id, child_frame_id, bounding_frame_id, segmentation_frame_id;
142 zones_config[i][
"name"] >> name;
143 zones_config[i][
"parent_frame_id"] >> parent_frame_id;
144 zones_config[i][
"child_frame_id"] >> child_frame_id;
145 zones_config[i][
"bounding_frame_id"] >> bounding_frame_id;
146 zones_config[i][
"segmentation_frame_id"] >> segmentation_frame_id;
149 SegmentationZone zone(name, parent_frame_id, child_frame_id, bounding_frame_id, segmentation_frame_id);
152 if (zones_config[i].FindValue(
"remove_surface") != NULL)
155 zones_config[i][
"remove_surface"] >> remove_surface;
160 if (zones_config[i].FindValue(
"roll_min") != NULL)
163 zones_config[i][
"roll_min"] >> roll_min;
166 if (zones_config[i].FindValue(
"roll_max") != NULL)
169 zones_config[i][
"roll_max"] >> roll_max;
172 if (zones_config[i].FindValue(
"pitch_min") != NULL)
175 zones_config[i][
"pitch_min"] >> pitch_min;
178 if (zones_config[i].FindValue(
"pitch_max") != NULL)
181 zones_config[i][
"pitch_max"] >> pitch_max;
184 if (zones_config[i].FindValue(
"yaw_min") != NULL)
187 zones_config[i][
"yaw_min"] >> yaw_min;
190 if (zones_config[i].FindValue(
"yaw_max") != NULL)
193 zones_config[i][
"yaw_max"] >> yaw_max;
196 if (zones_config[i].FindValue(
"x_min") != NULL)
199 zones_config[i][
"x_min"] >> x_min;
202 if (zones_config[i].FindValue(
"x_max") != NULL)
205 zones_config[i][
"x_max"] >> x_max;
208 if (zones_config[i].FindValue(
"y_min") != NULL)
211 zones_config[i][
"y_min"] >> y_min;
214 if (zones_config[i].FindValue(
"y_max") != NULL)
217 zones_config[i][
"y_max"] >> y_max;
220 if (zones_config[i].FindValue(
"z_min") != NULL)
223 zones_config[i][
"z_min"] >> z_min;
226 if (zones_config[i].FindValue(
"z_max") != NULL)
229 zones_config[i][
"z_max"] >> z_max;
241 ROS_INFO(
"Segmenter Successfully Initialized");
245 ROS_ERROR(
"No valid segmenation zones defined. Check %s.", zones_file.c_str());
258 boost::mutex::scoped_lock lock(
pc_mutex_);
267 for (
size_t i = 0; i <
zones_.size(); i++)
275 tf.transform.rotation.w));
276 double roll, pitch, yaw;
277 mat.
getRPY(roll, pitch, yaw);
280 if (roll >=
zones_[i].getRollMin() && pitch >=
zones_[i].getPitchMin() && yaw >=
zones_[i].getYawMin() &&
281 roll <=
zones_[i].getRollMax() && pitch <=
zones_[i].getPitchMax() && yaw <=
zones_[i].getYawMax())
287 ROS_WARN(
"Current state not in a valid segmentation zone. Defaulting to first zone.");
292 rail_segmentation::RemoveObject::Response &res)
308 markers_.markers[req.index].action = visualization_msgs::Marker::DELETE;
314 ROS_ERROR(
"Attempted to remove index %d from list of size %ld.", req.index,
object_list_.objects.size());
332 for (
size_t i = 0; i <
markers_.markers.size(); i++)
334 markers_.markers[i].action = visualization_msgs::Marker::DELETE;
346 rail_manipulation_msgs::SegmentedObjectList objects;
351 rail_manipulation_msgs::SegmentObjects::Response &res)
360 boost::mutex::scoped_lock lock(
pc_mutex_);
363 ROS_WARN(
"No point cloud received yet. Ignoring segmentation request.");
369 std_srvs::Empty empty;
377 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_pc(
new pcl::PointCloud<pcl::PointXYZRGB>);
380 boost::mutex::scoped_lock lock(
pc_mutex_);
383 *transformed_pc,
tf_);
385 transformed_pc->header.seq =
pc_->header.seq;
386 transformed_pc->header.stamp =
pc_->header.stamp;
390 pcl::IndicesPtr filter_indices(
new vector<int>);
391 filter_indices->resize(transformed_pc->points.size());
392 for (
size_t i = 0; i < transformed_pc->points.size(); i++)
394 filter_indices->at(i) = i;
401 table_ = this->
findSurface(transformed_pc, filter_indices, zone, filter_indices);
402 double z_surface =
table_.centroid.z;
408 pcl::ConditionOr<pcl::PointXYZRGB>::Ptr bounds(
new pcl::ConditionOr<pcl::PointXYZRGB>);
409 if (z_min > -numeric_limits<double>::infinity())
411 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
412 new pcl::FieldComparison<pcl::PointXYZRGB>(
"z", pcl::ComparisonOps::LE, z_min))
415 if (zone.
getZMax() < numeric_limits<double>::infinity())
417 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
418 new pcl::FieldComparison<pcl::PointXYZRGB>(
"z", pcl::ComparisonOps::GE, zone.
getZMax()))
421 if (zone.
getYMin() > -numeric_limits<double>::infinity())
423 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
424 new pcl::FieldComparison<pcl::PointXYZRGB>(
"y", pcl::ComparisonOps::LE, zone.
getYMin()))
427 if (zone.
getYMax() < numeric_limits<double>::infinity())
429 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
430 new pcl::FieldComparison<pcl::PointXYZRGB>(
"y", pcl::ComparisonOps::GE, zone.
getYMax()))
433 if (zone.
getXMin() > -numeric_limits<double>::infinity())
435 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
436 new pcl::FieldComparison<pcl::PointXYZRGB>(
"x", pcl::ComparisonOps::LE, zone.
getXMin()))
439 if (zone.
getXMax() < numeric_limits<double>::infinity())
441 bounds->addComparison(pcl::FieldComparison<pcl::PointXYZRGB>::ConstPtr(
442 new pcl::FieldComparison<pcl::PointXYZRGB>(
"x", pcl::ComparisonOps::GE, zone.
getXMax()))
447 this->
inverseBound(transformed_pc, filter_indices, bounds, filter_indices);
452 pcl::PointCloud<pcl::PointXYZRGB>::Ptr debug_pc(
new pcl::PointCloud<pcl::PointXYZRGB>);
453 this->
extract(transformed_pc, filter_indices, debug_pc);
458 vector<pcl::PointIndices> clusters;
464 if (clusters.size() > 0)
469 for (
size_t i = 0; i < clusters.size(); i++)
472 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cluster(
new pcl::PointCloud<pcl::PointXYZRGB>);
473 for (
size_t j = 0; j < clusters[i].indices.size(); j++)
475 cluster->points.push_back(transformed_pc->points[clusters[i].indices[j]]);
477 cluster->width = cluster->points.size();
479 cluster->is_dense =
true;
480 cluster->header.frame_id = transformed_pc->header.frame_id;
483 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_cluster(
new pcl::PointCloud<pcl::PointXYZRGB>);
484 pcl::PCLPointCloud2::Ptr converted(
new pcl::PCLPointCloud2);
489 *transformed_cluster,
tf_);
491 transformed_cluster->header.seq = cluster->header.seq;
492 transformed_cluster->header.stamp = cluster->header.stamp;
493 pcl::toPCLPointCloud2(*transformed_cluster, *converted);
496 pcl::toPCLPointCloud2(*cluster, *converted);
500 rail_manipulation_msgs::SegmentedObject segmented_object;
501 segmented_object.recognized =
false;
504 segmented_object.image = this->
createImage(transformed_pc, clusters[i]);
516 segmented_object.marker = this->
createMarker(converted);
517 segmented_object.marker.id = i;
520 Eigen::Vector3f rgb, lab;
521 rgb[0] = segmented_object.marker.color.r;
522 rgb[1] = segmented_object.marker.color.g;
523 rgb[2] = segmented_object.marker.color.b;
525 segmented_object.rgb.resize(3);
526 segmented_object.cielab.resize(3);
527 segmented_object.rgb[0] = rgb[0];
528 segmented_object.rgb[1] = rgb[1];
529 segmented_object.rgb[2] = rgb[2];
530 segmented_object.cielab[0] = lab[0];
531 segmented_object.cielab[1] = lab[1];
532 segmented_object.cielab[2] = lab[2];
535 Eigen::Vector4f centroid;
538 pcl::compute3DCentroid(*transformed_cluster, centroid);
541 pcl::compute3DCentroid(*cluster, centroid);
543 segmented_object.centroid.x = centroid[0];
544 segmented_object.centroid.y = centroid[1];
545 segmented_object.centroid.z = centroid[2];
551 Eigen::Vector4f min_pt, max_pt;
552 pcl::getMinMax3D(*cluster, min_pt, max_pt);
553 segmented_object.width = max_pt[0] - min_pt[0];
554 segmented_object.depth = max_pt[1] - min_pt[1];
555 segmented_object.height = max_pt[2] - min_pt[2];
558 segmented_object.center.x = (max_pt[0] + min_pt[0]) / 2.0;
559 segmented_object.center.y = (max_pt[1] + min_pt[1]) / 2.0;
560 segmented_object.center.z = (max_pt[2] + min_pt[2]) / 2.0;
563 pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(
new pcl::PointCloud<pcl::PointXYZRGB>);
565 pcl::ModelCoefficients::Ptr coefficients(
new pcl::ModelCoefficients());
566 coefficients->values.resize(4);
567 coefficients->values[0] = 0;
568 coefficients->values[1] = 0;
569 coefficients->values[2] = 1.0;
570 coefficients->values[3] = 0;
571 pcl::ProjectInliers<pcl::PointXYZRGB> proj;
572 proj.setModelType(pcl::SACMODEL_PLANE);
575 proj.setInputCloud(transformed_cluster);
578 proj.setInputCloud(cluster);
580 proj.setModelCoefficients(coefficients);
581 proj.filter(*projected_cluster);
584 Eigen::Vector4f projected_centroid;
585 Eigen::Matrix3f covariance_matrix;
586 pcl::compute3DCentroid(*projected_cluster, projected_centroid);
587 pcl::computeCovarianceMatrixNormalized(*projected_cluster, projected_centroid, covariance_matrix);
588 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance_matrix, Eigen::ComputeEigenvectors);
589 Eigen::Matrix3f eigen_vectors = eigen_solver.eigenvectors();
590 eigen_vectors.col(2) = eigen_vectors.col(0).cross(eigen_vectors.col(1));
592 const Eigen::Quaternionf qfinal(eigen_vectors);
596 tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
600 double angle = r + y;
601 while (angle < -M_PI)
612 objects.objects.push_back(segmented_object);
614 markers_.markers.push_back(segmented_object.marker);
618 objects.header.seq++;
621 objects.cleared =
false;
641 ROS_WARN(
"No segmented objects found.");
649 const pcl::IndicesPtr &indices_out)
const 651 rail_manipulation_msgs::SegmentedObject table;
654 pcl::SACSegmentation<pcl::PointXYZRGB> plane_seg;
656 plane_seg.setOptimizeCoefficients(
true);
657 plane_seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
658 plane_seg.setAxis(Eigen::Vector3f(0, 0, 1));
660 plane_seg.setMethodType(pcl::SAC_RANSAC);
665 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc_copy(
new pcl::PointCloud<pcl::PointXYZRGB>(*in));
666 plane_seg.setInputCloud(pc_copy);
667 plane_seg.setIndices(indices_in);
673 pcl::PointIndices::Ptr inliers_ptr(
new pcl::PointIndices);
676 pcl::ModelCoefficients coefficients;
677 plane_seg.segment(*inliers_ptr, coefficients);
680 if (inliers_ptr->indices.size() == 0)
683 *indices_out = *indices_in;
684 table.centroid.z = -numeric_limits<double>::infinity();
689 pcl::PointCloud<pcl::PointXYZRGB> plane;
690 pcl::ExtractIndices<pcl::PointXYZRGB>
extract(
true);
691 extract.setInputCloud(pc_copy);
692 extract.setIndices(inliers_ptr);
693 extract.setNegative(
false);
694 extract.filter(plane);
695 extract.setKeepOrganized(
true);
696 plane_seg.setIndices(extract.getRemovedIndices());
699 double height = this->
averageZ(plane.points);
702 ROS_INFO(
"Surface found at %fm.", height);
703 *indices_out = *plane_seg.getIndices();
706 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_pc(
new pcl::PointCloud<pcl::PointXYZRGB>);
707 pcl::PCLPointCloud2::Ptr converted(
new pcl::PCLPointCloud2);
712 *transformed_pc,
tf_);
714 transformed_pc->header.seq = plane.header.seq;
715 transformed_pc->header.stamp = plane.header.stamp;
716 pcl::toPCLPointCloud2(*transformed_pc, *converted);
719 pcl::toPCLPointCloud2(plane, *converted);
723 table.recognized =
false;
726 table.image = this->
createImage(pc_copy, *inliers_ptr);
742 Eigen::Vector4f centroid;
745 pcl::compute3DCentroid(*transformed_pc, centroid);
748 pcl::compute3DCentroid(plane, centroid);
750 table.centroid.x = centroid[0];
751 table.centroid.y = centroid[1];
752 table.centroid.z = centroid[2];
755 Eigen::Vector4f min_pt, max_pt;
756 pcl::getMinMax3D(plane, min_pt, max_pt);
757 table.width = max_pt[0] - min_pt[0];
758 table.depth = max_pt[1] - min_pt[1];
759 table.height = max_pt[2] - min_pt[2];
762 table.center.x = (max_pt[0] + min_pt[0]) / 2.0;
763 table.center.y = (max_pt[1] + min_pt[1]) / 2.0;
764 table.center.z = (max_pt[2] + min_pt[2]) / 2.0;
768 pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cluster(
new pcl::PointCloud<pcl::PointXYZRGB>);
770 pcl::ModelCoefficients::Ptr coefficients(
new pcl::ModelCoefficients());
771 coefficients->values.resize(4);
772 coefficients->values[0] = 0;
773 coefficients->values[1] = 0;
774 coefficients->values[2] = 1.0;
775 coefficients->values[3] = 0;
776 pcl::ProjectInliers<pcl::PointXYZRGB> proj;
777 proj.setModelType(pcl::SACMODEL_PLANE);
780 proj.setInputCloud(transformed_pc);
783 pcl::PointCloud<pcl::PointXYZRGB>::Ptr plane_ptr(
new pcl::PointCloud<pcl::PointXYZRGB>(plane));
784 proj.setInputCloud(plane_ptr);
786 proj.setModelCoefficients(coefficients);
787 proj.filter(*projected_cluster);
790 Eigen::Vector4f projected_centroid;
791 Eigen::Matrix3f covariance_matrix;
792 pcl::compute3DCentroid(*projected_cluster, projected_centroid);
793 pcl::computeCovarianceMatrixNormalized(*projected_cluster, projected_centroid, covariance_matrix);
794 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance_matrix, Eigen::ComputeEigenvectors);
795 Eigen::Matrix3f eigen_vectors = eigen_solver.eigenvectors();
796 eigen_vectors.col(2) = eigen_vectors.col(0).cross(eigen_vectors.col(1));
798 const Eigen::Quaternionf qfinal(eigen_vectors);
802 tf_quat.setValue(qfinal.x(), qfinal.y(), qfinal.z(), qfinal.w());
806 double angle = r + y;
807 while (angle < -M_PI)
823 const pcl::IndicesConstPtr &indices_in, vector<pcl::PointIndices> &clusters)
const 826 pcl::IndicesPtr valid(
new vector<int>);
827 for (
size_t i = 0; i < indices_in->size(); i++)
829 if (pcl_isfinite(in->points[indices_in->at(i)].x) & pcl_isfinite(in->points[indices_in->at(i)].y) &
830 pcl_isfinite(in->points[indices_in->at(i)].z))
832 valid->push_back(indices_in->at(i));
836 pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> seg;
837 pcl::search::KdTree<pcl::PointXYZRGB>::Ptr kd_tree(
new pcl::search::KdTree<pcl::PointXYZRGB>);
838 kd_tree->setInputCloud(in);
842 seg.setSearchMethod(kd_tree);
843 seg.setInputCloud(in);
844 seg.setIndices(valid);
845 seg.extract(clusters);
849 const pcl::IndicesConstPtr &indices_in, vector<pcl::PointIndices> &clusters)
const 852 pcl::IndicesPtr valid(
new vector<int>);
853 for (
size_t i = 0; i < indices_in->size(); i++)
855 if (pcl_isfinite(in->points[indices_in->at(i)].x) & pcl_isfinite(in->points[indices_in->at(i)].y) &
856 pcl_isfinite(in->points[indices_in->at(i)].z))
858 valid->push_back(indices_in->at(i));
861 pcl::RegionGrowingRGB<pcl::PointXYZRGB> seg;
862 pcl::search::KdTree<pcl::PointXYZRGB>::Ptr kd_tree(
new pcl::search::KdTree<pcl::PointXYZRGB>);
863 kd_tree->setInputCloud(in);
869 seg.setSearchMethod(kd_tree);
870 seg.setInputCloud(in);
871 seg.setIndices(valid);
872 seg.extract(clusters);
876 const pcl::PointIndices &cluster)
const 879 int row_min = numeric_limits<int>::max();
880 int row_max = numeric_limits<int>::min();
881 int col_min = numeric_limits<int>::max();
882 int col_max = numeric_limits<int>::min();
884 for (
size_t i = 0; i < cluster.indices.size(); i++)
887 int row = cluster.indices[i] / in->width;
888 int col = cluster.indices[i] - (row * in->width);
893 }
else if (row > row_max)
900 }
else if (col > col_max)
907 sensor_msgs::Image msg;
910 msg.header.frame_id = in->header.frame_id;
912 msg.width = col_max - col_min;
913 msg.height = row_max - row_min;
915 msg.step = 3 * msg.width;
916 msg.data.resize(msg.step * msg.height);
920 for (
int h = 0; h < msg.height; h++)
922 for (
int w = 0;
w < msg.width;
w++)
925 const pcl::PointXYZRGB &point = in->at(col_min +
w, row_min + h);
927 int index = (msg.step * h) + (
w * 3);
928 msg.data[index] = point.b;
929 msg.data[index + 1] = point.g;
930 msg.data[index + 2] = point.r;
939 visualization_msgs::Marker marker;
941 marker.header.frame_id = pc->header.frame_id;
944 marker.pose.position.x = 0.0;
945 marker.pose.position.y = 0.0;
946 marker.pose.position.z = 0.0;
947 marker.pose.orientation.x = 0.0;
948 marker.pose.orientation.y = 0.0;
949 marker.pose.orientation.z = 0.0;
950 marker.pose.orientation.w = 1.0;
958 marker.type = visualization_msgs::Marker::CUBE_LIST;
959 marker.color.a = 1.0;
962 pcl::PCLPointCloud2 downsampled;
963 pcl::VoxelGrid<pcl::PCLPointCloud2> voxel_grid;
964 voxel_grid.setInputCloud(pc);
966 voxel_grid.filter(downsampled);
969 sensor_msgs::PointCloud2 pc2_msg;
971 sensor_msgs::PointCloud pc_msg;
975 marker.points.resize(pc_msg.points.size());
976 int r = 0, g = 0, b = 0;
977 for (
size_t j = 0; j < pc_msg.points.size(); j++)
979 marker.points[j].x = pc_msg.points[j].x;
980 marker.points[j].y = pc_msg.points[j].y;
981 marker.points[j].z = pc_msg.points[j].z;
984 uint32_t rgb = *
reinterpret_cast<int *
>(&pc_msg.channels[0].values[j]);
985 r += (int) ((rgb >> 16) & 0x0000ff);
986 g += (int) ((rgb >> 8) & 0x0000ff);
987 b += (int) ((rgb) & 0x0000ff);
991 marker.color.r = ((float) r / (
float) pc_msg.points.size()) / 255.0;
992 marker.color.g = ((float) g / (
float) pc_msg.points.size()) / 255.0;
993 marker.color.b = ((float) b / (
float) pc_msg.points.size()) / 255.0;
994 marker.color.a = 1.0;
999 void Segmenter::extract(
const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &in,
const pcl::IndicesConstPtr &indices_in,
1000 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &out)
const 1002 pcl::ExtractIndices<pcl::PointXYZRGB>
extract;
1003 extract.setInputCloud(in);
1004 extract.setIndices(indices_in);
1005 extract.filter(*out);
1009 const pcl::IndicesConstPtr &indices_in,
1010 const pcl::ConditionBase<pcl::PointXYZRGB>::Ptr &conditions,
1011 const pcl::IndicesPtr &indices_out)
const 1014 pcl::PointCloud<pcl::PointXYZRGB> tmp;
1016 pcl::ConditionalRemoval<pcl::PointXYZRGB> removal(
true);
1017 removal.setCondition(conditions);
1018 removal.setInputCloud(in);
1019 removal.setIndices(indices_in);
1020 removal.filter(tmp);
1021 *indices_out = *removal.getRemovedIndices();
1024 double Segmenter::averageZ(
const vector<pcl::PointXYZRGB, Eigen::aligned_allocator<pcl::PointXYZRGB> > &v)
const 1027 for (
size_t i = 0; i < v.size(); i++)
1031 return (avg / (
double) v.size());
1035 Eigen::Vector3f
RGB2Lab (
const Eigen::Vector3f& colorRGB)
1040 double R, G, B, X, Y, Z;
1048 R = pow ( (R + 0.055) / 1.055, 2.4);
1053 G = pow ( (G + 0.055) / 1.055, 2.4);
1058 B = pow ( (B + 0.055) / 1.055, 2.4);
1068 X = R * 0.4124 + G * 0.3576 + B * 0.1805;
1069 Y = R * 0.2126 + G * 0.7152 + B * 0.0722;
1070 Z = R * 0.0193 + G * 0.1192 + B * 0.9505;
1079 X = pow (X, 1.0 / 3.0);
1081 X = 7.787 * X + 16.0 / 116.0;
1084 Y = pow (Y, 1.0 / 3.0);
1086 Y = 7.787 * Y + 16.0 / 116.0;
1089 Z = pow (Z, 1.0 / 3.0);
1091 Z = 7.787 * Z + 16.0 / 116.0;
1093 Eigen::Vector3f colorLab;
1094 colorLab[0] =
static_cast<float> (116.0 * Y - 16.0);
1095 colorLab[1] =
static_cast<float> (500.0 * (X - Y));
1096 colorLab[2] =
static_cast<float> (200.0 * (Y - Z));
const SegmentationZone & getCurrentZone() const
Determine the current zone based on the latest state of the TF tree.
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
void getRPY(tf2Scalar &roll, tf2Scalar &pitch, tf2Scalar &yaw, unsigned int solution_number=1) const
ros::ServiceServer remove_object_srv_
void publish(const boost::shared_ptr< M > &message) const
void setYawMin(const double yaw_min)
Yaw min value mutator.
double getZMax() const
Z max value accessor.
void setZMin(const double z_min)
Z min value mutator.
visualization_msgs::Marker table_marker_
rail_manipulation_msgs::SegmentedObjectList object_list_
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.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setYawMax(const double yaw_max)
Yaw max value mutator.
ros::Publisher debug_img_pub_
static const double SAC_EPS_ANGLE
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
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
tf::TransformListener tf_
pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr pc_
ros::NodeHandle private_node_
void setPitchMin(const double pitch_min)
Pitch min value mutator.
ros::Publisher table_pub_
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.
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)
const std::string & getBoundingFrameID() const
Segmentation frame ID value accessor.
rail_manipulation_msgs::SegmentedObject findSurface(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &in, const pcl::IndicesConstPtr &indices_in, const SegmentationZone &zone, const pcl::IndicesPtr &indices_out) const
Find and remove a surface from the given point cloud.
static const float DOWNSAMPLE_LEAF_SIZE
TFSIMD_FORCE_INLINE const tfScalar & y() const
static const bool DEFAULT_DEBUG
double getYMin() const
Y min value accessor.
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_
static const double CLUSTER_TOLERANCE
void setRollMin(const double roll_min)
Roll min value mutator.
void setYMin(const double y_min)
Y min value mutator.
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
static const double SURFACE_REMOVAL_PADDING
double getXMax() const
X max value accessor.
bool okay() const
A check for a valid Segmenter.
std::vector< SegmentationZone > zones_
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
double getZMin() const
Z min value accessor.
bool removeObjectCallback(rail_segmentation::RemoveObject::Request &req, rail_segmentation::RemoveObject::Response &res)
Callback for the remove object request.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void pointCloudCallback(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &pc)
Callback for the point cloud topic.
void setXMax(const double x_max)
X max value mutator.
double getYMax() const
Y max value accessor.
static const int SAC_MAX_ITERATIONS
ros::Publisher markers_pub_
double averageZ(const std::vector< pcl::PointXYZRGB, Eigen::aligned_allocator< pcl::PointXYZRGB > > &v) const
Find the average Z value of the point vector.
void setZMax(const double z_max)
Z max value mutator.
ros::Publisher segmented_objects_pub_
static const int DEFAULT_MIN_CLUSTER_SIZE
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static const double REGION_COLOR_THRESHOLD
ROSLIB_DECL std::string getPath(const std::string &package_name)
bool getRemoveSurface() const
Remove surface value accessor.
static const double MARKER_SCALE
The main segmentation node object.
ros::Publisher table_marker_pub_
static const double SAC_DISTANCE_THRESHOLD
TFSIMD_FORCE_INLINE const tfScalar & w() const
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.
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
double getXMin() const
X min value accessor.
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
bool getParam(const std::string &key, std::string &s) const
visualization_msgs::Marker createMarker(const pcl::PCLPointCloud2::ConstPtr &pc) const
Create a Marker from the given point cloud.
const std::string & getSegmentationFrameID() const
Segmentation frame ID value accessor.
ros::Subscriber point_cloud_sub_
ros::Publisher debug_pc_pub_
rail_manipulation_msgs::SegmentedObject table_
void setXMin(const double x_min)
X min value mutator.
Eigen::Vector3f RGB2Lab(const Eigen::Vector3f &colorRGB)
void setRollMax(const double roll_max)
Roll max value mutator.
ros::ServiceServer segment_srv_
void setYMax(const double y_max)
Y max value mutator.
The criteria for a segmentation zone.
ros::ServiceServer clear_srv_
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 setRemoveSurface(const bool remove_surface)
Remove surface value mutator.
tf2_ros::Buffer tf_buffer_
const std::string & getName() const
Name value accessor.
sensor_msgs::Image createImage(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &in, const pcl::PointIndices &cluster) const
Create a cropped image of the segmented object.