PRIVATE. A helper class to track relevant state for publishing time. More...
#include <player.h>
Public Member Functions | |
ros::Time const & | getTime () const |
bool | horizonReached () |
void | runClock (const ros::WallDuration &duration) |
void | runStalledClock (const ros::WallDuration &duration) |
Sleep as necessary, but don't let the click run. More... | |
void | setHorizon (const ros::Time &horizon) |
void | setPublishFrequency (double publish_frequency) |
void | setTime (const ros::Time &time) |
void | setTimeScale (double time_scale) |
void | setWCHorizon (const ros::WallTime &horizon) |
void | stepClock () |
Step the clock to the horizon. More... | |
TimePublisher () | |
Private Attributes | |
ros::Time | current_ |
bool | do_publish_ |
ros::Time | horizon_ |
ros::WallTime | next_pub_ |
ros::NodeHandle | node_handle_ |
double | publish_frequency_ |
ros::Publisher | time_pub_ |
double | time_scale_ |
ros::WallDuration | wall_step_ |
ros::WallTime | wc_horizon_ |
PRIVATE. A helper class to track relevant state for publishing time.
rosbag::TimePublisher::TimePublisher | ( | ) |
Create a time publisher A publish_frequency of < 0 indicates that time shouldn't actually be published
Definition at line 707 of file player.cpp.
ros::Time const & rosbag::TimePublisher::getTime | ( | ) | const |
Get the current time
Definition at line 742 of file player.cpp.
bool rosbag::TimePublisher::horizonReached | ( | ) |
Definition at line 858 of file player.cpp.
void rosbag::TimePublisher::runClock | ( | const ros::WallDuration & | duration | ) |
Run the clock for AT MOST duration
If horizon has been reached this function returns immediately
Definition at line 747 of file player.cpp.
void rosbag::TimePublisher::runStalledClock | ( | const ros::WallDuration & | duration | ) |
Sleep as necessary, but don't let the click run.
Definition at line 826 of file player.cpp.
void rosbag::TimePublisher::setHorizon | ( | const ros::Time & | horizon | ) |
Set the horizon that the clock will run to
Definition at line 727 of file player.cpp.
void rosbag::TimePublisher::setPublishFrequency | ( | double | publish_frequency | ) |
Definition at line 713 of file player.cpp.
void rosbag::TimePublisher::setTime | ( | const ros::Time & | time | ) |
Set the current time
Definition at line 737 of file player.cpp.
void rosbag::TimePublisher::setTimeScale | ( | double | time_scale | ) |
Definition at line 722 of file player.cpp.
void rosbag::TimePublisher::setWCHorizon | ( | const ros::WallTime & | horizon | ) |
Set the horizon that the clock will run to
Definition at line 732 of file player.cpp.
void rosbag::TimePublisher::stepClock | ( | ) |
Step the clock to the horizon.
Definition at line 808 of file player.cpp.
|
private |
|
private |
|
private |
|
private |
|
private |