edge_depth_refinement_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 
37 
38 #include <pcl/segmentation/sac_segmentation.h>
39 #include <pcl/filters/extract_indices.h>
40 #include <pcl/io/io.h>
42 #include <sstream>
43 
44 namespace jsk_pcl_ros
45 {
47  {
48  ConnectionBasedNodelet::onInit();
49 
51  // publishers
53  pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
54  *pnh_, "output", 1);
55  pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
56  *pnh_, "output_coefficients", 1);
57  pub_edges_ = advertise<jsk_recognition_msgs::SegmentArray>(
58  *pnh_, "output_edges", 1);
59  pub_outlier_removed_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
60  *pnh_, "output_outlier_removed", 1);
61  pub_outlier_removed_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
62  *pnh_, "output_outlier_removed_coefficients", 1);
63  pub_outlier_removed_edges_= advertise<jsk_recognition_msgs::SegmentArray>(
64  *pnh_, "output_outlier_removed_edges", 1);
66  // dynamic reconfigure
68  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
69  dynamic_reconfigure::Server<Config>::CallbackType f =
70  boost::bind (&EdgeDepthRefinement::configCallback, this, _1, _2);
71  srv_->setCallback (f);
72 
74  }
75 
77  {
79  // subscribesrs
81  sub_input_.subscribe(*pnh_, "input", 1);
82  sub_indices_.subscribe(*pnh_, "input_indices", 1);
83  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
84  sync_->connectInput(sub_input_, sub_indices_);
85  sync_->registerCallback(boost::bind(&EdgeDepthRefinement::refine,
86  this, _1, _2));
87  }
88 
90  {
93  }
94 
96  // line coefficients are:
97  // 0: point.x
98  // 1: point.y
99  // 2. point.z
100  // 3. direction.x
101  // 4: direction.y
102  // 5. direction.z
105  const pcl::ModelCoefficients::Ptr coefficients)
106  {
107  Eigen::Vector3f p(coefficients->values[0],
108  coefficients->values[1],
109  coefficients->values[2]);
110  Eigen::Vector3f d(coefficients->values[3],
111  coefficients->values[4],
112  coefficients->values[5]);
114  return ret;
115  }
116 
117  boost::tuple<int, int> EdgeDepthRefinement::findMinMaxIndex(
118  const int width, const int height,
119  const std::vector<int>& indices)
120  {
121 
122  int min_y_index, max_y_index, min_x_index, max_x_index;
123  int min_y = INT_MAX;
124  int min_x = INT_MAX;
125  int max_y = INT_MIN;
126  int max_x = INT_MIN;
127  for (size_t i = 0; i < indices.size(); i++) {
128  int index = indices[i];
129  int x = index % width;
130  int y = index / width;
131 
132  if (x > max_x) {
133  max_x = x;
134  max_x_index = index;
135  }
136  if (x < min_x) {
137  min_x = x;
138  min_x_index = index;
139  }
140  if (y > max_y) {
141  max_y = y;
142  max_y_index = index;
143  }
144  if (y < min_y) {
145  min_y = y;
146  min_y_index = index;
147  }
148  }
149 
150  if (min_x_index != max_x_index) {
151  return boost::make_tuple(
152  min_x_index, max_x_index);
153  }
154  else {
155  return boost::make_tuple(
156  min_y_index, max_y_index);
157  }
158  }
159 
160 
162  const pcl::PointCloud<PointT>::Ptr& cloud,
163  const std::vector<int>& indices,
165  {
166  boost::tuple<int, int> min_max
167  = findMinMaxIndex(cloud->width, cloud->height, indices);
168  PointT min_point = cloud->points[min_max.get<0>()];
169  PointT max_point = cloud->points[min_max.get<1>()];
170  Eigen::Vector3f min_point_f = min_point.getVector3fMap();
171  Eigen::Vector3f max_point_f = max_point.getVector3fMap();
172  Eigen::Vector3f min_foot, max_foot;
173  line->foot(min_point_f, min_foot);
174  line->foot(max_point_f, max_foot);
176  return segment;
177  }
178 
180  const pcl::PointCloud<PointT>::Ptr& cloud,
181  const std::set<int>& duplicated_set,
182  const std::vector<pcl::PointIndices::Ptr> all_inliers,
183  pcl::PointIndices::Ptr& output_indices)
184  {
185  std::vector<int> integrated_indices;
186  for (std::set<int>::iterator it = duplicated_set.begin();
187  it != duplicated_set.end();
188  ++it) {
189  integrated_indices = jsk_recognition_utils::addIndices(all_inliers[*it]->indices,
190  integrated_indices);
191  }
192  output_indices->indices = integrated_indices;
193  }
194 
196  const pcl::PointCloud<PointT>::Ptr& cloud,
197  const std::vector<pcl::PointIndices::Ptr> all_inliers,
198  const std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
199  std::vector<pcl::PointIndices::Ptr>& output_inliers,
200  std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients)
201  {
202  if (all_inliers.size() == 0) {
203  NODELET_ERROR("no edges are specified");
204  return;
205  }
206 
207  // buildup Lines and Segments
208  std::vector<jsk_recognition_utils::Line::Ptr> lines;
209  std::vector<jsk_recognition_utils::Segment::Ptr> segments;
210 
211  for (size_t i = 0; i < all_inliers.size(); i++) {
212  pcl::PointIndices::Ptr the_inliers = all_inliers[i];
213  pcl::ModelCoefficients::Ptr the_coefficients = all_coefficients[i];
214  jsk_recognition_utils::Line::Ptr the_line = lineFromCoefficients(the_coefficients);
216  = segmentFromIndices(cloud, the_inliers->indices, the_line);
217  lines.push_back(the_line);
218  segments.push_back(the_segment);
219  }
220 
222  // build duplication map
223  // duplication map is a hash map from int to a list of int
225  std::map<int, std::vector<int> > duplication_map;
226  for (size_t i = 0; i < all_inliers.size() - 1; i++) {
227  duplication_map[i] = std::vector<int>(); // add empty map
228  jsk_recognition_utils::Line::Ptr the_line = lines[i];
229  jsk_recognition_utils::Segment::Ptr the_segment = segments[i];
230  for (size_t j = i + 1; j < all_inliers.size(); j++) {
231  jsk_recognition_utils::Line::Ptr candidate_line = lines[j];
232  jsk_recognition_utils::Segment::Ptr candidate_segment = segments[j];
233  Eigen::Vector3f candidate_midpoint;
234  candidate_segment->midpoint(candidate_midpoint);
235 
236  double angle_diff = the_line->angle(*candidate_line);
237  if (duplication_angle_threshold_ > angle_diff) {
238  double distance_diff = the_segment->distance(candidate_midpoint);
239  if (duplication_distance_threshold_ > distance_diff) {
240  duplication_map[i].push_back(j);
241  }
242  }
243  }
244  }
245 
247  // convert duplication map into set
249  std::vector<std::set<int> > duplication_set_list;
250  std::set<int> duplicated_indices;
251  for (size_t i = 0; i < all_inliers.size(); i++) {
252  std::vector<int> duplication_list;
253  if (i < all_inliers.size() - 1) {
254  duplication_list = duplication_map[i];
255  }
256  if (duplicated_indices.find(i) == duplicated_indices.end()) {
257  if (i == all_inliers.size() - 1 || duplication_list.size() == 0) { // no duplication found
258  std::set<int> no_duplication_set;
259  no_duplication_set.insert(i);
260  duplication_set_list.push_back(no_duplication_set);
261  jsk_recognition_utils::addSet<int>(duplicated_indices, no_duplication_set);
262  }
263  else { // some duplication found
264  std::set<int> new_duplication_set;
266  i,
267  duplication_list,
268  new_duplication_set);
269  duplication_set_list.push_back(new_duplication_set);
270  // add new_duplication_set to duplicated_indices
271  jsk_recognition_utils::addSet<int>(duplicated_indices, new_duplication_set);
272  }
273  }
274  }
275 
276 
277  for (size_t i = 0; i < duplication_set_list.size(); i++) {
278  pcl::PointIndices::Ptr integrated_indices (new pcl::PointIndices);
279  integrateDuplicatedIndices(cloud, duplication_set_list[i],
280  all_inliers,
281  integrated_indices);
282  output_inliers.push_back(integrated_indices);
283 
284  // use the first one,,, ok?
285  pcl::ModelCoefficients::Ptr integrated_coefficients
286  = all_coefficients[(*duplication_set_list[i].begin())];
287  output_coefficients.push_back(integrated_coefficients);
288  }
289 
290  // print result for debug
291  // NODELET_INFO("%lu duplication set", duplication_set_list.size());
292  // for (size_t i = 0; i < duplication_set_list.size(); i++) {
293  // std::stringstream ss;
294  // ss << "[";
295  // for (std::set<int>::iterator it = duplication_set_list[i].begin();
296  // it != duplication_set_list[i].end();
297  // ++it)
298  // {
299  // ss << *it << ", ";
300  // }
301  // NODELET_INFO("%s", ss.str().c_str());
302  // }
303 
304  // for (size_t i = 0; i < all_inliers.size() - 1; i++) {
305  // std::stringstream ss;
306  // std::vector<int> similar_indices = duplication_map[i];
307  // ss << i << " -> ";
308  // for (size_t j = 0; j < similar_indices.size(); j++) {
309  // ss << similar_indices[j] << ", ";
310  // }
311  // NODELET_INFO("%s", ss.str().c_str());
312  // }
313  }
314 
316  const pcl::PointCloud<PointT>::Ptr& cloud,
317  const std::vector<PCLIndicesMsg>& indices,
318  std::vector<pcl::PointIndices::Ptr>& output_inliers,
319  std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients)
320  {
321  // output_inliers.resize(indices.size());
322  // output_coefficients.resize(indices.size());
323  for (size_t i = 0; i < indices.size(); i++) {
324  std::vector<int> cluster_indices = indices[i].indices;
325  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
326  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
327  removeOutliersByLine(cloud, cluster_indices, *inliers, *coefficients);
328  if (inliers->indices.size() > min_inliers_) {
329  output_inliers.push_back(inliers);
330  output_coefficients.push_back(coefficients);
331  }
332  }
333  }
334 
336  const pcl::PointCloud<PointT>::Ptr& cloud,
337  const std::vector<int>& indices,
338  pcl::PointIndices& inliers,
339  pcl::ModelCoefficients& coefficients)
340  {
341  // one line shoud have ONE line at most...?
342  // in that case, we can estimate the true line by RANSAC
343  pcl::SACSegmentation<PointT> seg;
344  seg.setOptimizeCoefficients (true);
345  seg.setModelType (pcl::SACMODEL_LINE);
346  seg.setMethodType (pcl::SAC_RANSAC);
347  seg.setDistanceThreshold (outlier_distance_threshold_);
348  seg.setInputCloud(cloud);
349  pcl::PointIndices::Ptr indices_ptr (new pcl::PointIndices);
350  indices_ptr->indices = indices;
351  seg.setIndices(indices_ptr);
352  seg.segment (inliers, coefficients);
353  }
354 
357  ros::Publisher& pub_coefficients,
358  ros::Publisher& pub_edges,
359  const std::vector<pcl::PointIndices::Ptr> inliers,
360  const std::vector<pcl::ModelCoefficients::Ptr> coefficients,
361  const std_msgs::Header& header)
362  {
363  jsk_recognition_msgs::ClusterPointIndices output_ros_msg;
364  jsk_recognition_msgs::ModelCoefficientsArray output_ros_coefficients_msg;
365  jsk_recognition_msgs::SegmentArray output_ros_edges_msg;
366  output_ros_msg.header = header;
367  output_ros_coefficients_msg.header = header;
368  output_ros_edges_msg.header = header;
369  for (size_t i = 0; i < inliers.size(); i++) {
370  PCLIndicesMsg output_indices_msg;
371  PCLModelCoefficientMsg output_coefficients_msg;
372  jsk_recognition_msgs::Segment output_edge_msg;
373  output_indices_msg.header = header;
374  output_indices_msg.indices = inliers[i]->indices;
375  output_ros_msg.cluster_indices.push_back(output_indices_msg);
376 
377  output_coefficients_msg.header = header;
378  output_coefficients_msg.values = coefficients[i]->values;
379  output_ros_coefficients_msg.coefficients.push_back(output_coefficients_msg);
380 
381  output_edge_msg.start_point.x = coefficients[i]->values[0] - coefficients[i]->values[3];
382  output_edge_msg.start_point.y = coefficients[i]->values[1] - coefficients[i]->values[4];
383  output_edge_msg.start_point.z = coefficients[i]->values[2] - coefficients[i]->values[5];
384  output_edge_msg.end_point.x = coefficients[i]->values[0] + coefficients[i]->values[3];
385  output_edge_msg.end_point.y = coefficients[i]->values[1] + coefficients[i]->values[4];
386  output_edge_msg.end_point.z = coefficients[i]->values[2] + coefficients[i]->values[5];
387  output_ros_edges_msg.segments.push_back(output_edge_msg);
388  }
389  pub.publish(output_ros_msg);
390  pub_coefficients.publish(output_ros_coefficients_msg);
391  pub_edges.publish(output_ros_edges_msg);
392  }
393 
394  void EdgeDepthRefinement::configCallback (Config &config, uint32_t level)
395  {
396  boost::mutex::scoped_lock lock(mutex_);
397  outlier_distance_threshold_ = config.outlier_distance_threshold;
398  min_inliers_ = config.min_inliers;
399  duplication_angle_threshold_ = config.duplication_angle_threshold;
400  duplication_distance_threshold_ = config.duplication_distance_threshold;
401  }
402 
404  const sensor_msgs::PointCloud2ConstPtr &input,
405  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices)
406  {
407  boost::mutex::scoped_lock lock(mutex_);
408  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
409  pcl::fromROSMsg(*input, *cloud);
410 
411  std::vector<pcl::PointIndices::Ptr> inliers;
412  std::vector<pcl::ModelCoefficients::Ptr> coefficients;
413 
414  removeOutliers(cloud, indices->cluster_indices, inliers, coefficients);
415  std::vector<pcl::PointIndices::Ptr> non_duplicated_inliers;
416  std::vector<pcl::ModelCoefficients::Ptr> non_duplicated_coefficients;
417  removeDuplicatedEdges(cloud, inliers, coefficients,
418  non_duplicated_inliers,
419  non_duplicated_coefficients);
423  inliers, coefficients,
424  input->header);
427  pub_edges_,
428  non_duplicated_inliers,
429  non_duplicated_coefficients,
430  input->header);
431  }
432 
433 }
434 
list lines
d
virtual void removeDuplicatedEdges(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< pcl::PointIndices::Ptr > inliers, const std::vector< pcl::ModelCoefficients::Ptr > coefficients, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients)
#define NODELET_ERROR(...)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
virtual jsk_recognition_utils::Line::Ptr lineFromCoefficients(const pcl::ModelCoefficients::Ptr coefficients)
void publish(const boost::shared_ptr< M > &message) const
virtual boost::tuple< int, int > findMinMaxIndex(const int width, const int height, const std::vector< int > &indices)
virtual void removeOutliers(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< PCLIndicesMsg > &indices, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients)
coefficients
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
virtual void publishIndices(ros::Publisher &pub, ros::Publisher &pub_coefficients, ros::Publisher &pub_edges, const std::vector< pcl::PointIndices::Ptr > inliers, const std::vector< pcl::ModelCoefficients::Ptr > coefficients, const std_msgs::Header &header)
unsigned int index
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::EdgeDepthRefinement, nodelet::Nodelet)
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
virtual void removeOutliersByLine(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, pcl::PointIndices &inliers, pcl::ModelCoefficients &coefficients)
jsk_pcl_ros::EdgeDepthRefinementConfig Config
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)
void buildGroupFromGraphMap(IntegerGraphMap graph_map, const int from_index, std::vector< int > &to_indices, std::set< int > &output_set)
virtual void refine(const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices)
p
virtual void integrateDuplicatedIndices(const pcl::PointCloud< PointT >::Ptr &cloud, const std::set< int > &duplicated_set, const std::vector< pcl::PointIndices::Ptr > all_inliers, pcl::PointIndices::Ptr &output_indices)
pcl::PointIndices PCLIndicesMsg
cloud
pcl::ModelCoefficients PCLModelCoefficientMsg
virtual jsk_recognition_utils::Segment::Ptr segmentFromIndices(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const jsk_recognition_utils::Line::Ptr &line)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46