37 #ifndef JSK_PCL_ROS_FEATURE_REGISTRATION_H_ 38 #define JSK_PCL_ROS_FEATURE_REGISTRATION_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> 64 typedef FeatureRegistrationConfig
Config;
66 sensor_msgs::PointCloud2,
77 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
78 const sensor_msgs::PointCloud2::ConstPtr& feature_msg);
81 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
82 const sensor_msgs::PointCloud2::ConstPtr& feature_msg);
ros::Publisher pub_cloud_
double similarity_threshold_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
double max_correspondence_distance_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
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_
virtual void unsubscribe()
double transformation_epsilon_
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_feature_
boost::mutex mutex
global mutex.
FeatureRegistrationConfig Config
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
virtual void configCallback(Config &config, uint32_t level)
int correspondence_randomness_
pcl::PointCloud< pcl::FPFHSignature33 >::Ptr reference_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_
Nodelet implementation of jsk_pcl/FeatureRegistration.