line_segment_detector_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  *********************************************************************/
37 #include <visualization_msgs/Marker.h>
38 #include <pcl/sample_consensus/method_types.h>
39 #include <pcl/sample_consensus/model_types.h>
40 #include <pcl/segmentation/sac_segmentation.h>
41 #include <pcl/filters/extract_indices.h>
43 
44 namespace jsk_pcl_ros
45 {
46 
48  pcl::PointIndices::Ptr indices,
49  pcl::ModelCoefficients::Ptr coefficients):
50  indices_(indices), coefficients_(coefficients)
51  {
52  }
53 
55  const std_msgs::Header& input_header,
56  pcl::PointIndices::Ptr indices,
57  pcl::ModelCoefficients::Ptr coefficients,
58  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud):
59  header(input_header),
60  indices_(indices), coefficients_(coefficients),
61  points_(new pcl::PointCloud<pcl::PointXYZ>),
62  raw_points_(new pcl::PointCloud<pcl::PointXYZ>)
63  {
64  pcl::ProjectInliers<pcl::PointXYZ> proj;
65  proj.setInputCloud(cloud);
66  proj.setIndices(indices);
67  proj.setModelType(pcl::SACMODEL_LINE);
68  proj.setModelCoefficients(coefficients);
69  proj.filter(*points_);
70  pcl::ExtractIndices<pcl::PointXYZ> ex;
71  ex.setInputCloud(cloud);
72  ex.setIndices(indices);
73  ex.filter(*raw_points_);
74  }
75 
77  {
78  }
79 
81  {
82  // we suppose the first and the last point should be the end points
83  // return Segment::Ptr(
84  // new Segment(
85  // points_->points[0].getVector3fMap(),
86  // points_->points[points_->points.size() - 1].getVector3fMap()));
87  Eigen::Vector3f direction;
88  direction[0] = coefficients_->values[3];
89  direction[1] = coefficients_->values[4];
90  direction[2] = coefficients_->values[5];
92  points_->points[0].getVector3fMap()));
93  // return Segment::Ptr(
94  // new Segment(
95  // points_->points[0].getVector3fMap(),
96  // points_->points[points_->points.size() - 1].getVector3fMap()));
97  }
98 
99 
101  visualization_msgs::Marker& marker,
102  const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
103  const double minimum_line_length)
104  {
105  // lookup minimum and max index
106  int min_index = INT_MAX;
107  int max_index = - INT_MAX;
108  for (size_t i = 0; i < indices_->indices.size(); i++) {
109  int index = indices_->indices[i];
110  if (min_index > index) {
111  min_index = index;
112  }
113  if (max_index < index) {
114  max_index = index;
115  }
116  }
117  geometry_msgs::Point a, b;
118  jsk_recognition_utils::pointFromXYZToXYZ<pcl::PointXYZ, geometry_msgs::Point>(
119  cloud->points[min_index], a);
120  jsk_recognition_utils::pointFromXYZToXYZ<pcl::PointXYZ, geometry_msgs::Point>(
121  cloud->points[max_index], b);
122  if (std::sqrt((a.x - b.x) * (a.x - b.x) +
123  (a.y - b.y) * (a.y - b.y) +
124  (a.z - b.z) * (a.z - b.z)) < minimum_line_length) {
125  return false;
126  }
127  marker.points.push_back(a);
128  marker.points.push_back(b);
129  return true;
130  }
131 
133  {
134  DiagnosticNodelet::onInit();
135 
136  pnh_->param("approximate_sync", approximate_sync_, false);
137 
138  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (config_mutex_, *pnh_);
139  dynamic_reconfigure::Server<Config>::CallbackType f =
140  boost::bind (&LineSegmentDetector::configCallback, this, _1, _2);
141  srv_->setCallback (f);
142 
144  // setup publishers
146  pub_line_marker_ = advertise<visualization_msgs::Marker>(
147  *pnh_, "debug/line_marker", 1);
148  pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
149  *pnh_, "output/inliers", 1);
150  pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
151  *pnh_, "output/coefficients", 1);
152 
153  onInitPostProcess();
154  }
155 
156  void LineSegmentDetector::configCallback(Config &config, uint32_t level)
157  {
158  boost::mutex::scoped_lock lock(mutex_);
159  outlier_threshold_ = config.outlier_threshold;
160  max_iterations_ = config.max_iterations;
161  min_indices_ = config.min_indices;
162  min_length_ = config.min_length;
163  line_width_ = config.line_width;
164 
165 
166  // update segmentation parameters
167  seg_.setOptimizeCoefficients (true);
168  seg_.setModelType(pcl::SACMODEL_LINE);
169  int segmentation_method;
170  {
171  boost::lock_guard<boost::recursive_mutex> lock(config_mutex_);
172  segmentation_method = config.method_type;
173  }
174  seg_.setMethodType(segmentation_method);
175  seg_.setDistanceThreshold (outlier_threshold_);
176  seg_.setMaxIterations (max_iterations_);
177  }
178 
180  {
181  sub_input_.subscribe(*pnh_, "input", 1);
182  sub_indices_.subscribe(*pnh_, "input_indices", 1);
183  if (approximate_sync_) {
184  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
185  async_->connectInput(sub_input_, sub_indices_);
186  async_->registerCallback(boost::bind(&LineSegmentDetector::segment,
187  this, _1, _2));
188  }
189  else {
190  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
191  sync_->connectInput(sub_input_, sub_indices_);
192  sync_->registerCallback(boost::bind(&LineSegmentDetector::segment,
193  this, _1, _2));
194  }
195  }
196 
198  {
199  sub_input_.unsubscribe();
200  sub_indices_.unsubscribe();
201  }
202 
204  const std_msgs::Header& header,
205  const pcl::PointCloud<PointT>::Ptr& cloud,
206  const std::vector<LineSegment::Ptr>& segments)
207  {
208  std::vector<pcl::PointIndices::Ptr> indices;
209  std::vector<pcl::ModelCoefficients::Ptr> coefficients;
210  visualization_msgs::Marker marker;
211  marker.header = header;
212  marker.pose.orientation.w = 1.0;
213  marker.scale.x = line_width_;
214  marker.type = visualization_msgs::Marker::LINE_LIST;
215  marker.color.a = 1.0;
216  marker.color.r = 1.0;
217  for (size_t i = 0; i < segments.size(); i++) {
218  if (segments[i]->addMarkerLine(marker, cloud, min_length_) == false)
219  continue;
220  indices.push_back(segments[i]->getIndices());
221  coefficients.push_back(segments[i]->getCoefficients());
222  std_msgs::ColorRGBA color = jsk_topic_tools::colorCategory20(i);
223  color.a = 1.0;
224  marker.colors.push_back(color);
225  marker.colors.push_back(color);
226  }
227 
228  jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
229  jsk_recognition_msgs::ClusterPointIndices ros_indices;
230  ros_coefficients.header = header;
231  ros_indices.header = header;
232  ros_coefficients.coefficients
234  coefficients, header);
235  ros_indices.cluster_indices
237  indices, header);
238  pub_indices_.publish(ros_indices);
239  pub_coefficients_.publish(ros_coefficients);
240  pub_line_marker_.publish(marker);
241  }
242 
244  const pcl::PointCloud<PointT>::Ptr& cloud,
245  const pcl::PointIndices::Ptr& indices,
246  std::vector<pcl::PointIndices::Ptr>& line_indices,
247  std::vector<pcl::ModelCoefficients::Ptr>& line_coefficients)
248  {
249  boost::mutex::scoped_lock lock(mutex_);
250  pcl::PointIndices::Ptr rest_indices (new pcl::PointIndices);
251  rest_indices->indices = indices->indices;
252  // use RANSAC to segment lines
253  seg_.setInputCloud(cloud);
254  while (true) {
255  if (rest_indices->indices.size() > min_indices_) {
256  pcl::PointIndices::Ptr
257  result_indices (new pcl::PointIndices);
258  pcl::ModelCoefficients::Ptr
259  result_coefficients (new pcl::ModelCoefficients);
260  seg_.setIndices(rest_indices);
261  seg_.segment(*result_indices, *result_coefficients);
262  if (result_indices->indices.size() > min_indices_) {
263  line_indices.push_back(result_indices);
264  line_coefficients.push_back(result_coefficients);
265  rest_indices = jsk_recognition_utils::subIndices(*rest_indices, *result_indices);
266  }
267  else {
268  break;
269  }
270  }
271  else {
272  break;
273  }
274  }
275 
276  }
277 
279  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
280  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_msg)
281  {
282  pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);
283  pcl::fromROSMsg(*cloud_msg, *cloud);
284  std::vector<LineSegment::Ptr> segments;
285  std::vector<pcl::PointIndices::Ptr> input_indices
286  = pcl_conversions::convertToPCLPointIndices(cluster_msg->cluster_indices);
287  // for each cluster
288  for (size_t i = 0; i < cluster_msg->cluster_indices.size(); i++) {
289  std::vector<pcl::PointIndices::Ptr> line_indices;
290  std::vector<pcl::ModelCoefficients::Ptr> line_coefficients;
291  segmentLines(cloud, input_indices[i],
292  line_indices, line_coefficients);
293  if (line_indices.size() > 0) {
294  // update lines
295  for (size_t j = 0; j < line_indices.size(); j++) {
296  segments.push_back(
297  LineSegment::Ptr(new LineSegment(line_indices[j],
298  line_coefficients[j])));
299  }
300  }
301  }
302  // publish result
303  publishResult(cloud_msg->header, cloud, segments);
304  }
305 
306 }
307 
pcl::PointCloud< pcl::PointXYZ >::Ptr points_
jsk_pcl_ros::LineSegmentDetectorConfig Config
std::vector< PCLModelCoefficientMsg > convertToROSModelCoefficients(const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std_msgs::Header &header)
coefficients
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< Line > Ptr
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
int min_index
virtual void publishResult(const std_msgs::Header &header, const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< LineSegment::Ptr > &segments)
sensor_msgs::PointCloud2 PointCloud
pcl::ModelCoefficients::Ptr coefficients_
unsigned int index
virtual jsk_recognition_utils::Line::Ptr toSegment()
pcl::PointCloud< pcl::PointXYZ >::Ptr raw_points_
int max_index
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::LineSegmentDetector, nodelet::Nodelet)
pcl::ModelCoefficients::Ptr getCoefficients()
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cluster_msg)
virtual void segmentLines(const pcl::PointCloud< PointT >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, std::vector< pcl::PointIndices::Ptr > &line_indices, std::vector< pcl::ModelCoefficients::Ptr > &line_coefficients)
pcl::PointIndices::Ptr getIndices()
pcl::PointIndices::Ptr indices_
std_msgs::ColorRGBA colorCategory20(int i)
virtual void configCallback(Config &config, uint32_t level)
virtual bool addMarkerLine(visualization_msgs::Marker &marker, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, double minimum_line_length)
LineSegment(const std_msgs::Header &input_header, pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr coefficients, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
boost::mutex mutex_
cloud
std::vector< int > subIndices(const std::vector< int > &a, const std::vector< int > &b)
char a[26]


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