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 #ifndef JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_
00037 #define JSK_PCL_ROS_ADD_COLOR_FROM_IMAGE_H_
00038
00039 #include <jsk_topic_tools/diagnostic_nodelet.h>
00040 #include "jsk_recognition_utils/pcl_util.h"
00041 #include "jsk_recognition_utils/geo_util.h"
00042 #include "jsk_recognition_utils/pcl_conversion_util.h"
00043
00044 #include <message_filters/subscriber.h>
00045 #include <message_filters/time_synchronizer.h>
00046 #include <message_filters/synchronizer.h>
00047 #include <message_filters/sync_policies/approximate_time.h>
00048 #include <dynamic_reconfigure/server.h>
00049
00050 #include <sensor_msgs/PointCloud2.h>
00051 #include <jsk_recognition_msgs/PointsArray.h>
00052 #include <geometry_msgs/PoseArray.h>
00053 #include <geometry_msgs/Pose.h>
00054 #include <pcl/features/ppf.h>
00055 #include <pcl/features/normal_3d.h>
00056 #include <pcl/registration/ppf_registration.h>
00057 #include <jsk_pcl_ros/PPFRegistrationConfig.h>
00058
00059 namespace jsk_pcl_ros
00060 {
00061 class PPFRegistration: public jsk_topic_tools::DiagnosticNodelet
00062 {
00063 public:
00064 typedef message_filters::sync_policies::ExactTime<
00065 sensor_msgs::PointCloud2,
00066 jsk_recognition_msgs::PointsArray> ArraySyncPolicy;
00067 typedef message_filters::sync_policies::ApproximateTime<
00068 sensor_msgs::PointCloud2,
00069 jsk_recognition_msgs::PointsArray> ArrayApproximateSyncPolicy;
00070 typedef message_filters::sync_policies::ExactTime<
00071 sensor_msgs::PointCloud2,
00072 sensor_msgs::PointCloud2> CloudSyncPolicy;
00073 typedef message_filters::sync_policies::ApproximateTime<
00074 sensor_msgs::PointCloud2,
00075 sensor_msgs::PointCloud2> CloudApproximateSyncPolicy;
00076 typedef jsk_pcl_ros::PPFRegistrationConfig Config;
00077 PPFRegistration(): DiagnosticNodelet("PPFRegistration") {}
00078 protected:
00079 virtual void onInit();
00080 virtual void subscribe();
00081 virtual void unsubscribe();
00082 virtual pcl::PointCloud<pcl::PointNormal>::Ptr calculateNormals (pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
00083 virtual void configCallback(Config &config, uint32_t level);
00084 virtual void updateDiagnostic(
00085 diagnostic_updater::DiagnosticStatusWrapper &stat);
00086 virtual void ArrayRegistration(
00087 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
00088 const jsk_recognition_msgs::PointsArray::ConstPtr& input_reference_points_array);
00089 virtual void CloudRegistration(
00090 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
00091 const sensor_msgs::PointCloud2::ConstPtr& input_reference_cloud);
00092 boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
00093 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00094 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_reference_cloud_;
00095 message_filters::Subscriber<jsk_recognition_msgs::PointsArray> sub_reference_array_;
00096 boost::mutex mutex_;
00097 boost::shared_ptr<message_filters::Synchronizer<ArraySyncPolicy> > array_sync_;
00098 boost::shared_ptr<message_filters::Synchronizer<ArrayApproximateSyncPolicy> > array_async_;
00099 boost::shared_ptr<message_filters::Synchronizer<CloudSyncPolicy> > cloud_sync_;
00100 boost::shared_ptr<message_filters::Synchronizer<CloudApproximateSyncPolicy> > cloud_async_;
00101 bool approximate_sync_;
00102 int queue_size_;
00103 double search_radius_;
00104 int sampling_rate_;
00105 bool use_array_;
00106 double position_clustering_threshold_;
00107 double rotation_clustering_threshold_;
00108 ros::Publisher pub_pose_array_;
00109 ros::Publisher pub_points_array_;
00110 ros::Publisher pub_pose_stamped_;
00111 ros::Publisher pub_cloud_;
00112
00113 pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals;
00114 pcl::PointCloud<pcl::PointNormal>::Ptr reference_cloud_with_normals;
00115 pcl::PPFEstimation<pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature> ppf_estimator;
00116 pcl::PPFRegistration<pcl::PointNormal, pcl::PointNormal> ppf_registration;
00117 private:
00118
00119 };
00120 }
00121
00122 #endif