Protected Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes
viso2_ros::StereoProcessor Class Reference

#include <stereo_processor.h>

Inheritance diagram for viso2_ros::StereoProcessor:
Inheritance graph
[legend]

List of all members.

Protected Member Functions

virtual void imageCallback (const sensor_msgs::ImageConstPtr &l_image_msg, const sensor_msgs::ImageConstPtr &r_image_msg, const sensor_msgs::CameraInfoConstPtr &l_info_msg, const sensor_msgs::CameraInfoConstPtr &r_info_msg)=0
 StereoProcessor (const std::string &transport)

Private Types

typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
ApproximatePolicy
typedef
message_filters::Synchronizer
< ApproximatePolicy
ApproximateSync
typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
ExactPolicy
typedef
message_filters::Synchronizer
< ExactPolicy
ExactSync

Private Member Functions

void checkInputsSynchronized ()
void dataCb (const sensor_msgs::ImageConstPtr &l_image_msg, const sensor_msgs::ImageConstPtr &r_image_msg, const sensor_msgs::CameraInfoConstPtr &l_info_msg, const sensor_msgs::CameraInfoConstPtr &r_info_msg)

Static Private Member Functions

static void increment (int *value)

Private Attributes

int all_received_
boost::shared_ptr
< ApproximateSync
approximate_sync_
ros::WallTimer check_synced_timer_
boost::shared_ptr< ExactSyncexact_sync_
int left_info_received_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
left_info_sub_
int left_received_
image_transport::SubscriberFilter left_sub_
int queue_size_
int right_info_received_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
right_info_sub_
int right_received_
image_transport::SubscriberFilter right_sub_

Detailed Description

This is an abstract base class for stereo image processing nodes. It handles synchronization of input topics (approximate or exact) and checks for sync errors. To use this class, subclass it and implement the imageCallback() method.

Definition at line 23 of file stereo_processor.h.


Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> viso2_ros::StereoProcessor::ApproximatePolicy [private]

Definition at line 32 of file stereo_processor.h.

Definition at line 34 of file stereo_processor.h.

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> viso2_ros::StereoProcessor::ExactPolicy [private]

Definition at line 31 of file stereo_processor.h.

Definition at line 33 of file stereo_processor.h.


Constructor & Destructor Documentation

viso2_ros::StereoProcessor::StereoProcessor ( const std::string &  transport) [inline, protected]

Constructor, subscribes to input topics using image transport and registers callbacks.

Parameters:
transportThe image transport to use

Definition at line 96 of file stereo_processor.h.


Member Function Documentation

Definition at line 62 of file stereo_processor.h.

void viso2_ros::StereoProcessor::dataCb ( const sensor_msgs::ImageConstPtr &  l_image_msg,
const sensor_msgs::ImageConstPtr &  r_image_msg,
const sensor_msgs::CameraInfoConstPtr &  l_info_msg,
const sensor_msgs::CameraInfoConstPtr &  r_info_msg 
) [inline, private]

Definition at line 49 of file stereo_processor.h.

virtual void viso2_ros::StereoProcessor::imageCallback ( const sensor_msgs::ImageConstPtr &  l_image_msg,
const sensor_msgs::ImageConstPtr &  r_image_msg,
const sensor_msgs::CameraInfoConstPtr &  l_info_msg,
const sensor_msgs::CameraInfoConstPtr &  r_info_msg 
) [protected, pure virtual]

Implement this method in sub-classes

Implemented in viso2_ros::StereoOdometer.

static void viso2_ros::StereoProcessor::increment ( int *  value) [inline, static, private]

Definition at line 44 of file stereo_processor.h.


Member Data Documentation

Definition at line 41 of file stereo_processor.h.

Definition at line 36 of file stereo_processor.h.

Definition at line 40 of file stereo_processor.h.

boost::shared_ptr<ExactSync> viso2_ros::StereoProcessor::exact_sync_ [private]

Definition at line 35 of file stereo_processor.h.

Definition at line 41 of file stereo_processor.h.

Definition at line 30 of file stereo_processor.h.

Definition at line 41 of file stereo_processor.h.

Definition at line 29 of file stereo_processor.h.

Definition at line 37 of file stereo_processor.h.

Definition at line 41 of file stereo_processor.h.

Definition at line 30 of file stereo_processor.h.

Definition at line 41 of file stereo_processor.h.

Definition at line 29 of file stereo_processor.h.


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


viso2_ros
Author(s): Stephan Wirth
autogenerated on Thu Jun 6 2019 21:23:20