37 #include "jsk_recognition_msgs/ModelCoefficientsArray.h" 38 #include <pcl/segmentation/impl/organized_multi_plane_segmentation.hpp> 39 #include <pcl/filters/extract_indices.h> 40 #include <pcl/kdtree/kdtree_flann.h> 42 #include <Eigen/StdVector> 43 #include <pcl/surface/convex_hull.h> 44 #include <pcl/filters/project_inliers.h> 45 #include <pcl/features/integral_image_normal.h> 50 #include <boost/format.hpp> 51 #include <pcl/common/centroid.h> 52 #include <visualization_msgs/Marker.h> 55 #include <pcl/sample_consensus/method_types.h> 56 #include <pcl/sample_consensus/model_types.h> 57 #include <pcl/segmentation/sac_segmentation.h> 58 #include <pcl/surface/convex_hull.h> 67 ConnectionBasedNodelet::onInit();
68 pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
75 getName() +
"::NormalEstimation",
81 getName() +
"::PlaneSegmentation",
87 pnh_->param(
"vital_rate", vital_rate, 1.0);
97 pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"output", 1);
98 polygon_pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*
pnh_,
"output_polygon", 1);
100 = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*
pnh_,
"output_coefficients", 1);
101 org_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"output_nonconnected", 1);
103 = advertise<jsk_recognition_msgs::PolygonArray>(*
pnh_,
"output_nonconnected_polygon", 1);
105 = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*
pnh_,
106 "output_nonconnected_coefficients", 1);
109 "output_refined", 1);
111 = advertise<jsk_recognition_msgs::PolygonArray>(*
pnh_,
"output_refined_polygon", 1);
113 = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*
pnh_,
114 "output_refined_coefficients", 1);
117 = advertise<visualization_msgs::Marker>(*
pnh_,
118 "debug_connection_map", 1);
122 = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output_normal", 1);
125 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
126 dynamic_reconfigure::Server<Config>::CallbackType
f =
129 srv_->setCallback (f);
140 const std::vector<pcl::ModelCoefficients>& coefficients,
141 std::vector<pcl::ModelCoefficients>& output_coefficients)
143 output_coefficients.resize(coefficients.size());
144 for (
size_t i = 0; i < coefficients.size(); i++) {
145 pcl::ModelCoefficients plane_coefficient = coefficients[i];
151 output_coefficients[i] = plane_coefficient;
155 pcl::ModelCoefficients new_coefficient;
157 output_coefficients[i] = new_coefficient;
190 = config.ransac_refine_outlier_distance_threshold;
197 const pcl::PointCloud<PointT>::Ptr& input,
198 const std::vector<pcl::ModelCoefficients>& model_coefficients,
199 const std::vector<pcl::PointIndices>& boundary_indices,
202 NODELET_DEBUG(
"size of model_coefficients: %lu", model_coefficients.size());
203 if (model_coefficients.size() == 0) {
207 if (model_coefficients.size() == 1) {
208 connection_map[0]= std::vector<int>();
212 pcl::ExtractIndices<PointT> extract;
213 extract.setInputCloud(input);
214 for (
size_t i = 0; i < model_coefficients.size(); i++) {
216 connection_map[i] = std::vector<int>();
217 connection_map[i].push_back(i);
218 for (
size_t j = i + 1; j < model_coefficients.size(); j++) {
220 pcl::ModelCoefficients a_coefficient = model_coefficients[i];
221 pcl::ModelCoefficients b_coefficient = model_coefficients[j];
222 Eigen::Vector3f a_normal(a_coefficient.values[0], a_coefficient.values[1], a_coefficient.values[2]);
223 Eigen::Vector3f b_normal(b_coefficient.values[0], b_coefficient.values[1], b_coefficient.values[2]);
224 double a_distance = a_coefficient.values[3];
225 double b_distance = b_coefficient.values[3];
227 if (a_normal.norm() != 1.0) {
228 a_distance = a_distance / a_normal.norm();
229 a_normal = a_normal / a_normal.norm();
231 if (b_normal.norm() != 1.0) {
232 b_distance = b_distance / b_normal.norm();
233 b_normal = b_normal / b_normal.norm();
235 double theta = fabs(
acos(a_normal.dot(b_normal)));
237 if (theta >
M_PI / 2.0) {
238 theta =
M_PI - theta;
247 pcl::PointIndices::Ptr a_indices
248 = boost::make_shared<pcl::PointIndices>(boundary_indices[i]);
249 pcl::PointIndices::Ptr b_indices
250 = boost::make_shared<pcl::PointIndices>(boundary_indices[j]);
251 pcl::PointCloud<PointT> a_cloud, b_cloud;
252 extract.setIndices(a_indices);
253 extract.filter(a_cloud);
254 extract.setIndices(b_indices);
255 extract.filter(b_cloud);
256 if (a_cloud.points.size() > 0) {
257 pcl::KdTreeFLANN<PointT> kdtree;
258 kdtree.setInputCloud(a_cloud.makeShared());
260 for (
size_t pi = 0; pi < b_cloud.points.size(); pi++) {
262 std::vector<int> k_indices;
263 std::vector<float> k_sqr_distances;
264 if (kdtree.radiusSearch(
272 connection_map[i].push_back(j);
280 const std::vector<pcl::PointIndices>& inlier_indices,
281 const std_msgs::Header&
header,
282 jsk_recognition_msgs::ClusterPointIndices& output_indices)
284 for (
size_t i = 0; i < inlier_indices.size(); i++) {
285 pcl::PointIndices inlier = inlier_indices[i];
287 one_indices.header =
header;
288 one_indices.indices = inlier.indices;
289 output_indices.cluster_indices.push_back(one_indices);
294 const pcl::PointCloud<PointT>& input,
295 geometry_msgs::Polygon&
polygon)
297 for (
size_t i = 0; i < input.points.size(); i++) {
298 geometry_msgs::Point32
point;
299 point.
x = input.points[i].x;
300 point.y = input.points[i].y;
301 point.z = input.points[i].z;
302 polygon.points.push_back(point);
307 const pcl::PointCloud<PointT>::Ptr& input,
308 const std_msgs::Header&
header,
309 const std::vector<pcl::PointIndices>& inlier_indices,
310 const std::vector<pcl::PointIndices>& boundary_indices,
311 const std::vector<pcl::ModelCoefficients>& model_coefficients,
313 std::vector<pcl::PointIndices>& output_indices,
314 std::vector<pcl::ModelCoefficients>& output_coefficients,
315 std::vector<pcl::PointCloud<PointT> >& output_boundary_clouds)
317 std::vector<std::set<int> > cloud_sets;
319 for (jsk_recognition_utils::IntegerGraphMap::const_iterator it = connection_map.begin();
320 it != connection_map.end();
322 int from_index = it->first;
323 std::stringstream ss;
324 ss <<
"connection map: " << from_index <<
" [";
325 for (
size_t i = 0; i < it->second.size(); i++) {
333 for (
size_t i = 0; i < cloud_sets.size(); i++) {
334 pcl::PointIndices one_indices;
335 pcl::PointIndices one_boundaries;
336 std::vector<float> new_coefficients;
337 new_coefficients.resize(4, 0);
338 for (std::set<int>::iterator it = cloud_sets[i].
begin();
339 it != cloud_sets[i].end();
342 new_coefficients = model_coefficients[*it].values;
343 pcl::PointIndices inlier = inlier_indices[*it];
344 pcl::PointIndices boundary_inlier = boundary_indices[*it];
349 if (one_indices.indices.size() == 0) {
353 double norm =
sqrt(new_coefficients[0] * new_coefficients[0]
354 + new_coefficients[1] * new_coefficients[1]
355 + new_coefficients[2] * new_coefficients[2]);
356 new_coefficients[0] /= norm;
357 new_coefficients[1] /= norm;
358 new_coefficients[2] /= norm;
359 new_coefficients[3] /= norm;
362 pcl::ModelCoefficients pcl_new_coefficients;
363 pcl_new_coefficients.values = new_coefficients;
365 pcl::PointIndices::Ptr indices_ptr
366 = boost::make_shared<pcl::PointIndices>(one_boundaries);
367 pcl::ModelCoefficients::Ptr coefficients_ptr
368 = boost::make_shared<pcl::ModelCoefficients>(pcl_new_coefficients);
370 = jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
371 input, indices_ptr, coefficients_ptr);
373 pcl::PointCloud<PointT> chull_output;
374 convex->boundariesToPointCloud<
PointT>(chull_output);
375 output_indices.push_back(one_indices);
376 output_coefficients.push_back(pcl_new_coefficients);
377 output_boundary_clouds.push_back(chull_output);
390 pcl::PointCloud<PointT>::Ptr input,
391 pcl::PointCloud<pcl::Normal>::Ptr normal,
393 std::vector<pcl::ModelCoefficients>& model_coefficients,
394 std::vector<pcl::PointIndices>& inlier_indices,
395 pcl::PointCloud<pcl::Label>::Ptr& labels,
396 std::vector<pcl::PointIndices>& label_indices,
397 std::vector<pcl::PointIndices>& boundary_indices)
400 pcl::OrganizedMultiPlaneSegmentation<PointT, pcl::Normal, pcl::Label> mps;
405 mps.setInputCloud(input);
406 mps.setInputNormals(normal);
409 mps.segmentAndRefine(
410 regions, model_coefficients, inlier_indices,
411 labels, label_indices, boundary_indices);
416 const std_msgs::Header&
header,
417 const pcl::PointCloud<PointT>::Ptr input,
421 const std::vector<pcl::PointIndices>& inlier_indices,
422 const std::vector<pcl::PointCloud<PointT> >& boundaries,
423 const std::vector<pcl::ModelCoefficients>& model_coefficients)
425 jsk_recognition_msgs::ClusterPointIndices indices;
426 jsk_recognition_msgs::ModelCoefficientsArray coefficients_array;
427 jsk_recognition_msgs::PolygonArray polygon_array;
429 polygon_array.header =
header;
430 coefficients_array.header =
header;
441 for (
size_t i = 0; i < boundaries.size(); i++) {
442 geometry_msgs::PolygonStamped
polygon;
443 pcl::PointCloud<PointT> boundary_cloud = boundaries[i];
446 polygon_array.polygons.push_back(polygon);
448 polygon_pub.
publish(polygon_array);
453 for (
size_t i = 0; i < model_coefficients.size(); i++) {
455 coefficient.values = model_coefficients[i].values;
456 coefficient.header =
header;
457 coefficients_array.coefficients.push_back(coefficient);
459 coefficients_pub.
publish(coefficients_array);
463 const std_msgs::Header&
header,
464 const pcl::PointCloud<PointT>::Ptr input,
468 const std::vector<pcl::PointIndices>& inlier_indices,
469 const std::vector<pcl::PointIndices>& boundary_indices,
470 const std::vector<pcl::ModelCoefficients>& model_coefficients)
473 std::vector<pcl::PointCloud<PointT> > boundaries;
474 pcl::ExtractIndices<PointT> extract;
475 extract.setInputCloud(input);
476 for (
size_t i = 0; i < boundary_indices.size(); i++) {
477 pcl::PointCloud<PointT> boundary_cloud;
478 pcl::PointIndices boundary_one_indices = boundary_indices[i];
479 pcl::PointIndices::Ptr indices_ptr = boost::make_shared<pcl::PointIndices>(boundary_indices[i]);
480 extract.setIndices(indices_ptr);
481 extract.filter(boundary_cloud);
482 boundaries.push_back(boundary_cloud);
486 header, input, indices_pub, polygon_pub, coefficients_pub,
487 inlier_indices, boundaries, model_coefficients);
492 const pcl::PointCloud<PointT>::Ptr cloud,
493 const std::vector<pcl::PointIndices>& inliers,
494 const std_msgs::Header&
header)
499 visualization_msgs::Marker connection_marker;
500 connection_marker.type = visualization_msgs::Marker::LINE_LIST;
501 connection_marker.scale.x = 0.01;
502 connection_marker.header =
header;
503 connection_marker.pose.orientation.w = 1.0;
510 for (
size_t i = 0; i < inliers.size(); i++) {
511 pcl::PointIndices::Ptr target_inliers
512 = boost::make_shared<pcl::PointIndices>(inliers[i]);
513 pcl::PointCloud<PointT>::Ptr target_cloud (
new pcl::PointCloud<PointT>);
514 Eigen::Vector4f centroid;
515 pcl::ExtractIndices<PointT>
ex;
516 ex.setInputCloud(cloud);
517 ex.setIndices(target_inliers);
518 ex.filter(*target_cloud);
519 pcl::compute3DCentroid(*target_cloud, centroid);
520 Eigen::Vector3f centroid_3f(centroid[0], centroid[1], centroid[2]);
521 centroids.push_back(centroid_3f);
524 for (jsk_recognition_utils::IntegerGraphMap::iterator it = connection_map.begin();
525 it != connection_map.end();
528 int from_index = it->first;
529 std::vector<int> the_connection_map = connection_map[from_index];
530 for (
size_t j = 0; j < the_connection_map.size(); j++) {
531 int to_index = the_connection_map[j];
533 Eigen::Vector3f from_point = centroids[from_index];
534 Eigen::Vector3f to_point = centroids[to_index];
535 geometry_msgs::Point from_point_ros, to_point_ros;
536 jsk_recognition_utils::pointFromVectorToXYZ<Eigen::Vector3f, geometry_msgs::Point>(
537 from_point, from_point_ros);
538 jsk_recognition_utils::pointFromVectorToXYZ<Eigen::Vector3f, geometry_msgs::Point>(
539 to_point, to_point_ros);
540 connection_marker.points.push_back(from_point_ros);
541 connection_marker.points.push_back(to_point_ros);
550 pcl::PointCloud<PointT>::Ptr input,
551 pcl::PointCloud<pcl::Normal>::Ptr normal,
552 const std_msgs::Header&
header)
555 std::vector<pcl::ModelCoefficients> model_coefficients;
556 std::vector<pcl::PointIndices> inlier_indices;
557 pcl::PointCloud<pcl::Label>::Ptr
labels (
new pcl::PointCloud<pcl::Label>());
558 std::vector<pcl::PointIndices> label_indices;
559 std::vector<pcl::PointIndices> boundary_indices;
565 inlier_indices, labels, label_indices,
567 std::vector<pcl::ModelCoefficients> fixed_model_coefficients;
569 model_coefficients = fixed_model_coefficients;
575 inlier_indices, boundary_indices, model_coefficients);
582 connectPlanesMap(input, model_coefficients, boundary_indices, connection_map);
584 std::vector<pcl::PointIndices> output_nonrefined_indices;
585 std::vector<pcl::ModelCoefficients> output_nonrefined_coefficients;
586 std::vector<pcl::PointCloud<PointT> > output_nonrefined_boundary_clouds;
592 output_nonrefined_indices,
593 output_nonrefined_coefficients,
594 output_nonrefined_boundary_clouds);
595 std::vector<pcl::ModelCoefficients> fixed_output_nonrefined_coefficients;
597 output_nonrefined_coefficients = fixed_output_nonrefined_coefficients;
601 output_nonrefined_indices,
602 output_nonrefined_boundary_clouds,
603 output_nonrefined_coefficients);
608 std::vector<pcl::PointIndices> refined_inliers;
609 std::vector<pcl::ModelCoefficients> refined_coefficients;
610 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> refined_convexes;
612 input, output_nonrefined_indices, output_nonrefined_coefficients,
613 refined_inliers, refined_coefficients, refined_convexes);
614 std::vector<pcl::PointCloud<PointT> > refined_boundary_clouds;
615 for (
size_t i = 0; i < refined_convexes.size(); i++) {
616 pcl::PointCloud<PointT> refined_boundary;
617 refined_convexes[i]->boundariesToPointCloud(refined_boundary);
618 refined_boundary_clouds.push_back(refined_boundary);
620 std::vector<pcl::ModelCoefficients> fixed_refined_coefficients;
622 refined_coefficients = fixed_refined_coefficients;
626 refined_inliers, refined_boundary_clouds, refined_coefficients);
631 const pcl::PointCloud<PointT>::Ptr input,
632 const std::vector<pcl::PointIndices>& input_indices,
633 const std::vector<pcl::ModelCoefficients>& input_coefficients,
634 std::vector<pcl::PointIndices>& output_indices,
635 std::vector<pcl::ModelCoefficients>& output_coefficients,
636 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_convexes)
640 for (
size_t i = 0; i < input_indices.size(); i++) {
641 pcl::PointIndices::Ptr input_indices_ptr
642 = boost::make_shared<pcl::PointIndices>(input_indices[i]);
643 Eigen::Vector3f normal(input_coefficients[i].
values[0],
644 input_coefficients[i].values[1],
645 input_coefficients[i].values[2]);
650 pcl::SACSegmentation<PointT> seg;
651 seg.setOptimizeCoefficients (
true);
652 seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
653 seg.setMethodType (pcl::SAC_RANSAC);
655 seg.setInputCloud(input);
656 seg.setIndices(input_indices_ptr);
657 seg.setMaxIterations (10000);
659 seg.setEpsAngle(pcl::deg2rad(20.0));
660 pcl::PointIndices::Ptr refined_inliers (
new pcl::PointIndices);
661 pcl::ModelCoefficients::Ptr refined_coefficients(
new pcl::ModelCoefficients);
662 seg.segment(*refined_inliers, *refined_coefficients);
663 if (refined_inliers->indices.size() > 0) {
668 input, refined_inliers, refined_coefficients);
671 double area = convex->area();
674 output_convexes.push_back(convex);
675 output_indices.push_back(*refined_inliers);
676 output_coefficients.push_back(*refined_coefficients);
684 pcl::PointCloud<pcl::Normal>::Ptr output)
687 pcl::IntegralImageNormalEstimation<PointT, pcl::Normal> ne;
689 ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
692 ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX);
695 ne.setNormalEstimationMethod (ne.AVERAGE_DEPTH_CHANGE);
698 NODELET_FATAL(
"unknown estimation method, force to use COVARIANCE_MATRIX: %d",
700 ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX);
704 ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<PointT, pcl::Normal>::BORDER_POLICY_IGNORE);
707 ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<PointT, pcl::Normal>::BORDER_POLICY_MIRROR);
713 ne.setInputCloud(input);
718 (
const sensor_msgs::PointCloud2::ConstPtr&
msg)
724 pcl::PointCloud<PointT>::Ptr input(
new pcl::PointCloud<PointT>());
725 pcl::PointCloud<pcl::Normal>::Ptr normal(
new pcl::PointCloud<pcl::Normal>());
733 sensor_msgs::PointCloud2 normal_ros_cloud;
735 normal_ros_cloud.header = msg->header;
753 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"NormalEstimation running");
758 stat.
add(
"Estimation Method",
"AVERAGE_3D_GRADIENT");
761 stat.
add(
"Estimation Method",
"COVARIANCE_MATRIX");
764 stat.
add(
"Estimation Method",
"AVERAGE_DEPTH_CHANGE");
767 stat.
add(
"Border Policy",
"ignore");
770 stat.
add(
"Border Policy",
"mirror");
775 stat.
add(
"Depth Dependent Smooting",
"Enabled");
778 stat.
add(
"Depth Dependent Smooting",
"Disabled");
781 stat.
add(
"Publish Normal",
"Enabled");
784 stat.
add(
"Publish Normal",
"Disabled");
788 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
789 (boost::format(
"NormalEstimation not running for %f sec")
795 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
796 "NormalEstimation is not activated");
805 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
806 "PlaneSegmentation running");
819 stat.
add(
"Use RANSAC refinement",
"True");
820 stat.
add(
"RANSAC refinement distance threshold",
824 stat.
add(
"Use RANSAC refinement",
"False");
827 stat.
add(
"Number of original segmented planes (Avg.)",
829 stat.
add(
"Number of connected segmented planes (Avg.)",
833 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
834 (boost::format(
"PlaneSegmentation not running for %f sec")
ros::Publisher refined_polygon_pub_
jsk_topic_tools::VitalChecker::Ptr normal_estimation_vital_checker_
bool depth_dependent_smoothing_
jsk_topic_tools::TimeAccumulator plane_segmentation_time_acc_
double normal_smoothing_size_
#define NODELET_ERROR(...)
double angular_threshold_
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher polygon_pub_
double max_depth_change_factor_
void summary(unsigned char lvl, const std::string s)
ros::Publisher org_polygon_pub_
virtual Eigen::Vector3f getPointOnPlane()
ros::Publisher coefficients_pub_
virtual void unsubscribe()
ros::Publisher refined_coefficients_pub_
const std::string & getName() const
ros::Timer diagnostics_timer_
jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig Config
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_recognition_utils::Counter connected_plane_num_counter_
virtual void pclIndicesArrayToClusterPointIndices(const std::vector< pcl::PointIndices > &inlier_indices, const std_msgs::Header &header, jsk_recognition_msgs::ClusterPointIndices &output_indices)
jsk_recognition_utils::Counter original_plane_num_counter_
jsk_topic_tools::VitalChecker::Ptr plane_segmentation_vital_checker_
virtual void publishMarkerOfConnection(jsk_recognition_utils::IntegerGraphMap connection_map, const pcl::PointCloud< PointT >::Ptr cloud, const std::vector< pcl::PointIndices > &inliers, const std_msgs::Header &header)
std::map< int, std::vector< int > > IntegerGraphMap
virtual void toCoefficients(std::vector< float > &output)
ros::Publisher org_coefficients_pub_
double distance_threshold_
double max_refined_area_threshold_
virtual void publishSegmentationInformation(const std_msgs::Header &header, const pcl::PointCloud< PointT >::Ptr input, ros::Publisher &indices_pub, ros::Publisher &polygon_pub, ros::Publisher &coefficients_pub, const std::vector< pcl::PointIndices > &inlier_indices, const std::vector< pcl::PointCloud< PointT > > &boundaries, const std::vector< pcl::ModelCoefficients > &model_coefficients)
virtual void estimateNormal(pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr output)
virtual void configCallback(Config &config, uint32_t level)
virtual void forceToDirectOrigin(const std::vector< pcl::ModelCoefficients > &coefficients, std::vector< pcl::ModelCoefficients > &output_coefficients)
bool border_policy_ignore_
ros::Publisher pub_connection_marker_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
virtual void segmentOrganizedMultiPlanes(pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr normal, PlanarRegionVector ®ions, std::vector< pcl::ModelCoefficients > &model_coefficients, std::vector< pcl::PointIndices > &inlier_indices, pcl::PointCloud< pcl::Label >::Ptr &labels, std::vector< pcl::PointIndices > &label_indices, std::vector< pcl::PointIndices > &boundary_indices)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
bool ransac_refine_coefficients_
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
virtual void connectPlanesMap(const pcl::PointCloud< PointT >::Ptr &input, const std::vector< pcl::ModelCoefficients > &model_coefficients, const std::vector< pcl::PointIndices > &boundary_indices, jsk_recognition_utils::IntegerGraphMap &connection_map)
double connect_distance_threshold_
virtual void add(double v)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
ros::Publisher normal_pub_
void buildAllGroupsSetFromGraphMap(IntegerGraphMap graph_map, std::vector< std::set< int > > &output_sets)
jsk_topic_tools::TimeAccumulator ransac_refinement_time_acc_
virtual void updateDiagnosticNormalEstimation(diagnostic_updater::DiagnosticStatusWrapper &stat)
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
virtual void refineBasedOnRANSAC(const pcl::PointCloud< PointT >::Ptr input, const std::vector< pcl::PointIndices > &input_indices, const std::vector< pcl::ModelCoefficients > &input_coefficients, std::vector< pcl::PointIndices > &output_indices, std::vector< pcl::ModelCoefficients > &output_coefficients, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &output_boundaries)
virtual void buildConnectedPlanes(const pcl::PointCloud< PointT >::Ptr &input, const std_msgs::Header &header, const std::vector< pcl::PointIndices > &inlier_indices, const std::vector< pcl::PointIndices > &boundary_indices, const std::vector< pcl::ModelCoefficients > &model_coefficients, const jsk_recognition_utils::IntegerGraphMap &connection_map, std::vector< pcl::PointIndices > &output_indices, std::vector< pcl::ModelCoefficients > &output_coefficients, std::vector< pcl::PointCloud< PointT > > &output_boundary_clouds)
double min_refined_area_threshold_
double connect_plane_angle_threshold_
std::vector< pcl::PlanarRegion< PointT >, Eigen::aligned_allocator< pcl::PlanarRegion< PointT > > > PlanarRegionVector
void add(const std::string &key, const T &val)
#define NODELET_FATAL(...)
virtual void updateDiagnosticPlaneSegmentation(diagnostic_updater::DiagnosticStatusWrapper &stat)
pcl::PointIndices PCLIndicesMsg
ros::Publisher refined_pub_
virtual void updateDiagnostics(const ros::TimerEvent &event)
double ransac_refine_outlier_distance_threshold_
virtual void segmentFromNormals(pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr normal, const std_msgs::Header &header)
#define NODELET_DEBUG(...)
pcl::ModelCoefficients PCLModelCoefficientMsg
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::OrganizedMultiPlaneSegmentation, nodelet::Nodelet)
virtual void pointCloudToPolygon(const pcl::PointCloud< PointT > &input, geometry_msgs::Polygon &polygon)
virtual Eigen::Vector3f getNormal()
jsk_topic_tools::TimeAccumulator normal_estimation_time_acc_