Class PlayerClock

Inheritance Relationships

Derived Type

Class Documentation

class PlayerClock

Virtual interface used to drive the timing of bag playback. This clock should be used to query times and sleep between message playing, so that the complexity involved around time control and time sources is encapsulated in this one place.

Subclassed by rosbag2_cpp::TimeControllerClock

Public Types

typedef std::function<std::chrono::steady_clock::time_point()> NowFunction

Type representing an arbitrary steady time, used to measure real-time durations This type is never exposed by the PlayerClock - it is only used as input to the PlayerClock.

Public Functions

virtual ROSBAG2_CPP_PUBLIC ~PlayerClock() = default
virtual ROSBAG2_CPP_PUBLIC rcutils_time_point_value_t now () const =0

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

virtual ROSBAG2_CPP_PUBLIC bool sleep_until (rcutils_time_point_value_t until)=0

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 time)=0

See also

sleep_until

virtual ROSBAG2_CPP_PUBLIC bool set_rate (double rate)=0

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

Parameters:

rate – new rate of clock playback \bool false if rate is invalid for the clock implementation

virtual ROSBAG2_CPP_PUBLIC double get_rate () const =0
Returns:

the current playback rate.

virtual ROSBAG2_CPP_PUBLIC void pause ()=0

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 ()=0

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 =0

Return whether the clock is currently paused.

virtual ROSBAG2_CPP_PUBLIC void jump (rcutils_time_point_value_t time_point)=0

Change the current ROS time to an arbitrary time.

Note

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

Parameters:

time_point – Time point in ROS playback timeline.

virtual ROSBAG2_CPP_PUBLIC void jump (rclcpp::Time time)=0

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)=0

Add a callback to invoke if the jump threshold is exceeded.

See also

rclcpp::Clock::create_jump_callback