Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_PCL_ROS_INCREMENTAL_MODEL_REGISTRATION_H_
00038 #define JSK_PCL_ROS_INCREMENTAL_MODEL_REGISTRATION_H_
00039
00040 #include <geometry_msgs/PoseStamped.h>
00041 #include <sensor_msgs/PointCloud.h>
00042 #include <pcl_conversions/pcl_conversions.h>
00043 #include <jsk_topic_tools/diagnostic_nodelet.h>
00044 #include <message_filters/subscriber.h>
00045 #include <message_filters/time_synchronizer.h>
00046 #include <message_filters/synchronizer.h>
00047 #include <pcl/visualization/pcl_visualizer.h>
00048 #include <std_srvs/Empty.h>
00049
00050 namespace jsk_pcl_ros
00051 {
00052 class CapturedSamplePointCloud
00053 {
00054 public:
00055 typedef boost::shared_ptr<CapturedSamplePointCloud> Ptr;
00056 CapturedSamplePointCloud();
00057 CapturedSamplePointCloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
00058 const Eigen::Affine3f& original_pose);
00059 virtual pcl::PointCloud<pcl::PointXYZRGB>::Ptr getOriginalPointCloud();
00060 virtual Eigen::Affine3f getOriginalPose();
00061 virtual pcl::PointCloud<pcl::PointXYZRGB>::Ptr getRefinedPointCloud();
00062 virtual Eigen::Affine3f getRefinedPose();
00063 virtual void setRefinedPointCloud(
00064 pcl::PointCloud<pcl::PointXYZRGB> cloud);
00065 virtual void setRefinedPose(Eigen::Affine3f pose);
00066
00067 protected:
00068 pcl::PointCloud<pcl::PointXYZRGB>::Ptr original_cloud_;
00069 pcl::PointCloud<pcl::PointXYZRGB>::Ptr refined_cloud_;
00070 Eigen::Affine3f original_pose_;
00071 Eigen::Affine3f refined_pose_;
00072 private:
00073
00074 };
00075
00076 class IncrementalModelRegistration: public jsk_topic_tools::DiagnosticNodelet
00077 {
00078 public:
00079 IncrementalModelRegistration(): DiagnosticNodelet("IncrementalModelRegistration") {}
00080 typedef message_filters::sync_policies::ExactTime<
00081 sensor_msgs::PointCloud2,
00082 pcl_msgs::PointIndices,
00083 geometry_msgs::PoseStamped > SyncPolicy;
00084 protected:
00086
00088 virtual void onInit();
00089 virtual void subscribe() {}
00090 virtual void unsubscribe() {}
00091 virtual void updateDiagnostic(
00092 diagnostic_updater::DiagnosticStatusWrapper &stat) {}
00093 virtual void newsampleCallback(
00094 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00095 const pcl_msgs::PointIndices::ConstPtr& indices_msg,
00096 const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
00097 virtual void transformPointCloudRepsectedToPose(
00098 pcl::PointCloud<pcl::PointXYZRGB>::Ptr input,
00099 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output,
00100 const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
00101 virtual bool startRegistration(
00102 std_srvs::Empty::Request& req,
00103 std_srvs::Empty::Response& res);
00104 virtual void callICP(
00105 pcl::PointCloud<pcl::PointXYZRGB>::Ptr reference,
00106 pcl::PointCloud<pcl::PointXYZRGB>::Ptr target,
00107 Eigen::Affine3f& output_transform);
00109
00111 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00112 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_cloud_;
00113 message_filters::Subscriber<pcl_msgs::PointIndices> sub_indices_;
00114 message_filters::Subscriber<geometry_msgs::PoseStamped> sub_pose_;
00115 boost::mutex mutex_;
00116 ros::ServiceServer start_registration_srv_;
00117 ros::Publisher pub_cloud_non_registered_;
00118 ros::Publisher pub_registered_;
00119 boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer_;
00120
00122
00124 std::vector<CapturedSamplePointCloud::Ptr> samples_;
00125 Eigen::Affine3f origin_;
00126 pcl::PointCloud<pcl::PointXYZRGB> all_cloud_;
00127 std::string frame_id_;
00128 private:
00129
00130 };
00131 }
00132
00133 #endif