#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 | |
| typedef message_filters::Synchronizer < SyncPolicy > | SyncType |
Private Attributes | |
| string | camera_ |
| > Timer to check the image sync | |
| bool | init_ |
| image_transport::ImageTransport | it_ |
| double | last_ros_sync_ |
| > True when node is initialized. | |
| double | max_unsync_time_ |
| > Timer period | |
| ros::NodeHandle | nh_ |
| ros::NodeHandle | nhp_ |
| ros::Publisher | pub_info_ |
| ros::Timer | sync_timer_ |
| > Maximum time without sync | |
| double | timer_period_ |
| > Last ros time sync | |
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> avt_vimba_camera::Sync::SyncPolicy [private] |
typedef message_filters::Synchronizer<SyncPolicy> avt_vimba_camera::Sync::SyncType [private] |
| 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] |
| void avt_vimba_camera::Sync::run | ( | ) |
| void avt_vimba_camera::Sync::syncCallback | ( | const ros::TimerEvent & | ) | [protected] |
string avt_vimba_camera::Sync::camera_ [private] |
bool avt_vimba_camera::Sync::init_ [private] |
double avt_vimba_camera::Sync::last_ros_sync_ [private] |
double avt_vimba_camera::Sync::max_unsync_time_ [private] |
ros::NodeHandle avt_vimba_camera::Sync::nh_ [private] |
ros::NodeHandle avt_vimba_camera::Sync::nhp_ [private] |
double avt_vimba_camera::Sync::timer_period_ [private] |