
| Public Member Functions | |
| StereoSync () | |
| virtual | ~StereoSync () | 
| 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_ | 
| message_filters::Synchronizer < MyExactSyncPolicy > * | exactSync_ | 
| image_transport::SubscriberFilter | imageLeftSub_ | 
| image_transport::SubscriberFilter | imageRightSub_ | 
| ros::Publisher | rgbdImageCompressedPub_ | 
| ros::Publisher | rgbdImagePub_ | 
| boost::thread * | warningThread_ | 
Definition at line 57 of file stereo_sync.cpp.
| 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 204 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 207 of file stereo_sync.cpp.
| rtabmap_ros::StereoSync::StereoSync | ( | ) |  [inline] | 
Definition at line 60 of file stereo_sync.cpp.
| virtual rtabmap_ros::StereoSync::~StereoSync | ( | ) |  [inline, virtual] | 
Definition at line 67 of file stereo_sync.cpp.
| 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 | ||
| ) |  [inline, private] | 
Definition at line 155 of file stereo_sync.cpp.
| virtual void rtabmap_ros::StereoSync::onInit | ( | ) |  [inline, private, virtual] | 
Implements nodelet::Nodelet.
Definition at line 83 of file stereo_sync.cpp.
| void rtabmap_ros::StereoSync::warningLoop | ( | const std::string & | subscribedTopicsMsg, | 
| bool | approxSync | ||
| ) |  [inline, private] | 
Definition at line 136 of file stereo_sync.cpp.
Definition at line 205 of file stereo_sync.cpp.
| bool rtabmap_ros::StereoSync::callbackCalled_  [private] | 
Definition at line 194 of file stereo_sync.cpp.
| message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::StereoSync::cameraInfoLeftSub_  [private] | 
Definition at line 201 of file stereo_sync.cpp.
| message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::StereoSync::cameraInfoRightSub_  [private] | 
Definition at line 202 of file stereo_sync.cpp.
Definition at line 208 of file stereo_sync.cpp.
Definition at line 199 of file stereo_sync.cpp.
Definition at line 200 of file stereo_sync.cpp.
Definition at line 197 of file stereo_sync.cpp.
Definition at line 196 of file stereo_sync.cpp.
| boost::thread* rtabmap_ros::StereoSync::warningThread_  [private] | 
Definition at line 193 of file stereo_sync.cpp.