ppf_registration_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, 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/or 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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
38 #include <pcl/features/ppf.h>
39 #include <pcl/features/normal_3d.h>
40 #include <pcl/registration/ppf_registration.h>
42 
43 namespace jsk_pcl_ros
44 {
46  {
47  DiagnosticNodelet::onInit();
48  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49  dynamic_reconfigure::Server<Config>::CallbackType f =
50  boost::bind (&PPFRegistration::configCallback, this, _1, _2);
51  srv_->setCallback (f);
52 
53  pub_points_array_ = advertise<jsk_recognition_msgs::PointsArray>(*pnh_, "output/points_array", 1);
54  pub_pose_array_ = advertise<geometry_msgs::PoseArray>(*pnh_, "output/pose_array", 1);
55  pub_pose_stamped_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output/pose_stamped", 1);
56  pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output/cloud", 1);
57  onInitPostProcess();
58  }
59 
61  // message_filters::Synchronizer needs to be called reset
62  // before message_filters::Subscriber is freed.
63  // Calling reset fixes the following error on shutdown of the nodelet:
64  // terminate called after throwing an instance of
65  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
66  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
67  // Also see https://github.com/ros/ros_comm/issues/720 .
68  array_sync_.reset();
69  cloud_sync_.reset();
70  array_async_.reset();
71  cloud_async_.reset();
72  }
73 
75  {
76  sub_input_.subscribe(*pnh_, "input/cloud", 1);
77  sub_reference_array_.subscribe(*pnh_, "input/reference_array", 1);
78  sub_reference_cloud_.subscribe(*pnh_, "input/reference_cloud", 1);
79  if (use_array_)
80  {
82  {
83  array_async_ = boost::make_shared<message_filters::Synchronizer<ArrayApproximateSyncPolicy> >(queue_size_);
85  array_async_->registerCallback(boost::bind(&PPFRegistration::ArrayRegistration, this, _1, _2));
86  }
87  else
88  {
89  array_sync_ = boost::make_shared<message_filters::Synchronizer<ArraySyncPolicy> >(queue_size_);
91  array_sync_->registerCallback(boost::bind(&PPFRegistration::ArrayRegistration, this, _1, _2));
92  }
93  }
94  else
95  {
97  {
98  cloud_async_ = boost::make_shared<message_filters::Synchronizer<CloudApproximateSyncPolicy> >(queue_size_);
100  cloud_async_->registerCallback(boost::bind(&PPFRegistration::CloudRegistration, this, _1, _2));
101  }
102  else
103  {
104  cloud_sync_ = boost::make_shared<message_filters::Synchronizer<CloudSyncPolicy> >(queue_size_);
106  cloud_sync_->registerCallback(boost::bind(&PPFRegistration::CloudRegistration, this, _1, _2));
107  }
108  }
109  }
110 
112  {
116  }
117 
118  pcl::PointCloud<pcl::PointNormal>::Ptr PPFRegistration::calculateNormals (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
119  {
120  float normal_estimation_search_radius = float(search_radius_);
121  pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal> ());
122  pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> normal_estimation_filter;
123  pcl::search::KdTree<pcl::PointXYZ>::Ptr search_tree (new pcl::search::KdTree<pcl::PointXYZ> ());
124  pcl::PointCloud<pcl::PointNormal>::Ptr cloud_calculated (new pcl::PointCloud<pcl::PointNormal> ());
125  normal_estimation_filter.setInputCloud (cloud);
126  normal_estimation_filter.setSearchMethod (search_tree);
127  normal_estimation_filter.setRadiusSearch (normal_estimation_search_radius);
128  normal_estimation_filter.compute (*cloud_normals);
129  pcl::concatenateFields (*cloud, *cloud_normals, *cloud_calculated);
130 
131  // DEBUG
132  NODELET_INFO_STREAM("cloud with normals size:" << cloud_calculated->points.size());
133  return cloud_calculated;
134  }
135 
136  void PPFRegistration::configCallback(Config &config, uint32_t level)
137  {
138  boost::mutex::scoped_lock lock(mutex_);
139  use_array_ = config.use_array;
140  queue_size_ = config.queue_size;
141  approximate_sync_ = config.approximate_sync;
142  search_radius_ = config.search_radius;
143  sampling_rate_ = config.sampling_rate;
144  }
145 
147  (const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
148  const sensor_msgs::PointCloud2::ConstPtr& input_reference_cloud)
149  {
150  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ> ());
151  pcl::fromROSMsg(*input_cloud, *cloud);
152 
153  //calculate normals for target
154  cloud_with_normals = calculateNormals (cloud);
155 
156  // training from reference
157  // convert from ROSMsg -> pcl PointCloud
158  pcl::PointCloud<pcl::PointXYZ>::Ptr reference_cloud (new pcl::PointCloud<pcl::PointXYZ> ());
159  pcl::fromROSMsg(*input_reference_cloud, *reference_cloud);
160 
161  // calculate normal for reference
162  reference_cloud_with_normals = calculateNormals (reference_cloud);
163 
164  // ppf estimation registration
165  pcl::PointCloud<pcl::PPFSignature>::Ptr reference_cloud_ppf (new pcl::PointCloud<pcl::PPFSignature> ());
166  ppf_estimator.setInputCloud (reference_cloud_with_normals);
167  ppf_estimator.setInputNormals (reference_cloud_with_normals);
168  ppf_estimator.compute (*reference_cloud_ppf);
169 
170  // hashmap search
171  pcl::PPFHashMapSearch::Ptr hashmap_search (new pcl::PPFHashMapSearch (12.0f / 180.0f * float (M_PI), 0.05f));
172  hashmap_search->setInputFeatureCloud (reference_cloud_ppf);
173 
174  // register references to target
175  // set parameters for the PPF registration procedure
176  ppf_registration.setSceneReferencePointSamplingRate (sampling_rate_);
177  ppf_registration.setPositionClusteringThreshold (float(position_clustering_threshold_));
178  ppf_registration.setRotationClusteringThreshold (float(rotation_clustering_threshold_) / 180.0f * float (M_PI));
179  ppf_registration.setSearchMethod (hashmap_search);
180  ppf_registration.setInputSource (reference_cloud_with_normals);
181  ppf_registration.setInputTarget (cloud_with_normals);
182  pcl::PointCloud<pcl::PointNormal> cloud_output_subsampled;
183  ppf_registration.align (cloud_output_subsampled);
184 
185  // get ppf transformation
186  Eigen::Matrix4f mat = ppf_registration.getFinalTransformation ();
187  Eigen::Affine3f pose (mat);
188  // DEBUG
189  Eigen::IOFormat CleanFmt(4, 0, ", ", "\n", "[", "]");
190  NODELET_INFO_STREAM( "Matrix:\n" << mat.format(CleanFmt));
191 
192  // transform reference
193  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_output (new pcl::PointCloud<pcl::PointXYZ> ());
194  pcl::transformPointCloud (*reference_cloud, *cloud_output, pose);
195 
196  //convert pcl to ROSMsg
197  sensor_msgs::PointCloud2 cloud_msg;
198  toROSMsg(*cloud_output, cloud_msg);
199  geometry_msgs::Pose pose_msg_;
200  geometry_msgs::PoseStamped pose_stamped_msg;
201  tf::poseEigenToMsg(pose, pose_msg_);
202  pose_stamped_msg.pose = pose_msg_;
203 
204  // publish
205  pose_stamped_msg.header = input_cloud->header;
206  cloud_msg.header = input_cloud->header;
207  pub_pose_stamped_.publish(pose_stamped_msg);
208  pub_cloud_.publish(cloud_msg);
209  }
210 
212  (const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
213  const jsk_recognition_msgs::PointsArray::ConstPtr& input_reference_points_array)
214  {
215  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ> ());
216  pcl::fromROSMsg(*input_cloud, *cloud);
217 
218  //calculate normals for target
219  cloud_with_normals = calculateNormals (cloud);
220 
221  jsk_recognition_msgs::PointsArray::Ptr points_array_msg (new jsk_recognition_msgs::PointsArray ());
222  geometry_msgs::PoseArray::Ptr pose_array_msg (new geometry_msgs::PoseArray ());
223  std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > reference_cloud_vector;
224  std::vector<pcl::PointCloud<pcl::PointNormal>::Ptr > reference_cloud_with_normals_vector;
225  std::vector<pcl::PPFHashMapSearch::Ptr > hashmap_search_vector;
226 
227  // training from reference
228  for (size_t reference_i=0; reference_i < input_reference_points_array->cloud_list.size(); reference_i++)
229  {
230  sensor_msgs::PointCloud2 input_reference_cloud = input_reference_points_array->cloud_list[reference_i];
231 
232  // convert from ROSMsg -> pcl PointCloud
233  pcl::PointCloud<pcl::PointXYZ>::Ptr reference_cloud (new pcl::PointCloud<pcl::PointXYZ> ());
234  pcl::fromROSMsg(input_reference_cloud, *reference_cloud);
235  reference_cloud_vector.push_back(reference_cloud);
236 
237  // calculate normal for reference
238  reference_cloud_with_normals = calculateNormals (reference_cloud);
239  reference_cloud_with_normals_vector.push_back(reference_cloud_with_normals);
240 
241  // ppf estimation registration
242  pcl::PointCloud<pcl::PPFSignature>::Ptr reference_cloud_ppf (new pcl::PointCloud<pcl::PPFSignature> ());
243  ppf_estimator.setInputCloud (reference_cloud_with_normals);
244  ppf_estimator.setInputNormals (reference_cloud_with_normals);
245  ppf_estimator.compute (*reference_cloud_ppf);
246 
247  // hashmap search
248  pcl::PPFHashMapSearch::Ptr hashmap_search (new pcl::PPFHashMapSearch (12.0f / 180.0f * float (M_PI), 0.05f));
249  hashmap_search->setInputFeatureCloud (reference_cloud_ppf);
250  hashmap_search_vector.push_back(hashmap_search);
251  }
252 
253  // register references to target
254  for (size_t reference_i=0; reference_i < input_reference_points_array->cloud_list.size(); reference_i++)
255  {
256  // set parameters for the PPF registration procedure
257  ppf_registration.setSceneReferencePointSamplingRate (sampling_rate_);
258  ppf_registration.setPositionClusteringThreshold (float(position_clustering_threshold_));
259  ppf_registration.setRotationClusteringThreshold (float(rotation_clustering_threshold_) / 180.0f * float (M_PI));
260  ppf_registration.setSearchMethod (hashmap_search_vector[reference_i]);
261  ppf_registration.setInputSource (reference_cloud_with_normals_vector[reference_i]);
262  ppf_registration.setInputTarget (cloud_with_normals);
263  pcl::PointCloud<pcl::PointNormal> cloud_output_subsampled;
264  ppf_registration.align (cloud_output_subsampled);
265 
266  // get ppf transformation
267  Eigen::Matrix4f mat = ppf_registration.getFinalTransformation ();
268  Eigen::Affine3f pose (mat);
269  // DEBUG
270  Eigen::IOFormat CleanFmt(4, 0, ", ", "\n", "[", "]");
271  NODELET_INFO_STREAM( "Matrix:\n" << mat.format(CleanFmt));
272 
273  // transform reference
274  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_output (new pcl::PointCloud<pcl::PointXYZ> ());
275  pcl::transformPointCloud (*reference_cloud_vector[reference_i], *cloud_output, pose);
276 
277  //convert pcl to ROSMsg
278  sensor_msgs::PointCloud2 cloud_msg_;
279  toROSMsg(*cloud_output, cloud_msg_);
280  geometry_msgs::Pose pose_msg_;
281  tf::poseEigenToMsg(pose, pose_msg_);
282  points_array_msg->cloud_list.push_back(cloud_msg_);
283  pose_array_msg->poses.push_back(pose_msg_);
284  }
285  // publish
286  pose_array_msg->header = input_cloud->header;
287  points_array_msg->header = input_cloud->header;
288  pub_pose_array_.publish(pose_array_msg);
289  pub_points_array_.publish(points_array_msg);
290  }
291 }
292 
jsk_pcl_ros::PPFRegistration::queue_size_
int queue_size_
Definition: ppf_registration.h:165
jsk_pcl_ros::PPFRegistration::mutex_
boost::mutex mutex_
Definition: ppf_registration.h:159
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
_2
boost::arg< 2 > _2
jsk_pcl_ros::PPFRegistration::approximate_sync_
bool approximate_sync_
Definition: ppf_registration.h:164
jsk_pcl_ros::PPFRegistration::sub_reference_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_cloud_
Definition: ppf_registration.h:157
M_PI
#define M_PI
jsk_pcl_ros::PPFRegistration::array_sync_
boost::shared_ptr< message_filters::Synchronizer< ArraySyncPolicy > > array_sync_
Definition: ppf_registration.h:160
ppf_registration.h
jsk_pcl_ros::PPFRegistration::sampling_rate_
int sampling_rate_
Definition: ppf_registration.h:167
jsk_pcl_ros::PPFRegistration::CloudRegistration
virtual void CloudRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const sensor_msgs::PointCloud2::ConstPtr &input_reference_cloud)
Definition: ppf_registration_nodelet.cpp:147
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros::PPFRegistration::ArrayRegistration
virtual void ArrayRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::PointsArray::ConstPtr &input_reference_points_array)
Definition: ppf_registration_nodelet.cpp:212
jsk_pcl_ros::PPFRegistration::pub_pose_array_
ros::Publisher pub_pose_array_
Definition: ppf_registration.h:171
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::PPFRegistration::pub_pose_stamped_
ros::Publisher pub_pose_stamped_
Definition: ppf_registration.h:173
cloud
cloud
pose
pose
class_list_macros.h
jsk_pcl_ros::PPFRegistration::sub_reference_array_
message_filters::Subscriber< jsk_recognition_msgs::PointsArray > sub_reference_array_
Definition: ppf_registration.h:158
jsk_pcl_ros::PPFRegistration::~PPFRegistration
virtual ~PPFRegistration()
Definition: ppf_registration_nodelet.cpp:60
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::PPFRegistration::cloud_async_
boost::shared_ptr< message_filters::Synchronizer< CloudApproximateSyncPolicy > > cloud_async_
Definition: ppf_registration.h:163
pcl::concatenateFields
void concatenateFields(PointCloud< PointXYZ > &cloud_xyz, PointCloud< RGB > &cloud_rgb, PointCloud< PointXYZRGB > &cloud)
Definition: kinfu_nodelet.cpp:58
jsk_pcl_ros::PPFRegistration::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: ppf_registration.h:155
_1
boost::arg< 1 > _1
tf::poseEigenToMsg
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
jsk_pcl_ros::PPFRegistration::search_radius_
double search_radius_
Definition: ppf_registration.h:166
jsk_pcl_ros::PPFRegistration::subscribe
virtual void subscribe()
Definition: ppf_registration_nodelet.cpp:74
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros::PPFRegistration::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: ppf_registration.h:156
jsk_pcl_ros::PPFRegistration::onInit
virtual void onInit()
Definition: ppf_registration_nodelet.cpp:45
jsk_pcl_ros::PPFRegistration::pub_points_array_
ros::Publisher pub_points_array_
Definition: ppf_registration.h:172
nodelet::Nodelet
jsk_pcl_ros::PPFRegistration::Config
jsk_pcl_ros::PPFRegistrationConfig Config
Definition: ppf_registration.h:140
dump_depth_error.f
f
Definition: dump_depth_error.py:39
toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::PPFRegistration::pub_cloud_
ros::Publisher pub_cloud_
Definition: ppf_registration.h:174
jsk_pcl_ros::PPFRegistration
Definition: ppf_registration.h:93
jsk_pcl_ros::PPFRegistration::array_async_
boost::shared_ptr< message_filters::Synchronizer< ArrayApproximateSyncPolicy > > array_async_
Definition: ppf_registration.h:161
NODELET_INFO_STREAM
#define NODELET_INFO_STREAM(...)
config
config
jsk_pcl_ros::PPFRegistration::cloud_sync_
boost::shared_ptr< message_filters::Synchronizer< CloudSyncPolicy > > cloud_sync_
Definition: ppf_registration.h:162
jsk_pcl_ros::PPFRegistration::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: ppf_registration_nodelet.cpp:136
jsk_pcl_ros::PPFRegistration::use_array_
bool use_array_
Definition: ppf_registration.h:168
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PPFRegistration, nodelet::Nodelet)
jsk_pcl_ros::PPFRegistration::unsubscribe
virtual void unsubscribe()
Definition: ppf_registration_nodelet.cpp:111
jsk_pcl_ros::PPFRegistration::calculateNormals
virtual pcl::PointCloud< pcl::PointNormal >::Ptr calculateNormals(pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
Definition: ppf_registration_nodelet.cpp:118


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45