Public Member Functions | Private Attributes | List of all members
rosbag::TimePublisher Class Reference

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_
 

Detailed Description

PRIVATE. A helper class to track relevant state for publishing time.

Definition at line 106 of file player.h.

Constructor & Destructor Documentation

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.

Member Function Documentation

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.

Member Data Documentation

ros::Time rosbag::TimePublisher::current_
private

Definition at line 158 of file player.h.

bool rosbag::TimePublisher::do_publish_
private

Definition at line 144 of file player.h.

ros::Time rosbag::TimePublisher::horizon_
private

Definition at line 157 of file player.h.

ros::WallTime rosbag::TimePublisher::next_pub_
private

Definition at line 154 of file player.h.

ros::NodeHandle rosbag::TimePublisher::node_handle_
private

Definition at line 149 of file player.h.

double rosbag::TimePublisher::publish_frequency_
private

Definition at line 146 of file player.h.

ros::Publisher rosbag::TimePublisher::time_pub_
private

Definition at line 150 of file player.h.

double rosbag::TimePublisher::time_scale_
private

Definition at line 147 of file player.h.

ros::WallDuration rosbag::TimePublisher::wall_step_
private

Definition at line 152 of file player.h.

ros::WallTime rosbag::TimePublisher::wc_horizon_
private

Definition at line 156 of file player.h.


The documentation for this class was generated from the following files:


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman
autogenerated on Sun Feb 3 2019 03:30:26