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>
48 DiagnosticNodelet::onInit();
50 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
53 srv_->setCallback (
f);
57 reference_sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
64 pub_pose_ = advertise<geometry_msgs::PoseStamped>(*pnh_,
"output", 1);
65 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output/cloud", 1);
83 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
99 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
100 const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
111 Config &config, uint32_t level)
123 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
124 const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
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>);
141 pcl::SampleConsensusPrerejective<pcl::PointNormal,
143 pcl::FPFHSignature33> align;
148 align.setInputTarget(
cloud);
149 align.setTargetFeatures(feature);
152 align.setNumberOfSamples(3);
159 align.align (*object_aligned);
161 if (align.hasConverged ())
165 Eigen::Affine3f transformation(align.getFinalTransformation());
166 geometry_msgs::PoseStamped ros_pose;
168 ros_pose.header = cloud_msg->header;
171 pcl::PointCloud<pcl::PointNormal>::Ptr
172 result_cloud (
new pcl::PointCloud<pcl::PointNormal>);
173 pcl::transformPointCloud(
175 sensor_msgs::PointCloud2 ros_cloud;
177 ros_cloud.header = cloud_msg->header;