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 108 of file player.h.

Constructor & Destructor Documentation

◆ TimePublisher()

rosbag::TimePublisher::TimePublisher ( )

Create a time publisher A publish_frequency of < 0 indicates that time shouldn't actually be published

Definition at line 768 of file player.cpp.

Member Function Documentation

◆ getTime()

ros::Time const & rosbag::TimePublisher::getTime ( ) const

Get the current time

Definition at line 803 of file player.cpp.

◆ horizonReached()

bool rosbag::TimePublisher::horizonReached ( )

Definition at line 919 of file player.cpp.

◆ runClock()

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 808 of file player.cpp.

◆ runStalledClock()

void rosbag::TimePublisher::runStalledClock ( const ros::WallDuration duration)

Sleep as necessary, but don't let the click run.

Definition at line 887 of file player.cpp.

◆ setHorizon()

void rosbag::TimePublisher::setHorizon ( const ros::Time horizon)

Set the horizon that the clock will run to

Definition at line 788 of file player.cpp.

◆ setPublishFrequency()

void rosbag::TimePublisher::setPublishFrequency ( double  publish_frequency)

Definition at line 774 of file player.cpp.

◆ setTime()

void rosbag::TimePublisher::setTime ( const ros::Time time)

Set the current time

Definition at line 798 of file player.cpp.

◆ setTimeScale()

void rosbag::TimePublisher::setTimeScale ( double  time_scale)

Definition at line 783 of file player.cpp.

◆ setWCHorizon()

void rosbag::TimePublisher::setWCHorizon ( const ros::WallTime horizon)

Set the horizon that the clock will run to

Definition at line 793 of file player.cpp.

◆ stepClock()

void rosbag::TimePublisher::stepClock ( )

Step the clock to the horizon.

Definition at line 869 of file player.cpp.

Member Data Documentation

◆ current_

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

Definition at line 160 of file player.h.

◆ do_publish_

bool rosbag::TimePublisher::do_publish_
private

Definition at line 146 of file player.h.

◆ horizon_

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

Definition at line 159 of file player.h.

◆ next_pub_

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

Definition at line 156 of file player.h.

◆ node_handle_

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

Definition at line 151 of file player.h.

◆ publish_frequency_

double rosbag::TimePublisher::publish_frequency_
private

Definition at line 148 of file player.h.

◆ time_pub_

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

Definition at line 152 of file player.h.

◆ time_scale_

double rosbag::TimePublisher::time_scale_
private

Definition at line 149 of file player.h.

◆ wall_step_

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

Definition at line 154 of file player.h.

◆ wc_horizon_

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

Definition at line 158 of file player.h.


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


rosbag
Author(s): Tim Field, Jeremy Leibs, James Bowman, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:34:21