pc2_filter.h
Go to the documentation of this file.
00001 
00002 #include "pcl_ros/point_cloud.h"
00003 #include "pcl/point_types.h"
00004 //#include "pcl/sample_consensus/method_types.h"
00005 //#include "pcl/sample_consensus/model_types.h"
00006 //#include "pcl/segmentation/sac_segmentation.h"
00007 #include "pcl/filters/voxel_grid.h"
00008 //#include "pcl/filters/extract_indices.h"
00009 //#include "pcl/ModelCoefficients.h"
00010 
00011 #include "ros/ros.h"
00012 
00013 #ifndef _PCL2_FILTER_
00014 #define _PCL2_FILTER_
00015 
00016 #define SUB_TOPIC "/camera/rgb/points"
00017 
00018 typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
00019 
00020 class PCL2_Filter
00021 {
00022   private:
00023     sensor_msgs::PointCloud2::Ptr new_msg;
00024     PointCloud::Ptr cloud_filtered;
00025     pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
00026     
00027     /*
00028     PointCloud::Ptr cloud_p;
00029     
00030     
00031     pcl::ModelCoefficients::Ptr coefficients;
00032     pcl::PointIndices::Ptr inliers;
00033     pcl::SACSegmentation<pcl::PointType> seg;
00034     pcl::ExtractIndices<pcl::PointType> extract;
00035     */
00036 
00037     ros::Publisher pub;
00038     ros::Subscriber sub;
00039     ros::NodeHandle n;
00040     int skip;
00041     double leaf_size;
00042 
00043   public:
00044     PCL2_Filter();
00045     PCL2_Filter(int argc,char** argv);
00046 
00047     ~PCL2_Filter();
00048     void processPoints(const sensor_msgs::PointCloud2::ConstPtr& msg);
00049     void filterCloud(PointCloud::Ptr cloud_filtered);
00050     void spin();
00051 };
00052 #endif


pcl_filter
Author(s): Jihoon
autogenerated on Fri Jan 3 2014 11:11:35