plane_concatenator_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 #define BOOST_PARAMETER_MAX_ARITY 7
37 #include <pcl/kdtree/kdtree_flann.h>
38 #include <pcl/sample_consensus/method_types.h>
39 #include <pcl/sample_consensus/model_types.h>
40 #include <pcl/segmentation/sac_segmentation.h>
43 
44 namespace jsk_pcl_ros_utils
45 {
47  {
48  DiagnosticNodelet::onInit();
49  pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
50  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51  dynamic_reconfigure::Server<Config>::CallbackType f =
52  boost::bind (
53  &PlaneConcatenator::configCallback, this, _1, _2);
54  srv_->setCallback (f);
55 
56  pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
57  *pnh_, "output/indices", 1);
58  pub_polygon_ = advertise<jsk_recognition_msgs::PolygonArray>(
59  *pnh_, "output/polygons", 1);
60  pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
61  *pnh_, "output/coefficients", 1);
62 
64  }
65 
67  {
68  sub_cloud_.subscribe(*pnh_, "input", 1);
69  sub_indices_.subscribe(*pnh_, "input/indices", 1);
70  sub_polygon_.subscribe(*pnh_, "input/polygons", 1);
71  sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
72  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> > (100);
73  sync_->connectInput(sub_cloud_, sub_indices_,
75  sync_->registerCallback(boost::bind(&PlaneConcatenator::concatenate, this,
76  _1, _2, _3, _4));
77  }
78 
80  {
85  }
86 
88  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
89  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
90  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_array_msg,
91  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_array_msg)
92  {
93  boost::mutex::scoped_lock lock(mutex_);
94  vital_checker_->poke();
95 
96  size_t nr_cluster = polygon_array_msg->polygons.size();
97  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
98  pcl::fromROSMsg(*cloud_msg, *cloud);
99  // first convert to polygon instance
100  std::vector<pcl::ModelCoefficients::Ptr> all_coefficients
102  coefficients_array_msg->coefficients);
103  std::vector<pcl::PointIndices::Ptr> all_indices
104  = pcl_conversions::convertToPCLPointIndices(indices_msg->cluster_indices);
105  std::vector<pcl::PointCloud<PointT>::Ptr> all_clouds
106  = jsk_recognition_utils::convertToPointCloudArray<PointT>(cloud, all_indices);
107  std::vector<jsk_recognition_utils::Plane::Ptr> planes
108  = jsk_recognition_utils::convertToPlanes(all_coefficients);
109  // build connection map
111  for (size_t i = 0; i < nr_cluster; i++) {
112  connection_map[i] = std::vector<int>();
113  connection_map[i].push_back(i);
114  // build kdtree
115  pcl::KdTreeFLANN<PointT> kdtree;
116  pcl::PointCloud<PointT>::Ptr focused_cloud = all_clouds[i];
117  kdtree.setInputCloud(focused_cloud);
118  // look up near polygon
119  jsk_recognition_utils::Plane::Ptr focused_plane = planes[i];
120  for (size_t j = i + 1; j < nr_cluster; j++) {
121  jsk_recognition_utils::Plane::Ptr target_plane = planes[j];
122  if (focused_plane->angle(*target_plane) < connect_angular_threshold_) {
123  // second, check distance
124  bool is_near_enough = isNearPointCloud(kdtree, all_clouds[j], target_plane);
125  if (is_near_enough) {
126  connection_map[i].push_back(j);
127  }
128  }
129  }
130  }
131  std::vector<std::set<int> > cloud_sets;
132  jsk_recognition_utils::buildAllGroupsSetFromGraphMap(connection_map, cloud_sets);
133  // build new indices
134  std::vector<pcl::PointIndices::Ptr> new_indices;
135  std::vector<pcl::ModelCoefficients::Ptr> new_coefficients;
136  for (size_t i = 0; i < cloud_sets.size(); i++) {
137  pcl::PointIndices::Ptr new_one_indices (new pcl::PointIndices);
138  new_coefficients.push_back(all_coefficients[*cloud_sets[i].begin()]);
139  for (std::set<int>::iterator it = cloud_sets[i].begin();
140  it != cloud_sets[i].end();
141  ++it) {
142  new_one_indices = jsk_recognition_utils::addIndices(*new_one_indices, *all_indices[*it]);
143  }
144  if (new_one_indices->indices.size() > min_size_) {
145  new_indices.push_back(new_one_indices);
146  }
147  }
148 
149  // refinement
150  std::vector<pcl::ModelCoefficients::Ptr> new_refined_coefficients;
151  for (size_t i = 0; i < new_indices.size(); i++) {
152  pcl::ModelCoefficients::Ptr refined_coefficients
153  = refinement(cloud, new_indices[i], new_coefficients[i]);
154  new_refined_coefficients.push_back(refined_coefficients);
155  }
156 
157  // publish
158  jsk_recognition_msgs::ClusterPointIndices new_ros_indices;
159  jsk_recognition_msgs::ModelCoefficientsArray new_ros_coefficients;
160  jsk_recognition_msgs::PolygonArray new_ros_polygons;
161  new_ros_indices.header = cloud_msg->header;
162  new_ros_coefficients.header = cloud_msg->header;
163  new_ros_polygons.header = cloud_msg->header;
164  for (size_t i = 0; i < new_indices.size(); i++) {
166  = jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
167  cloud, new_indices[i], new_refined_coefficients[i]);
168  if (convex->area() > min_area_ && convex->area() < max_area_) {
169  geometry_msgs::PolygonStamped polygon;
170  polygon.polygon = convex->toROSMsg();
171  polygon.header = cloud_msg->header;
172  new_ros_polygons.polygons.push_back(polygon);
173  pcl_msgs::PointIndices ros_indices;
174  ros_indices.header = cloud_msg->header;
175  ros_indices.indices = new_indices[i]->indices;
176  new_ros_indices.cluster_indices.push_back(ros_indices);
177  pcl_msgs::ModelCoefficients ros_coefficients;
178  ros_coefficients.header = cloud_msg->header;
179  ros_coefficients.values = new_refined_coefficients[i]->values;
180  new_ros_coefficients.coefficients.push_back(ros_coefficients);
181  }
182  }
183 
184  // new_ros_indices.cluster_indices
185  // = pcl_conversions::convertToROSPointIndices(new_indices, cloud_msg->header);
186  // new_ros_coefficients.coefficients
187  // = pcl_conversions::convertToROSModelCoefficients(
188  // new_refined_coefficients, cloud_msg->header);
189 
190  pub_indices_.publish(new_ros_indices);
191  pub_polygon_.publish(new_ros_polygons);
192  pub_coefficients_.publish(new_ros_coefficients);
193  }
194 
195  pcl::ModelCoefficients::Ptr PlaneConcatenator::refinement(
196  pcl::PointCloud<PointT>::Ptr cloud,
197  pcl::PointIndices::Ptr indices,
198  pcl::ModelCoefficients::Ptr original_coefficients)
199  {
200  pcl::SACSegmentation<PointT> seg;
201  seg.setOptimizeCoefficients (true);
202  seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
203  seg.setMethodType (pcl::SAC_RANSAC);
204  seg.setDistanceThreshold (ransac_refinement_outlier_threshold_);
205 
206  seg.setInputCloud(cloud);
207 
208  seg.setIndices(indices);
209  seg.setMaxIterations (ransac_refinement_max_iteration_);
210  Eigen::Vector3f normal (original_coefficients->values[0],
211  original_coefficients->values[1],
212  original_coefficients->values[2]);
213  seg.setAxis(normal);
214  // seg.setInputNormals(cloud);
215  // seg.setDistanceFromOrigin(original_coefficients->values[3]);
216  // seg.setEpsDist(ransac_refinement_eps_distance_);
217  seg.setEpsAngle(ransac_refinement_eps_angle_);
218  pcl::PointIndices::Ptr refined_inliers (new pcl::PointIndices);
219  pcl::ModelCoefficients::Ptr refined_coefficients(new pcl::ModelCoefficients);
220  seg.segment(*refined_inliers, *refined_coefficients);
221  if (refined_inliers->indices.size() > 0) {
222  return refined_coefficients;
223  }
224  else {
225  return original_coefficients;
226  }
227  }
228 
230  pcl::KdTreeFLANN<PointT>& kdtree,
231  pcl::PointCloud<PointT>::Ptr cloud,
233  {
234  pcl::PointCloud<PointT>::ConstPtr input_cloud = kdtree.getInputCloud();
235  for (size_t i = 0; i < cloud->points.size(); i++) {
236  PointT p = cloud->points[i];
237  std::vector<int> k_indices;
238  std::vector<float> k_sqr_distances;
239  if (kdtree.radiusSearch(p, connect_distance_threshold_,
240  k_indices, k_sqr_distances, 1) > 0) {
241  // Decompose distance into pependicular distance and parallel distance
242  const PointT near_p = input_cloud->points[k_indices[0]];
243  Eigen::Affine3f plane_coordinates = target_plane->coordinates();
244  Eigen::Vector3f plane_local_p = plane_coordinates.inverse() * p.getVector3fMap();
245  Eigen::Vector3f plane_local_near_p = plane_coordinates.inverse() * near_p.getVector3fMap();
246  Eigen::Vector3f plane_local_diff = plane_local_near_p - plane_local_p;
247  double perpendicular_distance = std::abs(plane_local_diff[2]);
248  if (perpendicular_distance < connect_perpendicular_distance_threshold_) {
249  return true;
250  }
251  }
252  }
253  return false;
254  }
255 
257  Config &config, uint32_t level)
258  {
259  boost::mutex::scoped_lock lock(mutex_);
260  connect_angular_threshold_ = config.connect_angular_threshold;
261  connect_distance_threshold_ = config.connect_distance_threshold;
262  connect_perpendicular_distance_threshold_ = config.connect_perpendicular_distance_threshold;
263  ransac_refinement_max_iteration_ = config.ransac_refinement_max_iteration;
265  = config.ransac_refinement_outlier_threshold;
266  ransac_refinement_eps_angle_ = config.ransac_refinement_eps_angle;
267  min_size_ = config.min_size;
268  min_area_ = config.min_area;
269  max_area_ = config.max_area;
270  }
271 }
272 
f
std::vector< Plane::Ptr > convertToPlanes(std::vector< pcl::ModelCoefficients::Ptr >)
lock
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PlaneConcatenator, nodelet::Nodelet)
void publish(const boost::shared_ptr< M > &message) const
std::vector< pcl::ModelCoefficients::Ptr > convertToPCLModelCoefficients(const std::vector< PCLModelCoefficientMsg > &coefficients)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
std::map< int, std::vector< int > > IntegerGraphMap
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
boost::shared_ptr< ros::NodeHandle > pnh_
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
virtual bool isNearPointCloud(pcl::KdTreeFLANN< PointT > &kdtree, pcl::PointCloud< PointT >::Ptr cloud, jsk_recognition_utils::Plane::Ptr target_plane)
virtual void configCallback(Config &config, uint32_t level)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
virtual pcl::ModelCoefficients::Ptr refinement(pcl::PointCloud< PointT >::Ptr cloud, pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr original_coefficients)
void buildAllGroupsSetFromGraphMap(IntegerGraphMap graph_map, std::vector< std::set< int > > &output_sets)
virtual void concatenate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_array_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_array_msg)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
p
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15