#include <bag_player.h>
Public Member Functions | |
BagPlayer (const std::string &filename) throw (BagException) | |
ros::Time | get_time () |
template<class T > | |
void | register_callback (const std::string &topic, typename BagCallbackT< T >::Callback f) |
void | set_end (const ros::Time &end) |
void | set_playback_speed (double scale) |
void | set_start (const ros::Time &start) |
void | start_play () |
void | unregister_callback (const std::string &topic) |
virtual | ~BagPlayer () |
Public Attributes | |
Bag | bag |
Private Member Functions | |
ros::Time | real_time (const ros::Time &msg_time) |
Private Attributes | |
ros::Time | bag_end_ |
ros::Time | bag_start_ |
std::map< std::string, BagCallback * > | cbs_ |
ros::Time | last_message_time_ |
ros::Time | play_start_ |
double | playback_speed_ |
Definition at line 76 of file bag_player.h.
rosbag::BagPlayer::BagPlayer | ( | const std::string & | filename | ) | throw (BagException) |
Definition at line 8 of file bag_player.cpp.
rosbag::BagPlayer::~BagPlayer | ( | ) | [virtual] |
Definition at line 18 of file bag_player.cpp.
Definition at line 22 of file bag_player.cpp.
ros::Time rosbag::BagPlayer::real_time | ( | const ros::Time & | msg_time | ) | [private] |
Definition at line 39 of file bag_player.cpp.
void rosbag::BagPlayer::register_callback | ( | const std::string & | topic, |
typename BagCallbackT< T >::Callback | f | ||
) |
Definition at line 128 of file bag_player.h.
void rosbag::BagPlayer::set_end | ( | const ros::Time & | end | ) |
Definition at line 30 of file bag_player.cpp.
void rosbag::BagPlayer::set_playback_speed | ( | double | scale | ) |
Definition at line 34 of file bag_player.cpp.
void rosbag::BagPlayer::set_start | ( | const ros::Time & | start | ) |
Definition at line 26 of file bag_player.cpp.
void rosbag::BagPlayer::start_play | ( | ) |
Definition at line 43 of file bag_player.cpp.
void rosbag::BagPlayer::unregister_callback | ( | const std::string & | topic | ) |
Definition at line 65 of file bag_player.cpp.
Definition at line 114 of file bag_player.h.
ros::Time rosbag::BagPlayer::bag_end_ [private] |
Definition at line 121 of file bag_player.h.
ros::Time rosbag::BagPlayer::bag_start_ [private] |
Definition at line 120 of file bag_player.h.
std::map<std::string, BagCallback *> rosbag::BagPlayer::cbs_ [private] |
Definition at line 119 of file bag_player.h.
Definition at line 122 of file bag_player.h.
ros::Time rosbag::BagPlayer::play_start_ [private] |
Definition at line 124 of file bag_player.h.
double rosbag::BagPlayer::playback_speed_ [private] |
Definition at line 123 of file bag_player.h.