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 #ifndef JSK_PCL_ROS_MULTI_PLANE_EXTRACTION_H_
00036 #define JSK_PCL_ROS_MULTI_PLANE_EXTRACTION_H_
00037
00038 #include <ros/ros.h>
00039 #include <ros/names.h>
00040 #include <pcl_ros/pcl_nodelet.h>
00041 #include <message_filters/time_synchronizer.h>
00042 #include <message_filters/synchronizer.h>
00043 #include <message_filters/sync_policies/approximate_time.h>
00044
00045 #include "jsk_recognition_msgs/ClusterPointIndices.h"
00046 #include "sensor_msgs/PointCloud2.h"
00047 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
00048 #include "jsk_recognition_msgs/PolygonArray.h"
00049 #include <dynamic_reconfigure/server.h>
00050 #include "jsk_pcl_ros/MultiPlaneExtractionConfig.h"
00051 #include "jsk_pcl_ros/pcl_util.h"
00052 #include "jsk_pcl_ros/pcl_conversion_util.h"
00053 #include <jsk_topic_tools/vital_checker.h>
00054 #include <jsk_topic_tools/diagnostic_nodelet.h>
00055 #include "jsk_pcl_ros/tf_listener_singleton.h"
00056
00057 namespace jsk_pcl_ros
00058 {
00059 class MultiPlaneExtraction: public jsk_topic_tools::DiagnosticNodelet
00060 {
00061 public:
00062
00063 typedef message_filters::sync_policies::ExactTime<
00064 sensor_msgs::PointCloud2,
00065 jsk_recognition_msgs::ClusterPointIndices,
00066 jsk_recognition_msgs::ModelCoefficientsArray,
00067 jsk_recognition_msgs::PolygonArray> SyncPolicy;
00068 typedef message_filters::sync_policies::ExactTime<
00069 sensor_msgs::PointCloud2,
00070 jsk_recognition_msgs::ModelCoefficientsArray,
00071 jsk_recognition_msgs::PolygonArray> SyncWithoutIndicesPolicy;
00072 typedef message_filters::sync_policies::ApproximateTime<
00073 sensor_msgs::PointCloud2,
00074 jsk_recognition_msgs::ClusterPointIndices,
00075 jsk_recognition_msgs::ModelCoefficientsArray,
00076 jsk_recognition_msgs::PolygonArray> ASyncPolicy;
00077 typedef message_filters::sync_policies::ApproximateTime<
00078 sensor_msgs::PointCloud2,
00079 jsk_recognition_msgs::ModelCoefficientsArray,
00080 jsk_recognition_msgs::PolygonArray> ASyncWithoutIndicesPolicy;
00081 typedef jsk_pcl_ros::MultiPlaneExtractionConfig Config;
00082
00083 MultiPlaneExtraction(): DiagnosticNodelet("MultiPlaneExtraction") { }
00084 protected:
00086
00088 virtual void onInit();
00089
00090 virtual void extract(const sensor_msgs::PointCloud2::ConstPtr& input,
00091 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
00092 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
00093 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
00094 virtual void extract(
00095 const sensor_msgs::PointCloud2::ConstPtr& input,
00096 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
00097 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
00098
00099 virtual void configCallback (Config &config, uint32_t level);
00100
00101 virtual void updateDiagnostic(
00102 diagnostic_updater::DiagnosticStatusWrapper &stat);
00103
00104 virtual void subscribe();
00105 virtual void unsubscribe();
00107
00109 boost::mutex mutex_;
00110 ros::Publisher pub_, nonplane_pub_;
00111 ros::Publisher pub_indices_;
00112 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00113 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00114 message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_;
00115 message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> sub_polygons_;
00116 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_indices_;
00117 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00118 boost::shared_ptr<message_filters::Synchronizer<SyncWithoutIndicesPolicy> > sync_wo_indices_;
00119 boost::shared_ptr<message_filters::Synchronizer<ASyncPolicy> > async_;
00120 boost::shared_ptr<message_filters::Synchronizer<ASyncWithoutIndicesPolicy> > async_wo_indices_;
00121
00123
00125 Counter plane_counter_;
00126
00128
00130 tf::TransformListener* tf_listener_;
00131 bool use_async_;
00132 int maximum_queue_size_;
00133 double min_height_, max_height_;
00134 bool use_indices_;
00135 double maginify_;
00136 bool use_sensor_frame_;
00137 std::string sensor_frame_;
00138 private:
00139
00140
00141 };
00142 }
00143
00144 #endif