Public Member Functions | Protected Member Functions | Private Types | Private Attributes | List of all members
avt_vimba_camera::Sync Class Reference

#include <sync.h>

Public Member Functions

void run ()
 
 Sync (ros::NodeHandle nh, ros::NodeHandle nhp)
 

Protected Member Functions

void msgsCallback (const sensor_msgs::ImageConstPtr &l_img_msg, const sensor_msgs::ImageConstPtr &r_img_msg, const sensor_msgs::CameraInfoConstPtr &l_info_msg, const sensor_msgs::CameraInfoConstPtr &r_info_msg)
 
void syncCallback (const ros::TimerEvent &)
 

Private Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > SyncPolicy
 

Camera name

More...
 
typedef message_filters::Synchronizer< SyncPolicySyncType
 

Private Attributes

string camera_
 

Timer to check the image sync

More...
 
bool init_
 
image_transport::ImageTransport it_
 
double last_ros_sync_
 

True when node is initialized.

More...
 
double max_unsync_time_
 

Timer period

More...
 
ros::NodeHandle nh_
 
ros::NodeHandle nhp_
 
ros::Publisher pub_info_
 
ros::Timer sync_timer_
 

Maximum time without sync

More...
 
double timer_period_
 

Last ros time sync

More...
 

Detailed Description

Definition at line 48 of file sync.h.

Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> avt_vimba_camera::Sync::SyncPolicy
private

Camera name

Definition at line 80 of file sync.h.

Definition at line 81 of file sync.h.

Constructor & Destructor Documentation

avt_vimba_camera::Sync::Sync ( ros::NodeHandle  nh,
ros::NodeHandle  nhp 
)

Definition at line 38 of file sync.cpp.

Member Function Documentation

void avt_vimba_camera::Sync::msgsCallback ( const sensor_msgs::ImageConstPtr &  l_img_msg,
const sensor_msgs::ImageConstPtr &  r_img_msg,
const sensor_msgs::CameraInfoConstPtr &  l_info_msg,
const sensor_msgs::CameraInfoConstPtr &  r_info_msg 
)
protected

Definition at line 70 of file sync.cpp.

void avt_vimba_camera::Sync::run ( )

Definition at line 46 of file sync.cpp.

void avt_vimba_camera::Sync::syncCallback ( const ros::TimerEvent )
protected

Definition at line 82 of file sync.cpp.

Member Data Documentation

string avt_vimba_camera::Sync::camera_
private

Timer to check the image sync

Definition at line 74 of file sync.h.

bool avt_vimba_camera::Sync::init_
private

Definition at line 69 of file sync.h.

image_transport::ImageTransport avt_vimba_camera::Sync::it_
private

Definition at line 84 of file sync.h.

double avt_vimba_camera::Sync::last_ros_sync_
private

True when node is initialized.

Definition at line 70 of file sync.h.

double avt_vimba_camera::Sync::max_unsync_time_
private

Timer period

Definition at line 72 of file sync.h.

ros::NodeHandle avt_vimba_camera::Sync::nh_
private

Definition at line 66 of file sync.h.

ros::NodeHandle avt_vimba_camera::Sync::nhp_
private

Definition at line 67 of file sync.h.

ros::Publisher avt_vimba_camera::Sync::pub_info_
private

Definition at line 86 of file sync.h.

ros::Timer avt_vimba_camera::Sync::sync_timer_
private

Maximum time without sync

Definition at line 73 of file sync.h.

double avt_vimba_camera::Sync::timer_period_
private

Last ros time sync

Definition at line 71 of file sync.h.


The documentation for this class was generated from the following files:


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