36 #define BOOST_PARAMETER_MAX_ARITY 7 
   38 #include <pcl/features/ppf.h> 
   39 #include <pcl/features/normal_3d.h> 
   40 #include <pcl/registration/ppf_registration.h> 
   47     DiagnosticNodelet::onInit();
 
   48     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   49     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   51     srv_->setCallback (
f);
 
   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);
 
  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);
 
  133     return cloud_calculated;
 
  147   (
const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
 
  148    const sensor_msgs::PointCloud2::ConstPtr& input_reference_cloud)
 
  150     pcl::PointCloud<pcl::PointXYZ>::Ptr 
cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
 
  154     cloud_with_normals = calculateNormals (
cloud);
 
  158     pcl::PointCloud<pcl::PointXYZ>::Ptr reference_cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
 
  162     reference_cloud_with_normals = calculateNormals (reference_cloud);
 
  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);
 
  171     pcl::PPFHashMapSearch::Ptr hashmap_search (
new pcl::PPFHashMapSearch (12.0
f / 180.0
f * 
float (
M_PI), 0.05
f));
 
  172     hashmap_search->setInputFeatureCloud (reference_cloud_ppf);
 
  176     ppf_registration.setSceneReferencePointSamplingRate (sampling_rate_);
 
  177     ppf_registration.setPositionClusteringThreshold (
float(position_clustering_threshold_));
 
  178     ppf_registration.setRotationClusteringThreshold (
float(rotation_clustering_threshold_) / 180.0
f * 
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);
 
  186     Eigen::Matrix4f mat = ppf_registration.getFinalTransformation ();
 
  187     Eigen::Affine3f 
pose (mat);
 
  189     Eigen::IOFormat CleanFmt(4, 0, 
", ", 
"\n", 
"[", 
"]");
 
  193     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_output (
new pcl::PointCloud<pcl::PointXYZ> ());
 
  194     pcl::transformPointCloud (*reference_cloud, *cloud_output, 
pose);
 
  197     sensor_msgs::PointCloud2 cloud_msg;
 
  199     geometry_msgs::Pose pose_msg_;
 
  200     geometry_msgs::PoseStamped pose_stamped_msg;
 
  202     pose_stamped_msg.pose = pose_msg_;
 
  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);
 
  212   (
const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
 
  213    const jsk_recognition_msgs::PointsArray::ConstPtr& input_reference_points_array)
 
  215     pcl::PointCloud<pcl::PointXYZ>::Ptr 
cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
 
  219     cloud_with_normals = calculateNormals (
cloud);
 
  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;
 
  228     for (
size_t reference_i=0; reference_i < input_reference_points_array->cloud_list.size(); reference_i++)
 
  230       sensor_msgs::PointCloud2 input_reference_cloud = input_reference_points_array->cloud_list[reference_i];
 
  233       pcl::PointCloud<pcl::PointXYZ>::Ptr reference_cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
 
  235       reference_cloud_vector.push_back(reference_cloud);
 
  238       reference_cloud_with_normals = calculateNormals (reference_cloud);
 
  239       reference_cloud_with_normals_vector.push_back(reference_cloud_with_normals);
 
  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);
 
  248       pcl::PPFHashMapSearch::Ptr hashmap_search (
new pcl::PPFHashMapSearch (12.0
f / 180.0
f * 
float (
M_PI), 0.05
f));
 
  249       hashmap_search->setInputFeatureCloud (reference_cloud_ppf);
 
  250       hashmap_search_vector.push_back(hashmap_search);
 
  254     for (
size_t reference_i=0; reference_i < input_reference_points_array->cloud_list.size(); reference_i++)
 
  257       ppf_registration.setSceneReferencePointSamplingRate (sampling_rate_);
 
  258       ppf_registration.setPositionClusteringThreshold (
float(position_clustering_threshold_));
 
  259       ppf_registration.setRotationClusteringThreshold (
float(rotation_clustering_threshold_) / 180.0
f * 
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);
 
  267       Eigen::Matrix4f mat = ppf_registration.getFinalTransformation ();
 
  268       Eigen::Affine3f 
pose (mat);
 
  270       Eigen::IOFormat CleanFmt(4, 0, 
", ", 
"\n", 
"[", 
"]");
 
  274       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_output (
new pcl::PointCloud<pcl::PointXYZ> ());
 
  275       pcl::transformPointCloud (*reference_cloud_vector[reference_i], *cloud_output, 
pose);
 
  278       sensor_msgs::PointCloud2 cloud_msg_;
 
  279       toROSMsg(*cloud_output, cloud_msg_);
 
  280       geometry_msgs::Pose pose_msg_;
 
  282       points_array_msg->cloud_list.push_back(cloud_msg_);
 
  283       pose_array_msg->poses.push_back(pose_msg_);
 
  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);