feature_registration_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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/registration/sample_consensus_prerejective.h>
38 #include <pcl/segmentation/sac_segmentation.h>
39 #include <pcl/features/fpfh_omp.h>
43 
44 namespace jsk_pcl_ros
45 {
47  {
48  DiagnosticNodelet::onInit();
49 
50  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51  typename dynamic_reconfigure::Server<Config>::CallbackType f =
52  boost::bind (&FeatureRegistration::configCallback, this, _1, _2);
53  srv_->setCallback (f);
54 
55 
56  // subscribe reference always
57  reference_sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
58  sub_input_reference_.subscribe(*pnh_, "input/reference/cloud", 1);
59  sub_input_reference_feature_.subscribe(*pnh_, "input/reference/feature", 1);
60  reference_sync_->connectInput(
62  reference_sync_->registerCallback(boost::bind(&FeatureRegistration::referenceCallback,
63  this, _1, _2));
64  pub_pose_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output", 1);
65  pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output/cloud", 1);
67  }
68 
70  {
71  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
72  sub_input_.subscribe(*pnh_, "input", 1);
73  sub_input_feature_.subscribe(*pnh_, "input/feature", 1);
74  sync_->connectInput(
76  sync_->registerCallback(boost::bind(&FeatureRegistration::estimate,
77  this, _1, _2));
78  }
79 
81  {
84  }
85 
87  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
88  const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
89  {
90  boost::mutex::scoped_lock lock(mutex_);
91  NODELET_DEBUG("update reference");
92  reference_cloud_.reset(new pcl::PointCloud<pcl::PointNormal>);
93  reference_feature_.reset(new pcl::PointCloud<pcl::FPFHSignature33>);
94  pcl::fromROSMsg(*cloud_msg, *reference_cloud_);
95  pcl::fromROSMsg(*feature_msg, *reference_feature_);
96  }
97 
99  Config &config, uint32_t level)
100  {
101  boost::mutex::scoped_lock lock(mutex_);
102  max_iterations_ = config.max_iterations;
103  correspondence_randomness_ = config.correspondence_randomness;
104  similarity_threshold_ = config.similarity_threshold;
105  max_correspondence_distance_ = config.max_correspondence_distance;
106  inlier_fraction_ = config.inlier_fraction;
107  transformation_epsilon_ = config.transformation_epsilon;
108  }
109 
111  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
112  const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
113  {
114  boost::mutex::scoped_lock lock(mutex_);
116  NODELET_ERROR("Not yet reference data is available");
117  return;
118  }
119 
120  pcl::PointCloud<pcl::PointNormal>::Ptr
121  cloud (new pcl::PointCloud<pcl::PointNormal>);
122  pcl::PointCloud<pcl::PointNormal>::Ptr
123  object_aligned (new pcl::PointCloud<pcl::PointNormal>);
124  pcl::PointCloud<pcl::FPFHSignature33>::Ptr
125  feature (new pcl::PointCloud<pcl::FPFHSignature33>);
126  pcl::fromROSMsg(*cloud_msg, *cloud);
127  pcl::fromROSMsg(*feature_msg, *feature);
128 
129  pcl::SampleConsensusPrerejective<pcl::PointNormal,
130  pcl::PointNormal,
131  pcl::FPFHSignature33> align;
132 
133  align.setInputSource(reference_cloud_);
134  align.setSourceFeatures(reference_feature_);
135 
136  align.setInputTarget(cloud);
137  align.setTargetFeatures(feature);
138 
139  align.setMaximumIterations(max_iterations_); // Number of RANSAC iterations
140  align.setNumberOfSamples(3); // Number of points to sample for generating/prerejecting a pose
141  align.setCorrespondenceRandomness(correspondence_randomness_); // Number of nearest features to use
142  align.setSimilarityThreshold(similarity_threshold_); // Polygonal edge length similarity threshold
143  align.setMaxCorrespondenceDistance(max_correspondence_distance_); // Inlier threshold
144  align.setInlierFraction(inlier_fraction_); // Required inlier fraction for accepting a pose hypothesis
145  // Maximum allowable difference between two consecutive transformations
146  align.setTransformationEpsilon(transformation_epsilon_);
147  align.align (*object_aligned);
148 
149  if (align.hasConverged ())
150  {
151  // Print results
152  printf ("\n");
153  Eigen::Affine3f transformation(align.getFinalTransformation());
154  geometry_msgs::PoseStamped ros_pose;
155  tf::poseEigenToMsg(transformation, ros_pose.pose);
156  ros_pose.header = cloud_msg->header;
157  pub_pose_.publish(ros_pose);
158 
159  pcl::PointCloud<pcl::PointNormal>::Ptr
160  result_cloud (new pcl::PointCloud<pcl::PointNormal>);
161  pcl::transformPointCloud(
162  *reference_cloud_, *result_cloud, transformation);
163  sensor_msgs::PointCloud2 ros_cloud;
164  pcl::toROSMsg(*object_aligned, ros_cloud);
165  ros_cloud.header = cloud_msg->header;
166  pub_cloud_.publish(ros_cloud);
167 
168  //pcl::console::print_info ("Inliers: %i/%i\n", align.getInliers ().size (), object->size ());
169 
170  }
171  else {
172  NODELET_WARN("failed to align pointcloud");
173  }
174 
175  }
176 }
177 
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > reference_sync_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_feature_
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_
boost::shared_ptr< ros::NodeHandle > pnh_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_feature_
FeatureRegistrationConfig 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)
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::FeatureRegistration, nodelet::Nodelet)
cloud
pcl::PointCloud< pcl::FPFHSignature33 >::Ptr reference_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_
Nodelet implementation of jsk_pcl/FeatureRegistration.
#define NODELET_DEBUG(...)


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