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_PLANE_CONCATENATOR_H_
00038 #define JSK_PCL_ROS_PLANE_CONCATENATOR_H_
00039
00040 #include <jsk_recognition_msgs/PolygonArray.h>
00041 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
00042 #include <jsk_recognition_msgs/ClusterPointIndices.h>
00043
00044 #include <jsk_pcl_ros/PlaneConcatenatorConfig.h>
00045 #include <dynamic_reconfigure/server.h>
00046 #include <jsk_topic_tools/diagnostic_nodelet.h>
00047 #include <message_filters/subscriber.h>
00048 #include <message_filters/time_synchronizer.h>
00049 #include <message_filters/synchronizer.h>
00050
00051 #include "jsk_pcl_ros/geo_util.h"
00052
00053 namespace jsk_pcl_ros
00054 {
00055 class PlaneConcatenator: public jsk_topic_tools::DiagnosticNodelet
00056 {
00057 public:
00058 typedef boost::shared_ptr<PlaneConcatenator> Ptr;
00059 typedef PlaneConcatenatorConfig Config;
00060 typedef pcl::PointXYZRGB PointT;
00061 typedef message_filters::sync_policies::ExactTime<
00062 sensor_msgs::PointCloud2,
00063 jsk_recognition_msgs::ClusterPointIndices,
00064 jsk_recognition_msgs::PolygonArray,
00065 jsk_recognition_msgs::ModelCoefficientsArray
00066 > SyncPolicy;
00067 PlaneConcatenator(): DiagnosticNodelet("PlaneConcatenator") {}
00068
00069 protected:
00071
00073 virtual void onInit();
00074 virtual void subscribe();
00075 virtual void unsubscribe();
00076 virtual void updateDiagnostic(
00077 diagnostic_updater::DiagnosticStatusWrapper &stat);
00078 virtual void concatenate(
00079 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00080 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
00081 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_array_msg,
00082 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_array_msg);
00083 virtual void configCallback(Config &config, uint32_t level);
00084 virtual bool isNearPointCloud(
00085 pcl::KdTreeFLANN<PointT>& kdtree,
00086 pcl::PointCloud<PointT>::Ptr cloud,
00087 Plane::Ptr target_plane);
00088 virtual pcl::ModelCoefficients::Ptr refinement(
00089 pcl::PointCloud<PointT>::Ptr cloud,
00090 pcl::PointIndices::Ptr indices,
00091 pcl::ModelCoefficients::Ptr original_coefficients);
00093
00095 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_cloud_;
00096 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_;
00097 message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> sub_polygon_;
00098 message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_;
00099 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00100 boost::mutex mutex_;
00101 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00102 ros::Publisher pub_indices_;
00103 ros::Publisher pub_polygon_;
00104 ros::Publisher pub_coefficients_;
00106
00108 double connect_angular_threshold_;
00109 double connect_distance_threshold_;
00110 double connect_perpendicular_distance_threshold_;
00111 int ransac_refinement_max_iteration_;
00112 double ransac_refinement_outlier_threshold_;
00113 double ransac_refinement_eps_distance_;
00114 double ransac_refinement_eps_angle_;
00115 int min_size_;
00116 private:
00117
00118 };
00119 }
00120 #endif