Class TimeControllerClock

Inheritance Relationships

Base Type

Class Documentation

class TimeControllerClock : public rosbag2_cpp::PlayerClock

Public Functions

ROSBAG2_CPP_PUBLIC TimeControllerClock(rcutils_time_point_value_t starting_time, NowFunction now_fn = std::chrono::steady_clock::now, std::chrono::milliseconds sleep_time_while_paused = std::chrono::milliseconds{100}, bool start_paused = false)

Constructor.

Parameters:
  • starting_time – provides an initial offset for managing time This will likely be the timestamp of the first message in the bag

  • now_fn – Function used to get the current steady time defaults to std::chrono::steady_clock::now Used to control for unit testing, or for specialized needs

  • sleep_time_while_paused – Amount of time to sleep in sleep_until when the clock is paused. Allows the caller to spin at a defined rate while receiving false

  • paused – Start the clock paused

virtual ROSBAG2_CPP_PUBLIC ~TimeControllerClock()
virtual ROSBAG2_CPP_PUBLIC rcutils_time_point_value_t now () const override

Calculate and return current rcutils_time_point_value_t based on starting time, playback rate, pause state.

virtual ROSBAG2_CPP_PUBLIC std::chrono::steady_clock::time_point ros_to_steady (rcutils_time_point_value_t ros_time) const override

Convert an arbitrary ROSTime to a SteadyTime, based on the current reference snapshot.

Parameters:

ros_time – - time point in ROSTime

Returns:

time point in steady clock i.e. std::chrono::steady_clock

virtual ROSBAG2_CPP_PUBLIC bool sleep_until (rcutils_time_point_value_t until) override

Try to sleep (non-busy) the current thread until the provided time is reached - according to this Clock

Return true if the time has been reached, false if it was not successfully reached after sleeping for the appropriate duration. The user should not take action based on this sleep until it returns true.

virtual ROSBAG2_CPP_PUBLIC bool sleep_until (rclcpp::Time until) override

See also

sleep_until

virtual ROSBAG2_CPP_PUBLIC bool set_rate (double rate) override

Change the rate of the flow of time for the clock.

To stop time,

See also

pause. It is not currently valid behavior to move time backwards.

Parameters:

rate – The new rate of time

Returns:

false if rate <= 0, true otherwise.

virtual ROSBAG2_CPP_PUBLIC double get_rate () const override

Return the current playback rate.

virtual ROSBAG2_CPP_PUBLIC void pause () override

Stop the flow of time of the clock. If this changes the pause state, this will wake any waiting sleep_until

virtual ROSBAG2_CPP_PUBLIC void resume () override

Start the flow of time of the clock If this changes the pause state, this will wake any waiting sleep_until

virtual ROSBAG2_CPP_PUBLIC bool is_paused () const override

Return whether the clock is currently paused.

virtual ROSBAG2_CPP_PUBLIC void jump (rcutils_time_point_value_t ros_time) override

Change the current ROS time to an arbitrary time.

Note

This will wake any waiting sleep_until and trigger any registered JumpHandler callbacks.

Note

The Player should not use this method while its queues are active (“during playback”) as an arbitrary time jump can make those queues, and the state of the Reader/Storage, invalid The current Player implementation should only use this method in between calls to play, to reset the initial time of the clock.

Parameters:

ros_time – The new ROS time to use as the basis for “now()”

virtual ROSBAG2_CPP_PUBLIC void jump (rclcpp::Time ros_time) override

See also

jump

virtual ROSBAG2_CPP_PUBLIC rclcpp::JumpHandler::SharedPtr create_jump_callback (rclcpp::JumpHandler::pre_callback_t pre_callback, rclcpp::JumpHandler::post_callback_t post_callback, const rcl_jump_threshold_t &threshold) override

Since a jump can only occur via a jump call by the owner of this Clock, jump callbacks are not handled in this clock. It is expected that the caller handles jumps in their calling code.

Returns:

nullptr