Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_FEATURE_REGISTRATION_H_
38 #define JSK_PCL_ROS_FEATURE_REGISTRATION_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
47 #include <dynamic_reconfigure/server.h>
48 #include <jsk_pcl_ros/FeatureRegistrationConfig.h>
50 #include <pcl/point_types.h>
51 #include <pcl/point_cloud.h>
52 #include <sensor_msgs/PointCloud2.h>
53 #include <geometry_msgs/PoseStamped.h>
61 class FeatureRegistration:
public jsk_topic_tools::DiagnosticNodelet
64 typedef FeatureRegistrationConfig
Config;
66 sensor_msgs::PointCloud2,
78 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
79 const sensor_msgs::PointCloud2::ConstPtr& feature_msg);
82 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
83 const sensor_msgs::PointCloud2::ConstPtr& feature_msg);
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
virtual void configCallback(Config &config, uint32_t level)
virtual void unsubscribe()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
double similarity_threshold_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > reference_sync_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_feature_
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pcl::PointCloud< pcl::FPFHSignature33 >::Ptr reference_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_feature_
int correspondence_randomness_
double transformation_epsilon_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
FeatureRegistrationConfig Config
boost::mutex mutex
global mutex.
virtual ~FeatureRegistration()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
double max_correspondence_distance_
ros::Publisher pub_cloud_
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44