37 #ifndef JSK_PCL_ROS_INCREMENTAL_MODEL_REGISTRATION_H_
38 #define JSK_PCL_ROS_INCREMENTAL_MODEL_REGISTRATION_H_
40 #include <geometry_msgs/PoseStamped.h>
41 #include <sensor_msgs/PointCloud.h>
43 #include <jsk_topic_tools/diagnostic_nodelet.h>
47 #include <pcl/visualization/pcl_visualizer.h>
48 #include <std_srvs/Empty.h>
52 class CapturedSamplePointCloud
58 const Eigen::Affine3f& original_pose);
64 pcl::PointCloud<pcl::PointXYZRGB> cloud);
76 class IncrementalModelRegistration:
public jsk_topic_tools::DiagnosticNodelet
82 sensor_msgs::PointCloud2,
83 pcl_msgs::PointIndices,
95 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
96 const pcl_msgs::PointIndices::ConstPtr& indices_msg,
97 const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
99 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
input,
100 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output,
101 const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
103 std_srvs::Empty::Request&
req,
104 std_srvs::Empty::Response&
res);
106 pcl::PointCloud<pcl::PointXYZRGB>::Ptr reference,
107 pcl::PointCloud<pcl::PointXYZRGB>::Ptr target,
108 Eigen::Affine3f& output_transform);
125 std::vector<CapturedSamplePointCloud::Ptr>
samples_;