ppf_registration.h
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/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 
36 #ifndef JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_
37 #define JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_
38 
43 
48 #include <dynamic_reconfigure/server.h>
49 
50 #include <sensor_msgs/PointCloud2.h>
51 #include <jsk_recognition_msgs/PointsArray.h>
52 #include <geometry_msgs/PoseArray.h>
53 #include <geometry_msgs/Pose.h>
54 #include <pcl/features/ppf.h>
55 #include <pcl/features/normal_3d.h>
56 #include <pcl/registration/ppf_registration.h>
57 #include <jsk_pcl_ros/PPFRegistrationConfig.h>
58 
59 namespace jsk_pcl_ros
60 {
62  {
63  public:
65  sensor_msgs::PointCloud2,
66  jsk_recognition_msgs::PointsArray> ArraySyncPolicy;
68  sensor_msgs::PointCloud2,
69  jsk_recognition_msgs::PointsArray> ArrayApproximateSyncPolicy;
71  sensor_msgs::PointCloud2,
72  sensor_msgs::PointCloud2> CloudSyncPolicy;
74  sensor_msgs::PointCloud2,
75  sensor_msgs::PointCloud2> CloudApproximateSyncPolicy;
76  typedef jsk_pcl_ros::PPFRegistrationConfig Config;
77  PPFRegistration(): DiagnosticNodelet("PPFRegistration") {}
78  protected:
79  virtual void onInit();
80  virtual void subscribe();
81  virtual void unsubscribe();
82  virtual pcl::PointCloud<pcl::PointNormal>::Ptr calculateNormals (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
83  virtual void configCallback(Config &config, uint32_t level);
84  virtual void ArrayRegistration(
85  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
86  const jsk_recognition_msgs::PointsArray::ConstPtr& input_reference_points_array);
87  virtual void CloudRegistration(
88  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
89  const sensor_msgs::PointCloud2::ConstPtr& input_reference_cloud);
110 
111  pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals;
112  pcl::PointCloud<pcl::PointNormal>::Ptr reference_cloud_with_normals;
113  pcl::PPFEstimation<pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature> ppf_estimator;
114  pcl::PPFRegistration<pcl::PointNormal, pcl::PointNormal> ppf_registration;
115  private:
116 
117  };
118 }
119 
120 #endif
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_with_normals
virtual void configCallback(Config &config, uint32_t level)
virtual void CloudRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const sensor_msgs::PointCloud2::ConstPtr &input_reference_cloud)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray > ArraySyncPolicy
boost::shared_ptr< message_filters::Synchronizer< ArraySyncPolicy > > array_sync_
config
boost::shared_ptr< message_filters::Synchronizer< CloudSyncPolicy > > cloud_sync_
virtual void ArrayRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::PointsArray::ConstPtr &input_reference_points_array)
DiagnosticNodelet(const std::string &name)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > CloudSyncPolicy
jsk_pcl_ros::PPFRegistrationConfig Config
pcl::PPFEstimation< pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature > ppf_estimator
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_cloud_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray > ArrayApproximateSyncPolicy
boost::shared_ptr< message_filters::Synchronizer< CloudApproximateSyncPolicy > > cloud_async_
boost::mutex mutex
global mutex.
pcl::PointCloud< pcl::PointNormal >::Ptr cloud_with_normals
boost::shared_ptr< message_filters::Synchronizer< ArrayApproximateSyncPolicy > > array_async_
cloud
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > CloudApproximateSyncPolicy
message_filters::Subscriber< jsk_recognition_msgs::PointsArray > sub_reference_array_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
pcl::PPFRegistration< pcl::PointNormal, pcl::PointNormal > ppf_registration
virtual pcl::PointCloud< pcl::PointNormal >::Ptr calculateNormals(pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)


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