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/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 
36 #ifndef JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_
37 #define JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_
38 
39 #include <jsk_topic_tools/diagnostic_nodelet.h>
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 {
61  class PPFRegistration: public jsk_topic_tools::DiagnosticNodelet
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  virtual ~PPFRegistration();
79  protected:
80  virtual void onInit();
81  virtual void subscribe();
82  virtual void unsubscribe();
83  virtual pcl::PointCloud<pcl::PointNormal>::Ptr calculateNormals (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
84  virtual void configCallback(Config &config, uint32_t level);
85  virtual void ArrayRegistration(
86  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
87  const jsk_recognition_msgs::PointsArray::ConstPtr& input_reference_points_array);
88  virtual void CloudRegistration(
89  const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
90  const sensor_msgs::PointCloud2::ConstPtr& input_reference_cloud);
100  bool approximate_sync_;
101  int queue_size_;
102  double search_radius_;
103  int sampling_rate_;
104  bool use_array_;
111 
112  pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals;
113  pcl::PointCloud<pcl::PointNormal>::Ptr reference_cloud_with_normals;
114  pcl::PPFEstimation<pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature> ppf_estimator;
115  pcl::PPFRegistration<pcl::PointNormal, pcl::PointNormal> ppf_registration;
116  private:
117 
118  };
119 }
120 
121 #endif
jsk_pcl_ros::PPFRegistration::queue_size_
int queue_size_
Definition: ppf_registration.h:165
jsk_pcl_ros::PPFRegistration::reference_cloud_with_normals
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_with_normals
Definition: ppf_registration.h:177
jsk_pcl_ros::PPFRegistration::rotation_clustering_threshold_
double rotation_clustering_threshold_
Definition: ppf_registration.h:170
jsk_pcl_ros::PPFRegistration::mutex_
boost::mutex mutex_
Definition: ppf_registration.h:159
jsk_pcl_ros::PPFRegistration::CloudApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > CloudApproximateSyncPolicy
Definition: ppf_registration.h:139
ros::Publisher
jsk_pcl_ros::PPFRegistration::position_clustering_threshold_
double position_clustering_threshold_
Definition: ppf_registration.h:169
boost::shared_ptr
jsk_pcl_ros::PPFRegistration::approximate_sync_
bool approximate_sync_
Definition: ppf_registration.h:164
jsk_pcl_ros::PPFRegistration::sub_reference_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_cloud_
Definition: ppf_registration.h:157
jsk_pcl_ros::PPFRegistration::array_sync_
boost::shared_ptr< message_filters::Synchronizer< ArraySyncPolicy > > array_sync_
Definition: ppf_registration.h:160
jsk_pcl_ros::PPFRegistration::sampling_rate_
int sampling_rate_
Definition: ppf_registration.h:167
geo_util.h
jsk_pcl_ros::PPFRegistration::CloudRegistration
virtual void CloudRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const sensor_msgs::PointCloud2::ConstPtr &input_reference_cloud)
Definition: ppf_registration_nodelet.cpp:147
time_synchronizer.h
jsk_pcl_ros::PPFRegistration::ArrayRegistration
virtual void ArrayRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::PointsArray::ConstPtr &input_reference_points_array)
Definition: ppf_registration_nodelet.cpp:212
jsk_pcl_ros::PPFRegistration::pub_pose_array_
ros::Publisher pub_pose_array_
Definition: ppf_registration.h:171
jsk_pcl_ros::PPFRegistration::pub_pose_stamped_
ros::Publisher pub_pose_stamped_
Definition: ppf_registration.h:173
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::PPFRegistration::sub_reference_array_
message_filters::Subscriber< jsk_recognition_msgs::PointsArray > sub_reference_array_
Definition: ppf_registration.h:158
jsk_pcl_ros::PPFRegistration::~PPFRegistration
virtual ~PPFRegistration()
Definition: ppf_registration_nodelet.cpp:60
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros
Definition: add_color_from_image.h:51
subscriber.h
jsk_pcl_ros::PPFRegistration::ppf_registration
pcl::PPFRegistration< pcl::PointNormal, pcl::PointNormal > ppf_registration
Definition: ppf_registration.h:179
jsk_pcl_ros::PPFRegistration::cloud_async_
boost::shared_ptr< message_filters::Synchronizer< CloudApproximateSyncPolicy > > cloud_async_
Definition: ppf_registration.h:163
jsk_pcl_ros::PPFRegistration::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: ppf_registration.h:155
jsk_pcl_ros::PPFRegistration::search_radius_
double search_radius_
Definition: ppf_registration.h:166
jsk_pcl_ros::PPFRegistration::ArrayApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray > ArrayApproximateSyncPolicy
Definition: ppf_registration.h:133
pcl_conversion_util.h
jsk_pcl_ros::PPFRegistration::subscribe
virtual void subscribe()
Definition: ppf_registration_nodelet.cpp:74
jsk_pcl_ros::PPFRegistration::ppf_estimator
pcl::PPFEstimation< pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature > ppf_estimator
Definition: ppf_registration.h:178
jsk_pcl_ros::PPFRegistration::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: ppf_registration.h:156
jsk_pcl_ros::PPFRegistration::onInit
virtual void onInit()
Definition: ppf_registration_nodelet.cpp:45
jsk_pcl_ros::PPFRegistration::pub_points_array_
ros::Publisher pub_points_array_
Definition: ppf_registration.h:172
jsk_pcl_ros::PPFRegistration::CloudSyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > CloudSyncPolicy
Definition: ppf_registration.h:136
jsk_pcl_ros::PPFRegistration::Config
jsk_pcl_ros::PPFRegistrationConfig Config
Definition: ppf_registration.h:140
jsk_pcl_ros::PPFRegistration::ArraySyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PointsArray > ArraySyncPolicy
Definition: ppf_registration.h:130
pcl_util.h
synchronizer.h
jsk_pcl_ros::PPFRegistration::PPFRegistration
PPFRegistration()
Definition: ppf_registration.h:141
approximate_time.h
jsk_pcl_ros::PPFRegistration::pub_cloud_
ros::Publisher pub_cloud_
Definition: ppf_registration.h:174
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::PPFRegistration::array_async_
boost::shared_ptr< message_filters::Synchronizer< ArrayApproximateSyncPolicy > > array_async_
Definition: ppf_registration.h:161
message_filters::sync_policies::ExactTime
jsk_pcl_ros::PPFRegistration::cloud_with_normals
pcl::PointCloud< pcl::PointNormal >::Ptr cloud_with_normals
Definition: ppf_registration.h:176
jsk_pcl_ros::PPFRegistration::cloud_sync_
boost::shared_ptr< message_filters::Synchronizer< CloudSyncPolicy > > cloud_sync_
Definition: ppf_registration.h:162
jsk_pcl_ros::PPFRegistration::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: ppf_registration_nodelet.cpp:136
jsk_pcl_ros::PPFRegistration::use_array_
bool use_array_
Definition: ppf_registration.h:168
jsk_pcl_ros::PPFRegistration::unsubscribe
virtual void unsubscribe()
Definition: ppf_registration_nodelet.cpp:111
jsk_pcl_ros::PPFRegistration::calculateNormals
virtual pcl::PointCloud< pcl::PointNormal >::Ptr calculateNormals(pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
Definition: ppf_registration_nodelet.cpp:118


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