00001 00002 00003 00004 00005 00006 00007 00008 00009 00010 00011 00012 00013 00014 00015 00016 00017 00018 00019 00020 00021 00022 00023 00024 00025 00026 00027 00028 00029 00030 00031 00032 00033 #ifndef SYNC_H 00034 #define SYNC_H 00035 00036 #include <ros/ros.h> 00037 #include <sensor_msgs/Image.h> 00038 #include <message_filters/subscriber.h> 00039 #include <message_filters/time_synchronizer.h> 00040 #include <message_filters/sync_policies/approximate_time.h> 00041 #include <image_transport/subscriber_filter.h> 00042 #include <std_msgs/String.h> 00043 #include <boost/lexical_cast.hpp> 00044 00045 using namespace std; 00046 00047 namespace avt_vimba_camera { 00048 class Sync { 00049 00050 public: 00051 Sync(ros::NodeHandle nh, ros::NodeHandle nhp); 00052 void run(); 00053 00054 protected: 00055 00056 void msgsCallback(const sensor_msgs::ImageConstPtr& l_img_msg, 00057 const sensor_msgs::ImageConstPtr& r_img_msg, 00058 const sensor_msgs::CameraInfoConstPtr& l_info_msg, 00059 const sensor_msgs::CameraInfoConstPtr& r_info_msg); 00060 00061 void syncCallback(const ros::TimerEvent&); 00062 00063 private: 00064 00065 // Node handles 00066 ros::NodeHandle nh_; 00067 ros::NodeHandle nhp_; 00068 00069 bool init_; 00070 double last_ros_sync_; 00071 double timer_period_; 00072 double max_unsync_time_; 00073 ros::Timer sync_timer_; 00074 string camera_; 00075 00076 // Topic sync 00077 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, 00078 sensor_msgs::Image, 00079 sensor_msgs::CameraInfo, 00080 sensor_msgs::CameraInfo> SyncPolicy; 00081 typedef message_filters::Synchronizer<SyncPolicy> SyncType; 00082 00083 // Image transport 00084 image_transport::ImageTransport it_; 00085 00086 ros::Publisher pub_info_; 00087 }; 00088 } 00089 #endif