#include <time_publisher.h>
Public Member Functions | |
| bool | horizonReached () |
| void | runClock (const ros::WallDuration &duration) |
| void | runStalledClock (const ros::WallDuration &duration) |
| Sleep as necessary, but don't let the click run. | |
| void | setHorizon (const ros::Time &horizon) |
| void | setTime (const ros::Time &time) |
| void | setWCHorizon (const ros::WallTime &horizon) |
| SimpleTimePublisher (double publish_frequency, double time_scale) | |
| void | stepClock () |
| Step the clock to the horizon. | |
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_ |
Definition at line 48 of file time_publisher.h.
| SimpleTimePublisher::SimpleTimePublisher | ( | double | publish_frequency, | |
| double | time_scale | |||
| ) |
Create a time publisher A publish_frequency of < 0 indicates that time shouldn't actually be published
Definition at line 42 of file time_publisher.cpp.
| bool SimpleTimePublisher::horizonReached | ( | ) |
Definition at line 177 of file time_publisher.cpp.
| void SimpleTimePublisher::runClock | ( | const ros::WallDuration & | duration | ) |
Run the clock for AT MOST duration
If horizon has been reached this function returns immediately
Definition at line 74 of file time_publisher.cpp.
| void SimpleTimePublisher::runStalledClock | ( | const ros::WallDuration & | duration | ) |
Sleep as necessary, but don't let the click run.
Definition at line 145 of file time_publisher.cpp.
| void SimpleTimePublisher::setHorizon | ( | const ros::Time & | horizon | ) |
Set the horizon that the clock will run to
Definition at line 59 of file time_publisher.cpp.
| void SimpleTimePublisher::setTime | ( | const ros::Time & | time | ) |
Set the current time
Definition at line 69 of file time_publisher.cpp.
| void SimpleTimePublisher::setWCHorizon | ( | const ros::WallTime & | horizon | ) |
Set the horizon that the clock will run to
Definition at line 64 of file time_publisher.cpp.
| void SimpleTimePublisher::stepClock | ( | ) |
Step the clock to the horizon.
Definition at line 125 of file time_publisher.cpp.
ros::Time SimpleTimePublisher::current_ [private] |
Definition at line 94 of file time_publisher.h.
bool SimpleTimePublisher::do_publish_ [private] |
Definition at line 80 of file time_publisher.h.
ros::Time SimpleTimePublisher::horizon_ [private] |
Definition at line 93 of file time_publisher.h.
ros::WallTime SimpleTimePublisher::next_pub_ [private] |
Definition at line 90 of file time_publisher.h.
ros::NodeHandle SimpleTimePublisher::node_handle_ [private] |
Definition at line 85 of file time_publisher.h.
double SimpleTimePublisher::publish_frequency_ [private] |
Definition at line 82 of file time_publisher.h.
ros::Publisher SimpleTimePublisher::time_pub_ [private] |
Definition at line 86 of file time_publisher.h.
double SimpleTimePublisher::time_scale_ [private] |
Definition at line 83 of file time_publisher.h.
ros::WallDuration SimpleTimePublisher::wall_step_ [private] |
Definition at line 88 of file time_publisher.h.
ros::WallTime SimpleTimePublisher::wc_horizon_ [private] |
Definition at line 92 of file time_publisher.h.