Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
rtabmap_ros::StereoSync Class Reference
Inheritance diagram for rtabmap_ros::StereoSync:
Inheritance graph
[legend]

Public Member Functions

 StereoSync ()
 
virtual ~StereoSync ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncPolicy
 

Private Member Functions

void callback (const sensor_msgs::ImageConstPtr &imageLeft, const sensor_msgs::ImageConstPtr &imageRight, const sensor_msgs::CameraInfoConstPtr &cameraInfoLeft, const sensor_msgs::CameraInfoConstPtr &cameraInfoRight)
 
virtual void onInit ()
 
void warningLoop (const std::string &subscribedTopicsMsg, bool approxSync)
 

Private Attributes

message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
 
bool callbackCalled_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeftSub_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRightSub_
 
double compressedRate_
 
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
 
image_transport::SubscriberFilter imageLeftSub_
 
image_transport::SubscriberFilter imageRightSub_
 
ros::Time lastCompressedPublished_
 
ros::Publisher rgbdImageCompressedPub_
 
ros::Publisher rgbdImagePub_
 
boost::thread * warningThread_
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Definition at line 57 of file stereo_sync.cpp.

Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> rtabmap_ros::StereoSync::MyApproxSyncPolicy
private

Definition at line 240 of file stereo_sync.cpp.

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> rtabmap_ros::StereoSync::MyExactSyncPolicy
private

Definition at line 243 of file stereo_sync.cpp.

Constructor & Destructor Documentation

rtabmap_ros::StereoSync::StereoSync ( )
inline

Definition at line 60 of file stereo_sync.cpp.

virtual rtabmap_ros::StereoSync::~StereoSync ( )
inlinevirtual

Definition at line 68 of file stereo_sync.cpp.

Member Function Documentation

void rtabmap_ros::StereoSync::callback ( const sensor_msgs::ImageConstPtr &  imageLeft,
const sensor_msgs::ImageConstPtr &  imageRight,
const sensor_msgs::CameraInfoConstPtr &  cameraInfoLeft,
const sensor_msgs::CameraInfoConstPtr &  cameraInfoRight 
)
inlineprivate

Definition at line 158 of file stereo_sync.cpp.

virtual void rtabmap_ros::StereoSync::onInit ( )
inlineprivatevirtual

Implements nodelet::Nodelet.

Definition at line 84 of file stereo_sync.cpp.

void rtabmap_ros::StereoSync::warningLoop ( const std::string &  subscribedTopicsMsg,
bool  approxSync 
)
inlineprivate

Definition at line 139 of file stereo_sync.cpp.

Member Data Documentation

message_filters::Synchronizer<MyApproxSyncPolicy>* rtabmap_ros::StereoSync::approxSync_
private

Definition at line 241 of file stereo_sync.cpp.

bool rtabmap_ros::StereoSync::callbackCalled_
private

Definition at line 229 of file stereo_sync.cpp.

message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::StereoSync::cameraInfoLeftSub_
private

Definition at line 237 of file stereo_sync.cpp.

message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::StereoSync::cameraInfoRightSub_
private

Definition at line 238 of file stereo_sync.cpp.

double rtabmap_ros::StereoSync::compressedRate_
private

Definition at line 227 of file stereo_sync.cpp.

message_filters::Synchronizer<MyExactSyncPolicy>* rtabmap_ros::StereoSync::exactSync_
private

Definition at line 244 of file stereo_sync.cpp.

image_transport::SubscriberFilter rtabmap_ros::StereoSync::imageLeftSub_
private

Definition at line 235 of file stereo_sync.cpp.

image_transport::SubscriberFilter rtabmap_ros::StereoSync::imageRightSub_
private

Definition at line 236 of file stereo_sync.cpp.

ros::Time rtabmap_ros::StereoSync::lastCompressedPublished_
private

Definition at line 230 of file stereo_sync.cpp.

ros::Publisher rtabmap_ros::StereoSync::rgbdImageCompressedPub_
private

Definition at line 233 of file stereo_sync.cpp.

ros::Publisher rtabmap_ros::StereoSync::rgbdImagePub_
private

Definition at line 232 of file stereo_sync.cpp.

boost::thread* rtabmap_ros::StereoSync::warningThread_
private

Definition at line 228 of file stereo_sync.cpp.


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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19