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/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 #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);
66  onInitPostProcess();
67  }
68 
70  // message_filters::Synchronizer needs to be called reset
71  // before message_filters::Subscriber is freed.
72  // Calling reset fixes the following error on shutdown of the nodelet:
73  // terminate called after throwing an instance of
74  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
75  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
76  // Also see https://github.com/ros/ros_comm/issues/720 .
77  sync_.reset();
78  reference_sync_.reset();
79  }
80 
82  {
83  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
84  sub_input_.subscribe(*pnh_, "input", 1);
85  sub_input_feature_.subscribe(*pnh_, "input/feature", 1);
86  sync_->connectInput(
88  sync_->registerCallback(boost::bind(&FeatureRegistration::estimate,
89  this, _1, _2));
90  }
91 
93  {
96  }
97 
99  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
100  const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
101  {
102  boost::mutex::scoped_lock lock(mutex_);
103  NODELET_DEBUG("update reference");
104  reference_cloud_.reset(new pcl::PointCloud<pcl::PointNormal>);
105  reference_feature_.reset(new pcl::PointCloud<pcl::FPFHSignature33>);
106  pcl::fromROSMsg(*cloud_msg, *reference_cloud_);
107  pcl::fromROSMsg(*feature_msg, *reference_feature_);
108  }
109 
111  Config &config, uint32_t level)
112  {
113  boost::mutex::scoped_lock lock(mutex_);
114  max_iterations_ = config.max_iterations;
115  correspondence_randomness_ = config.correspondence_randomness;
116  similarity_threshold_ = config.similarity_threshold;
117  max_correspondence_distance_ = config.max_correspondence_distance;
118  inlier_fraction_ = config.inlier_fraction;
119  transformation_epsilon_ = config.transformation_epsilon;
120  }
121 
123  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
124  const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
125  {
126  boost::mutex::scoped_lock lock(mutex_);
128  NODELET_ERROR("Not yet reference data is available");
129  return;
130  }
131 
132  pcl::PointCloud<pcl::PointNormal>::Ptr
133  cloud (new pcl::PointCloud<pcl::PointNormal>);
134  pcl::PointCloud<pcl::PointNormal>::Ptr
135  object_aligned (new pcl::PointCloud<pcl::PointNormal>);
136  pcl::PointCloud<pcl::FPFHSignature33>::Ptr
137  feature (new pcl::PointCloud<pcl::FPFHSignature33>);
138  pcl::fromROSMsg(*cloud_msg, *cloud);
139  pcl::fromROSMsg(*feature_msg, *feature);
140 
141  pcl::SampleConsensusPrerejective<pcl::PointNormal,
142  pcl::PointNormal,
143  pcl::FPFHSignature33> align;
144 
145  align.setInputSource(reference_cloud_);
146  align.setSourceFeatures(reference_feature_);
147 
148  align.setInputTarget(cloud);
149  align.setTargetFeatures(feature);
150 
151  align.setMaximumIterations(max_iterations_); // Number of RANSAC iterations
152  align.setNumberOfSamples(3); // Number of points to sample for generating/prerejecting a pose
153  align.setCorrespondenceRandomness(correspondence_randomness_); // Number of nearest features to use
154  align.setSimilarityThreshold(similarity_threshold_); // Polygonal edge length similarity threshold
155  align.setMaxCorrespondenceDistance(max_correspondence_distance_); // Inlier threshold
156  align.setInlierFraction(inlier_fraction_); // Required inlier fraction for accepting a pose hypothesis
157  // Maximum allowable difference between two consecutive transformations
158  align.setTransformationEpsilon(transformation_epsilon_);
159  align.align (*object_aligned);
160 
161  if (align.hasConverged ())
162  {
163  // Print results
164  printf ("\n");
165  Eigen::Affine3f transformation(align.getFinalTransformation());
166  geometry_msgs::PoseStamped ros_pose;
167  tf::poseEigenToMsg(transformation, ros_pose.pose);
168  ros_pose.header = cloud_msg->header;
169  pub_pose_.publish(ros_pose);
170 
171  pcl::PointCloud<pcl::PointNormal>::Ptr
172  result_cloud (new pcl::PointCloud<pcl::PointNormal>);
173  pcl::transformPointCloud(
174  *reference_cloud_, *result_cloud, transformation);
175  sensor_msgs::PointCloud2 ros_cloud;
176  pcl::toROSMsg(*object_aligned, ros_cloud);
177  ros_cloud.header = cloud_msg->header;
178  pub_cloud_.publish(ros_cloud);
179 
180  //pcl::console::print_info ("Inliers: %i/%i\n", align.getInliers ().size (), object->size ());
181 
182  }
183  else {
184  NODELET_WARN("failed to align pointcloud");
185  }
186 
187  }
188 }
189 
NODELET_ERROR
#define NODELET_ERROR(...)
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
_2
boost::arg< 2 > _2
jsk_pcl_ros::FeatureRegistration::subscribe
virtual void subscribe()
Definition: feature_registration_nodelet.cpp:81
jsk_pcl_ros::FeatureRegistration::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: feature_registration_nodelet.cpp:110
jsk_pcl_ros::FeatureRegistration::unsubscribe
virtual void unsubscribe()
Definition: feature_registration_nodelet.cpp:92
jsk_pcl_ros::FeatureRegistration::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: feature_registration.h:154
jsk_pcl_ros::FeatureRegistration::similarity_threshold_
double similarity_threshold_
Definition: feature_registration.h:168
NODELET_WARN
#define NODELET_WARN(...)
jsk_pcl_ros::FeatureRegistration::reference_sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > reference_sync_
Definition: feature_registration.h:160
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::FeatureRegistration::sub_input_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_feature_
Definition: feature_registration.h:155
cloud
cloud
jsk_pcl_ros::FeatureRegistration::reference_cloud_
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_
Definition: feature_registration.h:163
class_list_macros.h
jsk_pcl_ros::FeatureRegistration::inlier_fraction_
double inlier_fraction_
Definition: feature_registration.h:170
jsk_pcl_ros::FeatureRegistration
Nodelet implementation of jsk_pcl/FeatureRegistration.
Definition: feature_registration.h:93
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::FeatureRegistration::onInit
virtual void onInit()
Definition: feature_registration_nodelet.cpp:46
eigen_msg.h
jsk_pcl_ros::FeatureRegistration::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: feature_registration.h:156
jsk_pcl_ros::FeatureRegistration::reference_feature_
pcl::PointCloud< pcl::FPFHSignature33 >::Ptr reference_feature_
Definition: feature_registration.h:164
_1
boost::arg< 1 > _1
jsk_pcl_ros::FeatureRegistration::sub_input_reference_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_feature_
Definition: feature_registration.h:159
tf::poseEigenToMsg
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
pcl_conversion_util.h
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros::FeatureRegistration::correspondence_randomness_
int correspondence_randomness_
Definition: feature_registration.h:167
jsk_pcl_ros::FeatureRegistration::transformation_epsilon_
double transformation_epsilon_
Definition: feature_registration.h:171
nodelet::Nodelet
jsk_pcl_ros::FeatureRegistration::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: feature_registration.h:152
jsk_pcl_ros::FeatureRegistration::mutex_
boost::mutex mutex_
Definition: feature_registration.h:149
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::FeatureRegistration::referenceCallback
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
Definition: feature_registration_nodelet.cpp:98
jsk_pcl_ros::FeatureRegistration::Config
FeatureRegistrationConfig Config
Definition: feature_registration.h:128
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::FeatureRegistration::~FeatureRegistration
virtual ~FeatureRegistration()
Definition: feature_registration_nodelet.cpp:69
feature_registration.h
jsk_pcl_ros::FeatureRegistration::max_iterations_
int max_iterations_
Definition: feature_registration.h:166
jsk_pcl_ros::FeatureRegistration::sub_input_reference_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_
Definition: feature_registration.h:158
jsk_pcl_ros::FeatureRegistration::estimate
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
Definition: feature_registration_nodelet.cpp:122
jsk_pcl_ros::FeatureRegistration::pub_pose_
ros::Publisher pub_pose_
Definition: feature_registration.h:150
config
config
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::FeatureRegistration, nodelet::Nodelet)
jsk_pcl_ros::FeatureRegistration::max_correspondence_distance_
double max_correspondence_distance_
Definition: feature_registration.h:169
jsk_pcl_ros::FeatureRegistration::pub_cloud_
ros::Publisher pub_cloud_
Definition: feature_registration.h:151
NODELET_DEBUG
#define NODELET_DEBUG(...)
pcl_conversions.h


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