fpfh_node.h
Go to the documentation of this file.
00001 #ifndef FPFHNODE_
00002 #define FPFHNODE_
00003 #include "ros/ros.h"
00004 #include "sensor_msgs/PointCloud2.h"                                                                   
00005 #include "sensor_msgs/Image.h"
00006 #include "sensor_msgs/CameraInfo.h"
00007 #include "feature_extractor_fpfh/FPFHHist.h"
00008 #include "feature_extractor_fpfh/SubsampleCalc.h"
00009 
00010 class FPFHNode
00011 {
00012     protected:
00013         ros::NodeHandle n_;
00014         ros::Publisher hist_publisher;
00015         ros::ServiceServer fpfh_service;
00016         ros::ServiceServer subsample_service;
00017 
00018     public:
00019         FPFHNode(ros::NodeHandle &);
00020 
00021         void message_cb(const sensor_msgs::Image::ConstPtr& , const sensor_msgs::PointCloud2::ConstPtr& );
00022 
00023         void process_point_cloud(const sensor_msgs::PointCloud2::ConstPtr&, feature_extractor_fpfh::FPFHHist &);
00024 
00025         bool fpfh_srv_cb(feature_extractor_fpfh::FPFHCalc::Request &, feature_extractor_fpfh::FPFHCalc::Response &);
00026 
00027         bool subsample_srv_cb(feature_extractor_fpfh::SubsampleCalc::Request &, feature_extractor_fpfh::SubsampleCalc::Response &);
00028 };
00029 
00030 #endif  //#ifndef FPFHNODE_
00031 


feature_extractor_fpfh
Author(s): Hai Nguyen
autogenerated on Wed Nov 27 2013 11:46:13