openni_listener.h
Go to the documentation of this file.
00001 /* The purpose of this class is to listen to 
00002  * synchronized image pairs from the kinect
00003  * convert them to opencv, process them, convert
00004  * them to a qt image and send them to the mainwindow
00005  * defined in qtcv.h/.cpp
00006  */
00007 #ifndef OPENNI_LISTENER_H
00008 #define OPENNI_LISTENER_H
00009 #include "ros/ros.h"
00010 #include <rosbag/bag.h>
00011 //#include <pcl_tf/transforms.h>
00012 #include <message_filters/subscriber.h>
00013 #include <message_filters/synchronizer.h>
00014 #include <message_filters/sync_policies/approximate_time.h>
00015 //#include <image_geometry/pinhole_camera_model.h>
00016 #include <sensor_msgs/Image.h>
00017 #include <sensor_msgs/CameraInfo.h>
00018 #include <sensor_msgs/PointCloud2.h>
00019 //#include <opencv2/core/core.hpp>
00020 //#include <opencv2/features2d/features2d.hpp>
00021 //#include <Eigen/Core>
00022 //#include <tf/transform_listener.h>
00023 
00024 
00025 namespace s = sensor_msgs;
00026 namespace m = message_filters;
00027 
00028 //The policy merges kinect messages with approximately equal timestamp into one callback 
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", //Kinect:/camera/rgb/camera_info
00042                    const char* cloud_topic= "/cloud_in",
00043                    const char* filename= "test.bag",
00044                                    unsigned int step = 10);
00045 
00046 //    void Callback (const sensor_msgs::PointCloud2ConstPtr&  point_cloud);
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   //  tf::TransformListener  listener; 
00068    //ros::Publisher pc_pub; 
00069      unsigned int callback_counter_;
00070     unsigned int step_;
00071     //bool pause_;
00072     //bool first_frame_;
00073     rosbag::Bag bag_;
00074 
00075 
00076 };
00077 
00078 //QVector<float>* transformPointCloud (const Eigen::Matrix4f transform, const s::PointCloud2 &in);
00079 //Copied from pcl_tf/transform.cpp
00080 //void transformPointCloud (const Eigen::Matrix4f &transform, 
00081   //                        const sensor_msgs::PointCloud2 &in,
00082 //                          sensor_msgs::PointCloud2 &out);
00083 
00084 
00086 //std::string openCVCode2String(unsigned int code);
00087 
00089 //void printMatrixInfo(cv::Mat& image);
00090 #endif


depth_tracker_ros_vr8
Author(s): shusain
autogenerated on Fri Dec 6 2013 20:45:47