00001 #ifndef REALCAMERASYNCHRONIZER_HPP_ 00002 #define REALCAMERASYNCHRONIZER_HPP_ 00003 00004 #include <string> 00005 #include <vector> 00006 #include <map> 00007 #include <nodelet/nodelet.h> 00008 #include <image_transport/image_transport.h> 00009 #include <sensor_msgs/Image.h> 00010 #include "common_defs.hpp" 00011 #include "RealCamera.hpp" 00012 00013 namespace virtual_camera { 00014 00015 00023 class RealCameraSynchronizer { 00024 private: 00025 bool synchronize; 00026 std::map<std::string, RealCameraPtr> camsByFrame; 00027 std::map<std::string, sensor_msgs::ImageConstPtr> msgsByFrame; 00028 std::vector<image_transport::Subscriber> realCamImgSubs; 00029 MutexPtr syncMutex; 00030 int recentCount; 00031 int cameraCount; 00032 ros::Time mostRecentStamp; 00033 00034 void handleSynchronization(const sensor_msgs::ImageConstPtr & image); 00035 void pushMessages(); 00036 void generalCallback(const sensor_msgs::ImageConstPtr & image); 00037 public: 00045 RealCameraSynchronizer(bool synchronize, const MutexPtr & syncMutex); 00046 00047 00056 void addCamera(const std::string & topic, const RealCameraPtr & camera, 00057 const boost::shared_ptr<image_transport::ImageTransport> & it); 00058 00059 00063 bool isSynchronized(); 00064 00065 00070 void setSynchronization(bool mode); 00071 00072 00073 }; 00074 00075 typedef boost::shared_ptr<RealCameraSynchronizer> RealCameraSynchronizerPtr; 00076 00077 } 00078 00079 00080 00081 #endif /* REALCAMERASYNCHRONIZER_HPP_ */