Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007 #ifndef OPENNI_LISTENER_H
00008 #define OPENNI_LISTENER_H
00009 #include "ros/ros.h"
00010 #include <rosbag/bag.h>
00011
00012 #include <message_filters/subscriber.h>
00013 #include <message_filters/synchronizer.h>
00014 #include <message_filters/sync_policies/approximate_time.h>
00015
00016 #include <sensor_msgs/Image.h>
00017 #include <sensor_msgs/CameraInfo.h>
00018 #include <sensor_msgs/PointCloud2.h>
00019
00020
00021
00022
00023
00024
00025 namespace s = sensor_msgs;
00026 namespace m = message_filters;
00027
00028
00029 typedef m::sync_policies::ApproximateTime<s::Image, s::Image, s::CameraInfo, s::PointCloud2> MySyncPolicy;
00030
00031 class OpenNIListener {
00032
00033 public:
00038 OpenNIListener(ros::NodeHandle nh,
00039 const char* visual_topic= "/visual_in",
00040 const char* depth_topic= "/depth_in",
00041 const char* info_topic= "/cam_info_in",
00042 const char* cloud_topic= "/cloud_in",
00043 const char* filename= "test.bag",
00044 unsigned int step = 10);
00045
00046
00047
00052 void cameraCallback (const s::ImageConstPtr& visual_img,
00053 const s::ImageConstPtr& depth_img,
00054 const s::CameraInfoConstPtr& cam_info,
00055 const s::PointCloud2ConstPtr& point_cloud);
00056
00057 protected:
00058 m::Subscriber<s::Image> visual_sub_ ;
00059 m::Subscriber<s::Image> depth_sub_;
00060 m::Subscriber<s::CameraInfo> info_sub_;
00061 m::Subscriber<s::PointCloud2> cloud_sub_;
00062 m::Synchronizer<MySyncPolicy> sync_;
00063
00064 ros::Publisher pub_cloud_;
00065 ros::Publisher pub_transf_cloud_;
00066 ros::Publisher pub_ref_cloud_;
00067
00068
00069 unsigned int callback_counter_;
00070 unsigned int step_;
00071
00072
00073 rosbag::Bag bag_;
00074
00075
00076 };
00077
00078
00079
00080
00081
00082
00083
00084
00086
00087
00089
00090 #endif