#include <stereo_bag_processor.h>
Public Member Functions | |
void | processBag (const std::string &filename) |
template<class C > | |
void | registerCallback (const C &callback) |
StereoBagProcessor (const std::string &stereo_base_topic) | |
Private Attributes | |
BagSubscriber< sensor_msgs::Image > | l_img_sub_ |
BagSubscriber < sensor_msgs::CameraInfo > | l_info_sub_ |
BagSubscriber< sensor_msgs::Image > | r_img_sub_ |
BagSubscriber < sensor_msgs::CameraInfo > | r_info_sub_ |
std::string | stereo_base_topic_ |
message_filters::TimeSynchronizer < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > | sync_ |
Definition at line 60 of file stereo_bag_processor.h.
bag_tools::StereoBagProcessor::StereoBagProcessor | ( | const std::string & | stereo_base_topic | ) | [inline] |
Definition at line 64 of file stereo_bag_processor.h.
void bag_tools::StereoBagProcessor::processBag | ( | const std::string & | filename | ) | [inline] |
Processes given bagfile, calls registered callback function when a synchronized stereo pair with camera infos is found.
Definition at line 81 of file stereo_bag_processor.h.
void bag_tools::StereoBagProcessor::registerCallback | ( | const C & | callback | ) | [inline] |
Definition at line 72 of file stereo_bag_processor.h.
BagSubscriber<sensor_msgs::Image> bag_tools::StereoBagProcessor::l_img_sub_ [private] |
Definition at line 146 of file stereo_bag_processor.h.
BagSubscriber<sensor_msgs::CameraInfo> bag_tools::StereoBagProcessor::l_info_sub_ [private] |
Definition at line 147 of file stereo_bag_processor.h.
BagSubscriber<sensor_msgs::Image> bag_tools::StereoBagProcessor::r_img_sub_ [private] |
Definition at line 146 of file stereo_bag_processor.h.
BagSubscriber<sensor_msgs::CameraInfo> bag_tools::StereoBagProcessor::r_info_sub_ [private] |
Definition at line 147 of file stereo_bag_processor.h.
std::string bag_tools::StereoBagProcessor::stereo_base_topic_ [private] |
Definition at line 149 of file stereo_bag_processor.h.
message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> bag_tools::StereoBagProcessor::sync_ [private] |
Definition at line 151 of file stereo_bag_processor.h.