All Classes Namespaces Files Functions Variables Typedefs Defines
Public Member Functions | Private Member Functions | Private Attributes
virtual_camera::RealCameraSynchronizer Class Reference

#include <RealCameraSynchronizer.hpp>

List of all members.

Public Member Functions

void addCamera (const std::string &topic, const RealCameraPtr &camera, const boost::shared_ptr< image_transport::ImageTransport > &it)
bool isSynchronized ()
 RealCameraSynchronizer (bool synchronize, const MutexPtr &syncMutex)
void setSynchronization (bool mode)

Private Member Functions

void generalCallback (const sensor_msgs::ImageConstPtr &image)
void handleSynchronization (const sensor_msgs::ImageConstPtr &image)
void pushMessages ()

Private Attributes

int cameraCount
std::map< std::string,
RealCameraPtr
camsByFrame
ros::Time mostRecentStamp
std::map< std::string,
sensor_msgs::ImageConstPtr > 
msgsByFrame
std::vector
< image_transport::Subscriber > 
realCamImgSubs
int recentCount
bool synchronize
MutexPtr syncMutex

Detailed Description

Is able to synchronize dynamic number of camera images on the most recent timestamp. It can also call for n topics n separate callbacks instead of one huge as in message_filters::TimeSynchronizer

Author:
Jan Brabec

Definition at line 23 of file RealCameraSynchronizer.hpp.


Constructor & Destructor Documentation

virtual_camera::RealCameraSynchronizer::RealCameraSynchronizer ( bool  synchronize,
const MutexPtr syncMutex 
)

Constructs the synchronizer

Parameters:
boolsynchronize true if the synchronization shall be turned on false otherwise.
constMutexPtr & syncMutex concurrent tasks performed by this Synchronizer will be synchronized under this mutex

Definition at line 6 of file RealCameraSynchronizer.cpp.


Member Function Documentation

void virtual_camera::RealCameraSynchronizer::addCamera ( const std::string &  topic,
const RealCameraPtr camera,
const boost::shared_ptr< image_transport::ImageTransport > &  it 
)

Adds RealCamera to the synchronizer.

Parameters:
std::stringtopic topic the images are on.
RealCameraPtrinstance of the real camera that handles the callback.
constboost::shared_ptr<image_transport::ImageTransport> & it needed to create a subscriber

Definition at line 26 of file RealCameraSynchronizer.cpp.

void virtual_camera::RealCameraSynchronizer::generalCallback ( const sensor_msgs::ImageConstPtr &  image) [private]

Definition at line 39 of file RealCameraSynchronizer.cpp.

void virtual_camera::RealCameraSynchronizer::handleSynchronization ( const sensor_msgs::ImageConstPtr &  image) [private]

Definition at line 50 of file RealCameraSynchronizer.cpp.

Returns:
bool true if synchronization is active, false otherwise

Definition at line 21 of file RealCameraSynchronizer.cpp.

Definition at line 71 of file RealCameraSynchronizer.cpp.

Can turn synchronization on/off

Parameters:
boolmode true for turning synchronization on, false otherwise.

Definition at line 16 of file RealCameraSynchronizer.cpp.


Member Data Documentation

Definition at line 31 of file RealCameraSynchronizer.hpp.

Definition at line 26 of file RealCameraSynchronizer.hpp.

Definition at line 32 of file RealCameraSynchronizer.hpp.

std::map<std::string, sensor_msgs::ImageConstPtr> virtual_camera::RealCameraSynchronizer::msgsByFrame [private]

Definition at line 27 of file RealCameraSynchronizer.hpp.

std::vector<image_transport::Subscriber> virtual_camera::RealCameraSynchronizer::realCamImgSubs [private]

Definition at line 28 of file RealCameraSynchronizer.hpp.

Definition at line 30 of file RealCameraSynchronizer.hpp.

Definition at line 25 of file RealCameraSynchronizer.hpp.

Definition at line 29 of file RealCameraSynchronizer.hpp.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Defines


virtual_camera
Author(s): Jan Brabec; maintained by Tomas Petricek / petrito1@cmp.felk.cvut
autogenerated on Tue Dec 10 2013 14:58:12