segment_plane_nodelet.h
Go to the documentation of this file.
00001 #ifndef _segment_plane_h_
00002 #define _segment_plane_h_
00003 
00004 #include <nodelet/nodelet.h>
00005 #include <ros/ros.h>
00006 
00007 // [publisher subscriber headers]
00008 #include <sensor_msgs/PointCloud2.h>
00009 
00010 #include <pcl/point_cloud.h>
00011 //#include <pcl_ros/point_cloud.h>
00012 
00013 // segmentation
00014 #include <pcl/io/pcd_io.h>
00015 #include <pcl/ModelCoefficients.h>
00016 #include <pcl/segmentation/sac_segmentation.h>
00017 #include <pcl/sample_consensus/method_types.h>
00018 #include <pcl/filters/project_inliers.h>
00019 
00020 //#include <pcl/filters/extract_indices.h>
00021 //#include <pcl_ros/point_cloud.h>
00022 
00023 // Segmentation
00024 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00025 #include <pcl/surface/convex_hull.h>
00026 
00027 // clustering
00028 //#include <pcl/segmentation/extract_clusters.h>
00029 //#include <pcl/kdtree/kdtree_flann.h>
00030 
00031 // downsampling
00032 #include <pcl/filters/voxel_grid.h>
00033 
00034 // crop
00035 #include <pcl/filters/passthrough.h>
00036 
00037 
00038 
00039 namespace iri_clean_board
00040 {
00041 
00046 class SegmentPlane : public nodelet::Nodelet
00047 {
00048   private:
00049     // [publisher attributes]
00050     ros::Publisher segmented_pointcloud_publisher_pointclouds_;
00051     sensor_msgs::PointCloud2 PointCloud2_msg_;
00052 
00053     // [subscriber attributes]
00054     ros::Subscriber input_pointcloud_subscriber_;
00055     void input_pointcloud_callback(const sensor_msgs::PointCloud2::ConstPtr& msg);
00056 
00057     // [service attributes]
00058 
00059     // [client attributes]
00060 
00061     // [action server attributes]
00062 
00063     // [action client attributes]
00064     
00065     // node parameters
00066     int table_segmentation_downsample;
00067     double table_segmentation_min_height;
00068     double table_segmentation_max_height;
00069     double table_segmentation_height;
00070 
00076     pcl::PointCloud<pcl::PointXYZRGB>::Ptr getBiggestPlane (pcl::PointCloud<pcl::PointXYZ>::Ptr clouda, pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_rgb);
00077     
00083     void pcCallback(const sensor_msgs::PointCloud2::ConstPtr& msg);
00084     
00085   public:
00092     virtual void onInit();
00093 
00094 
00095 };
00096 
00097 }
00098 
00099 #endif


iri_clean_board
Author(s): David Martinez
autogenerated on Fri Dec 6 2013 23:52:37