#include <time_publisher.h>
Public Member Functions | |
| void | freezeTime () |
| void | initialize (double publish_frequency, double time_scale_factor=1.0) |
| void | setHorizon (ros::Time &horizon) |
| void | startTime (ros::Time bag_time) |
| void | stepTime (ros::Time bag_time) |
| TimePublisher () | |
| ~TimePublisher () | |
Private Member Functions | |
| const ros::Time & | getHorizon () |
| ros::Time | getSysTime () |
| void | publishTime () |
Private Attributes | |
| volatile bool | continue_ |
| bool | freeze_time_ |
| ros::Time | horizon_ |
| bool | is_started_ |
| ros::Time | last_pub_time_ |
| ros::Time | last_sys_time_ |
| ros::NodeHandle | node_handle |
| boost::mutex | offset_mutex_ |
| double | publish_freq_ |
| boost::thread * | publish_thread_ |
| ros::Publisher | time_pub |
| double | time_scale_factor_ |
Definition at line 97 of file time_publisher.h.
| TimePublisher::TimePublisher | ( | ) |
Definition at line 183 of file time_publisher.cpp.
| TimePublisher::~TimePublisher | ( | ) |
Definition at line 192 of file time_publisher.cpp.
| void TimePublisher::freezeTime | ( | ) |
Definition at line 219 of file time_publisher.cpp.
| const ros::Time & TimePublisher::getHorizon | ( | ) | [private] |
Definition at line 278 of file time_publisher.cpp.
| ros::Time TimePublisher::getSysTime | ( | ) | [private] |
Definition at line 286 of file time_publisher.cpp.
| void TimePublisher::initialize | ( | double | publish_frequency, | |
| double | time_scale_factor = 1.0 | |||
| ) |
Definition at line 201 of file time_publisher.cpp.
| void TimePublisher::publishTime | ( | ) | [private] |
Definition at line 296 of file time_publisher.cpp.
| void TimePublisher::setHorizon | ( | ros::Time & | horizon | ) |
Definition at line 271 of file time_publisher.cpp.
| void TimePublisher::startTime | ( | ros::Time | bag_time | ) |
Definition at line 231 of file time_publisher.cpp.
| void TimePublisher::stepTime | ( | ros::Time | bag_time | ) |
Definition at line 250 of file time_publisher.cpp.
volatile bool TimePublisher::continue_ [private] |
Definition at line 141 of file time_publisher.h.
bool TimePublisher::freeze_time_ [private] |
Definition at line 135 of file time_publisher.h.
ros::Time TimePublisher::horizon_ [private] |
Definition at line 132 of file time_publisher.h.
bool TimePublisher::is_started_ [private] |
Definition at line 136 of file time_publisher.h.
ros::Time TimePublisher::last_pub_time_ [private] |
Definition at line 133 of file time_publisher.h.
ros::Time TimePublisher::last_sys_time_ [private] |
Definition at line 134 of file time_publisher.h.
ros::NodeHandle TimePublisher::node_handle [private] |
Definition at line 130 of file time_publisher.h.
boost::mutex TimePublisher::offset_mutex_ [private] |
Definition at line 137 of file time_publisher.h.
double TimePublisher::publish_freq_ [private] |
Definition at line 129 of file time_publisher.h.
boost::thread* TimePublisher::publish_thread_ [private] |
Definition at line 138 of file time_publisher.h.
ros::Publisher TimePublisher::time_pub [private] |
Definition at line 131 of file time_publisher.h.
double TimePublisher::time_scale_factor_ [private] |
Definition at line 139 of file time_publisher.h.