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 Types | |
typedef std::map< std::string, ros::Publisher > | PublisherMap |
Private Member Functions | |
void | doKeepAlive () |
void | doPublish (rosbag::MessageInstance const &m) |
bool | pauseCallback (std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) |
void | printTime () |
void | processPause (const bool paused, ros::WallTime &horizon) |
int | readCharFromStdin () |
void | restoreTerminal () |
void | setupTerminal () |
void | updateRateTopicTime (const ros::MessageEvent< topic_tools::ShapeShifter const > &msg_event) |
void | waitForSubscribers () const |
Private Attributes | |
ros::Duration | bag_length_ |
std::vector< boost::shared_ptr< Bag > > | bags_ |
bool | delayed_ |
ros::Time | last_rate_control_ |
int | maxfd_ |
ros::NodeHandle | node_handle_ |
PlayerOptions | options_ |
termios | orig_flags_ |
bool | pause_change_requested_ |
bool | pause_for_topics_ |
ros::ServiceServer | pause_service_ |
bool | paused_ |
ros::WallTime | paused_time_ |
PublisherMap | publishers_ |
ros::Subscriber | rate_control_sub_ |
bool | requested_pause_state_ |
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.
|
private |
rosbag::Player::Player | ( | PlayerOptions const & | options | ) |
Definition at line 106 of file player.cpp.
rosbag::Player::~Player | ( | ) |
Definition at line 120 of file player.cpp.
|
private |
Definition at line 554 of file player.cpp.
|
private |
Definition at line 413 of file player.cpp.
|
private |
Definition at line 359 of file player.cpp.
|
private |
Definition at line 334 of file player.cpp.
|
private |
Definition at line 378 of file player.cpp.
void rosbag::Player::publish | ( | ) |
Definition at line 127 of file player.cpp.
|
private |
Definition at line 668 of file player.cpp.
|
private |
Definition at line 655 of file player.cpp.
|
private |
Definition at line 614 of file player.cpp.
|
private |
Definition at line 297 of file player.cpp.
|
private |
Definition at line 399 of file player.cpp.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |