parallel_edge_finder_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 
38 #include <jsk_recognition_msgs/ParallelEdgeArray.h>
39 
40 namespace jsk_pcl_ros
41 {
43  {
44  ConnectionBasedNodelet::onInit();
45 
47  // publishers
49  pub_ = advertise<jsk_recognition_msgs::ParallelEdgeArray>(*pnh_, "output_edges_groups", 1);
50  pub_clusters_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output_clusters", 1);
51 
53  // dynamic reconfigure
55  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
56  dynamic_reconfigure::Server<Config>::CallbackType f =
57  boost::bind (&ParallelEdgeFinder::configCallback, this, _1, _2);
58  srv_->setCallback (f);
60  }
61 
63  {
65  // subscription
67  sub_indices_.subscribe(*pnh_, "input_indices", 1);
68  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
69  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
70  sync_->connectInput(sub_indices_, sub_coefficients_);
71  sync_->registerCallback(boost::bind(&ParallelEdgeFinder::estimate,
72  this, _1, _2));
73  }
74 
76  {
79  }
80 
82  Config &config, uint32_t level)
83  {
84  boost::mutex::scoped_lock lock(mutex_);
85  angle_threshold_ = config.angular_threshold;
86  }
87 
89  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
90  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients)
91  {
92  boost::mutex::scoped_lock lock(mutex_);
94  // first, build Line instances
96  std::vector<jsk_recognition_utils::Line::Ptr> lines;
97  if (input_coefficients->coefficients.size() == 0) {
98  return;
99  }
100  for (size_t i = 0; i < input_coefficients->coefficients.size(); i++) {
101  std::vector<float> the_coefficients
102  = input_coefficients->coefficients[i].values;
103  lines.push_back(jsk_recognition_utils::Line::fromCoefficients(the_coefficients));
104  }
105 
106  std::map<int, std::vector<int> > parallel_map;
107  for (size_t i = 0; i < lines.size() - 1; i++) {
108  parallel_map[i] = std::vector<int>();
109  jsk_recognition_utils::Line::Ptr the_line = lines[i];
110  for (size_t j = i + 1; j < lines.size(); j++) {
111  jsk_recognition_utils::Line::Ptr candidate_line = lines[j];
112  if (the_line->isParallel(*candidate_line, angle_threshold_)) {
113  parallel_map[i].push_back(j);
114  }
115  }
116  }
117 
118  // build 'Group' recursively
119  // list of set of the indices of parallel edges
120  std::vector<std::set<int> > parallel_groups_list;
121 
122  // set of the indices which are already regarded as one of
123  // parallel edges
124  std::set<int> listed_indices;
125 
126  for (size_t i = 0; i < lines.size() - 1; i++) {
127  std::vector<int> parallel_indices = parallel_map[i];
128  if (listed_indices.find(i) == listed_indices.end()) {
129  if (parallel_indices.size() == 0) {
130  // nothing to do
131  }
132  else {
133  std::set<int> new_parallel_set;
135  i,
136  parallel_indices,
137  new_parallel_set);
138  parallel_groups_list.push_back(new_parallel_set);
139  jsk_recognition_utils::addSet(listed_indices, new_parallel_set);
140  }
141  }
142  }
143  // publish the result
144  publishResult(parallel_groups_list, input_indices, input_coefficients);
145  publishResultAsCluser(parallel_groups_list, input_indices,
146  input_coefficients);
147  }
148 
150  const std::vector<std::set<int> >& parallel_groups_list,
151  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
152  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients)
153  {
154  jsk_recognition_msgs::ParallelEdgeArray ros_output_msg;
155  ros_output_msg.header = input_indices->header;
156  for (size_t i = 0; i < parallel_groups_list.size(); i++) {
157  std::set<int> parallel_groups = parallel_groups_list[i];
158  jsk_recognition_msgs::ParallelEdge edge_group;
159  edge_group.header = input_indices->header;
160  for (std::set<int>::iterator it = parallel_groups.begin();
161  it != parallel_groups.end();
162  ++it) {
163  int the_index = *it;
164  std::vector<int> indices
165  = input_indices->cluster_indices[the_index].indices;
166  std::vector<float> coefficients
167  = input_coefficients->coefficients[the_index].values;
168  PCLIndicesMsg indices_msg;
169  indices_msg.header = input_indices->header;
170  indices_msg.indices = indices;
171  PCLModelCoefficientMsg coefficients_msg;
172  coefficients_msg.header = input_coefficients->header;
173  coefficients_msg.values = coefficients;
174  edge_group.cluster_indices.push_back(indices_msg);
175  edge_group.coefficients.push_back(coefficients_msg);
176  }
177  ros_output_msg.edge_groups.push_back(edge_group);
178  }
179  pub_.publish(ros_output_msg);
180  }
181 
183  const std::vector<std::set<int> >& parallel_groups_list,
184  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices,
185  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& input_coefficients)
186  {
187  jsk_recognition_msgs::ClusterPointIndices ros_output_msg;
188  ros_output_msg.header = input_indices->header;
189 
190  for (size_t i = 0; i < parallel_groups_list.size(); i++) {
191  std::set<int> parallel_groups = parallel_groups_list[i];
192  PCLIndicesMsg indices_msg;
193  indices_msg.header = input_indices->header;
194  for (std::set<int>::iterator it = parallel_groups.begin();
195  it != parallel_groups.end();
196  ++it) {
197  indices_msg.indices = jsk_recognition_utils::addIndices(
198  indices_msg.indices,
199  input_indices->cluster_indices[*it].indices);
200  }
201  ros_output_msg.cluster_indices.push_back(indices_msg);
202  }
203  pub_clusters_.publish(ros_output_msg);
204  }
205 
206 }
207 
210 
list lines
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
jsk_pcl_ros::ParallelEdgeFinderConfig Config
virtual void configCallback(Config &config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const
coefficients
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void publishResultAsCluser(const std::vector< std::set< int > > &parallel_groups_list, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)
boost::shared_ptr< ros::NodeHandle > pnh_
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
static Ptr fromCoefficients(const std::vector< float > &coefficients)
virtual void publishResult(const std::vector< std::set< int > > &parallel_groups_list, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
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)
void addSet(std::set< T > &output, const std::set< T > &new_set)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
pcl::PointIndices PCLIndicesMsg
pcl::ModelCoefficients PCLModelCoefficientMsg
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ParallelEdgeFinder, nodelet::Nodelet)
virtual void estimate(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &input_coefficients)


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