sync.h
Go to the documentation of this file.
1 
33 #ifndef SYNC_H
34 #define SYNC_H
35 
36 #include <ros/ros.h>
37 #include <sensor_msgs/Image.h>
42 #include <std_msgs/String.h>
43 #include <boost/lexical_cast.hpp>
44 
45 using namespace std;
46 
47 namespace avt_vimba_camera {
48 class Sync {
49 
50  public:
52  void run();
53 
54  protected:
55 
56  void msgsCallback(const sensor_msgs::ImageConstPtr& l_img_msg,
57  const sensor_msgs::ImageConstPtr& r_img_msg,
58  const sensor_msgs::CameraInfoConstPtr& l_info_msg,
59  const sensor_msgs::CameraInfoConstPtr& r_info_msg);
60 
61  void syncCallback(const ros::TimerEvent&);
62 
63  private:
64 
65  // Node handles
68 
69  bool init_;
70  double last_ros_sync_;
71  double timer_period_;
74  string camera_;
75 
76  // Topic sync
77  typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image,
78  sensor_msgs::Image,
79  sensor_msgs::CameraInfo,
80  sensor_msgs::CameraInfo> SyncPolicy;
82 
83  // Image transport
85 
87 };
88 }
89 #endif
image_transport::ImageTransport it_
Definition: sync.h:84
ros::Timer sync_timer_
Maximum time without sync
Definition: sync.h:73
ros::NodeHandle nhp_
Definition: sync.h:67
double timer_period_
Last ros time sync
Definition: sync.h:71
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > SyncPolicy
Camera name
Definition: sync.h:80
double last_ros_sync_
True when node is initialized.
Definition: sync.h:70
double max_unsync_time_
Timer period
Definition: sync.h:72
message_filters::Synchronizer< SyncPolicy > SyncType
Definition: sync.h:81
string camera_
Timer to check the image sync
Definition: sync.h:74
void run(ClassLoader *loader)
ros::Publisher pub_info_
Definition: sync.h:86
ros::NodeHandle nh_
Definition: sync.h:66


avt_vimba_camera
Author(s): Miquel Massot , Allied Vision Technologies
autogenerated on Mon Jun 10 2019 12:50:39