PRIVATE. Player class to abstract the interface to the player. More...
#include <player.h>
Public Member Functions | |
Player (PlayerOptions const &options) | |
void | publish () |
~Player () | |
Private Member Functions | |
void | doKeepAlive () |
void | doPublish (rosbag::MessageInstance const &m) |
void | printTime () |
char | readCharFromStdin () |
void | restoreTerminal () |
void | setupTerminal () |
Private Attributes | |
ros::Duration | bag_length_ |
std::vector< boost::shared_ptr < Bag > > | bags_ |
int | maxfd_ |
ros::NodeHandle | node_handle_ |
PlayerOptions | options_ |
termios | orig_flags_ |
bool | paused_ |
ros::WallTime | paused_time_ |
std::map< std::string, ros::Publisher > | publishers_ |
ros::Time | start_time_ |
fd_set | stdin_fdset_ |
bool | terminal_modified_ |
TimePublisher | time_publisher_ |
TimeTranslator | time_translator_ |
PRIVATE. Player class to abstract the interface to the player.
This API is currently considered private, but will be released in the future after view.
Definition at line 142 of file player.h.
rosbag::Player::Player | ( | PlayerOptions const & | options | ) |
Definition at line 84 of file player.cpp.
rosbag::Player::~Player | ( | ) |
Definition at line 91 of file player.cpp.
void rosbag::Player::doKeepAlive | ( | ) | [private] |
Definition at line 346 of file player.cpp.
void rosbag::Player::doPublish | ( | rosbag::MessageInstance const & | m | ) | [private] |
Definition at line 249 of file player.cpp.
void rosbag::Player::printTime | ( | ) | [private] |
Definition at line 230 of file player.cpp.
void rosbag::Player::publish | ( | ) |
Definition at line 98 of file player.cpp.
char rosbag::Player::readCharFromStdin | ( | ) | [private] |
Definition at line 430 of file player.cpp.
void rosbag::Player::restoreTerminal | ( | ) | [private] |
Definition at line 420 of file player.cpp.
void rosbag::Player::setupTerminal | ( | ) | [private] |
Definition at line 400 of file player.cpp.
ros::Duration rosbag::Player::bag_length_ [private] |
std::vector<boost::shared_ptr<Bag> > rosbag::Player::bags_ [private] |
int rosbag::Player::maxfd_ [private] |
ros::NodeHandle rosbag::Player::node_handle_ [private] |
PlayerOptions rosbag::Player::options_ [private] |
termios rosbag::Player::orig_flags_ [private] |
bool rosbag::Player::paused_ [private] |
ros::WallTime rosbag::Player::paused_time_ [private] |
std::map<std::string, ros::Publisher> rosbag::Player::publishers_ [private] |
ros::Time rosbag::Player::start_time_ [private] |
fd_set rosbag::Player::stdin_fdset_ [private] |
bool rosbag::Player::terminal_modified_ [private] |
TimePublisher rosbag::Player::time_publisher_ [private] |