rosbag::TimePublisher Class Reference

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

#include <player.h>

List of all members.

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


Member Function Documentation

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

Get the current time

Definition at line 482 of file player.cpp.

bool rosbag::TimePublisher::horizonReached (  ) 

Definition at line 598 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 487 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 566 of file player.cpp.

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

Set the horizon that the clock will run to

Definition at line 467 of file player.cpp.

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

Definition at line 453 of file player.cpp.

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

Set the current time

Definition at line 477 of file player.cpp.

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

Definition at line 462 of file player.cpp.

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

Set the horizon that the clock will run to

Definition at line 472 of file player.cpp.

void rosbag::TimePublisher::stepClock (  ) 

Step the clock to the horizon.

Definition at line 548 of file player.cpp.


Member Data Documentation

ros::Time rosbag::TimePublisher::current_ [private]

Definition at line 133 of file player.h.

Definition at line 119 of file player.h.

ros::Time rosbag::TimePublisher::horizon_ [private]

Definition at line 132 of file player.h.

ros::WallTime rosbag::TimePublisher::next_pub_ [private]

Definition at line 129 of file player.h.

ros::NodeHandle rosbag::TimePublisher::node_handle_ [private]

Definition at line 124 of file player.h.

Definition at line 121 of file player.h.

ros::Publisher rosbag::TimePublisher::time_pub_ [private]

Definition at line 125 of file player.h.

Definition at line 122 of file player.h.

ros::WallDuration rosbag::TimePublisher::wall_step_ [private]

Definition at line 127 of file player.h.

ros::WallTime rosbag::TimePublisher::wc_horizon_ [private]

Definition at line 131 of file player.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


rosbag
Author(s): Jeremy Leibs (leibs@willowgarage.com), James Bowman (jamesb@willowgarage.com), Ken Conley (kwc@willowgarage.com), and Tim Field (tfield@willowgarage.com)
autogenerated on Fri Jan 11 10:11:44 2013