fov_segmentation_node.h
Go to the documentation of this file.
00001 
00064 #ifndef __FOV_SEGMENTATION_NODE_H__
00065 #define __FOV_SEGMENTATION_NODE_H__
00066 
00067 // ROS includes
00068 #include <ros/ros.h>
00069 #include <dynamic_reconfigure/server.h>
00070 
00071 // ROS message includes
00072 #include <cob_3d_mapping_msgs/ShapeArray.h>
00073 
00074 #include "cob_3d_mapping_common/polygon.h"
00075 #include "cob_3d_fov_segmentation/field_of_view.h"
00076 #include "cob_3d_fov_segmentation/fov_segmentation.h"
00077 
00078 namespace cob_3d_mapping
00079 {
00086   class FOVSegmentationNode
00087   {
00088   public:
00092     FOVSegmentationNode ();
00096     ~FOVSegmentationNode ()
00097     {
00098     }
00099     ;
00100 
00112     void
00113     dynReconfCallback (cob_3d_fov_segmentation::fov_segmentationConfig &config, uint32_t level);
00114 
00120     void
00121     shapeCallback (const cob_3d_mapping_msgs::ShapeArray::ConstPtr& sa);
00122 
00123     ros::NodeHandle n_; 
00124 
00125   protected:
00126     ros::Subscriber shape_sub_; 
00127     ros::Publisher shape_pub_; 
00128 
00129     tf::TransformListener tf_listener_; 
00130 
00134     dynamic_reconfigure::Server<cob_3d_fov_segmentation::fov_segmentationConfig> config_server_;
00135 
00136     FieldOfView fov_; 
00137     FOVSegmentation fov_seg_; 
00138 
00139     std::string camera_frame_; 
00140     std::string target_frame_; 
00141   };
00142 }
00143 
00144 #endif // FOV_SEGMENTATION_NODE_H__


cob_3d_fov_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:04:19