segmentation_all_in_one_nodelet.h
Go to the documentation of this file.
00001 
00063 #ifndef __SEGMENTATION_ALL_IN_ONE_NODELET_H__
00064 #define __SEGMENTATION_ALL_IN_ONE_NODELET_H__
00065 
00066 
00067 // ROS includes
00068 #include <nodelet/nodelet.h>
00069 #include <pcl_ros/transforms.h>
00070 #include <tf/transform_listener.h>
00071 #include <tf_conversions/tf_eigen.h>
00072 #include <dynamic_reconfigure/server.h>
00073 #include <cob_3d_segmentation/segmentation_nodeletConfig.h>
00074 #include <actionlib/server/simple_action_server.h>
00075 
00076 // PCL includes
00077 #include <pcl/surface/concave_hull.h>
00078 #include <pcl/point_types.h>
00079 
00080 // Package includes
00081 #include "cob_3d_mapping_msgs/TriggerAction.h"
00082 #include "cob_3d_mapping_common/point_types.h"
00083 #include "cob_3d_features/organized_normal_estimation_omp.h"
00084 #include "cob_3d_segmentation/depth_segmentation.h"
00085 #include "cob_3d_segmentation/cluster_classifier.h"
00086 #include <cob_3d_segmentation/polygon_extraction/polygon_extraction.h>
00087 
00088 
00089 namespace cob_3d_segmentation
00090 {
00091   class SegmentationAllInOneNodelet : public nodelet::Nodelet
00092   {
00093   public:
00094     typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
00095     typedef pcl::PointCloud<pcl::Normal> NormalCloud;
00096     typedef pcl::PointCloud<PointLabel> LabelCloud;
00097     typedef PredefinedSegmentationTypes ST;
00098 
00099 
00100   public:
00101     SegmentationAllInOneNodelet()
00102       : one_()
00103       , seg_()
00104       , graph_(new ST::Graph)
00105       , pe_()
00106       , segmented_(new PointCloud)
00107       , classified_(new PointCloud)
00108       , normals_(new NormalCloud)
00109       , labels_(new LabelCloud)
00110       , centroid_passthrough_(5.0f)
00111       , enable_action_mode_(false)
00112       , is_running_(false)
00113     { }
00114 
00115     ~SegmentationAllInOneNodelet()
00116     { if(as_) delete as_; }
00117 
00118 
00119   protected:
00120     void onInit();
00121     void configCallback(cob_3d_segmentation::segmentation_nodeletConfig& config, uint32_t level);
00122 
00123     void actionCallback(const cob_3d_mapping_msgs::TriggerGoalConstPtr& goal);
00124     void receivedCloudCallback(PointCloud::ConstPtr cloud);
00125     void publishShapeArray(ST::CH::Ptr cluster_handler, PointCloud::ConstPtr cloud);
00126 
00127     //boost::mutex mutex_;
00128     ros::NodeHandle nh_;
00129     ros::Subscriber sub_points_;
00130     ros::Publisher pub_segmented_;
00131     ros::Publisher pub_classified_;
00132     ros::Publisher pub_shape_array_;
00133     ros::Publisher pub_chull_;
00134     ros::Publisher pub_chull_dense_;
00135     actionlib::SimpleActionServer<cob_3d_mapping_msgs::TriggerAction>* as_;
00136 
00137     boost::shared_ptr<dynamic_reconfigure::Server<cob_3d_segmentation::segmentation_nodeletConfig> > config_server_;
00138 
00139     cob_3d_features::OrganizedNormalEstimationOMP<pcl::PointXYZRGB, pcl::Normal, PointLabel> one_;
00140     DepthSegmentation<ST::Graph, ST::Point, ST::Normal, ST::Label> seg_;
00141     ClusterClassifier<ST::CH, ST::Point, ST::Normal, ST::Label> cc_;
00142     ST::Graph::Ptr graph_;
00143     PolygonExtraction pe_;
00144 
00145     PointCloud::Ptr segmented_;
00146     PointCloud::Ptr classified_;
00147     NormalCloud::Ptr normals_;
00148     LabelCloud::Ptr labels_;
00149 
00150 
00151     float centroid_passthrough_;
00152     bool enable_action_mode_;
00153     bool is_running_;
00154   };
00155 
00156 }
00157 
00158 
00159 #endif  //__cob_3d_features_SEGMENTATION_NODELET_H__


cob_3d_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:03