Class Player

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class Player : public rclcpp::Node

Public Types

using play_msg_callback_t = std::function<void(std::shared_ptr<rosbag2_storage::SerializedBagMessage>)>

Type for callback functions.

using callback_handle_t = uint64_t

Callback handle returning from add_on_play_message_pre_callback and add_on_play_message_post_callback and used as an argument for delete_on_play_message_callback.

Public Functions

explicit ROSBAG2_TRANSPORT_PUBLIC Player(const std::string &node_name = "rosbag2_player", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())
ROSBAG2_TRANSPORT_PUBLIC Player(const rosbag2_storage::StorageOptions &storage_options, const rosbag2_transport::PlayOptions &play_options, const std::string &node_name = "rosbag2_player", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())
ROSBAG2_TRANSPORT_PUBLIC Player(std::unique_ptr<rosbag2_cpp::Reader> reader, const rosbag2_storage::StorageOptions &storage_options, const rosbag2_transport::PlayOptions &play_options, const std::string &node_name = "rosbag2_player", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())
ROSBAG2_TRANSPORT_PUBLIC Player(std::unique_ptr<rosbag2_cpp::Reader> reader, std::shared_ptr<KeyboardHandler> keyboard_handler, const rosbag2_storage::StorageOptions &storage_options, const rosbag2_transport::PlayOptions &play_options, const std::string &node_name = "rosbag2_player", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())
virtual ROSBAG2_TRANSPORT_PUBLIC ~Player()
ROSBAG2_TRANSPORT_PUBLIC bool play ()
ROSBAG2_TRANSPORT_PUBLIC void stop ()

Unpause if in pause mode, stop playback and exit from play.

virtual ROSBAG2_TRANSPORT_PUBLIC void pause ()

Pause the flow of time for playback.

virtual ROSBAG2_TRANSPORT_PUBLIC void resume ()

Start the flow of time for playback.

ROSBAG2_TRANSPORT_PUBLIC void toggle_paused ()

Pause if time running, resume if paused.

ROSBAG2_TRANSPORT_PUBLIC bool is_paused () const

Return whether the playback is currently paused.

ROSBAG2_TRANSPORT_PUBLIC double get_rate () const

Return current playback rate.

virtual ROSBAG2_TRANSPORT_PUBLIC bool set_rate (double)

Set the playback rate.

Returns:

false if an invalid value was provided (<= 0).

virtual ROSBAG2_TRANSPORT_PUBLIC bool play_next ()

Playing next message from queue when in pause.

This is blocking call and it will wait until next available message will be published or rclcpp context shut down.

Note

If internal player queue is starving and storage has not been completely loaded, this method will wait until new element will be pushed to the queue.

Returns:

true if player in pause mode and successfully played next message, otherwise false.

virtual ROSBAG2_TRANSPORT_PUBLIC size_t burst (const size_t num_messages)

Burst the next num_messages messages from the queue when paused.

This call will play the next num_messages from the queue in burst mode. The timing of the messages is ignored.

Note

If internal player queue is starving and storage has not been completely loaded, this method will wait until new element will be pushed to the queue.

Parameters:

num_messages – The number of messages to burst from the queue. Specifying zero means no limit (i.e. burst the entire bag).

Returns:

The number of messages that was played.

ROSBAG2_TRANSPORT_PUBLIC void seek (rcutils_time_point_value_t time_point)

Advance player to the message with closest timestamp >= time_point.

This is blocking call and it will wait until current message will be published and message queue will be refilled. If time_point is before the beginning of the bag, then playback time will be set to the beginning of the bag. If time_point is after the end of the bag, playback time will be set to the end of the bag, which will then end playback, or if loop is enabled then will start playing at the beginning of the next loop.

Parameters:

time_point – Time point in ROS playback timeline.

ROSBAG2_TRANSPORT_PUBLIC callback_handle_t add_on_play_message_pre_callback (const play_msg_callback_t &callback)

Adding callable object as handler for pre-callback on play message.

Note

In case of registering multiple callbacks later-registered callbacks will be called first.

Parameters:

callback – Callable which will be called before next message will be published.

Returns:

Returns newly created callback handle if callback was successfully added, otherwise returns invalid_callback_handle.

ROSBAG2_TRANSPORT_PUBLIC callback_handle_t add_on_play_message_post_callback (const play_msg_callback_t &callback)

Adding callable object as handler for post-callback on play message.

Note

In case of registering multiple callbacks later-registered callbacks will be called first.

Parameters:

callback – Callable which will be called after next message will be published.

Returns:

Returns newly created callback handle if callback was successfully added, otherwise returns invalid_callback_handle.

ROSBAG2_TRANSPORT_PUBLIC void delete_on_play_message_callback (const callback_handle_t &handle)

Delete pre or post on play message callback from internal player lists.

Parameters:

handle – Callback’s handle returned from add_on_play_message_pre_callback or add_on_play_message_post_callback

Public Static Attributes

static constexpr ROSBAG2_TRANSPORT_PUBLIC callback_handle_t invalid_callback_handle   = 0

Const describing invalid value for callback_handle.

Protected Attributes

std::mutex on_play_msg_callbacks_mutex_
std::forward_list<play_msg_callback_data> on_play_msg_pre_callbacks_
std::forward_list<play_msg_callback_data> on_play_msg_post_callbacks_
bool is_ready_to_play_from_queue_ = {false}
std::mutex ready_to_play_from_queue_mutex_
std::condition_variable ready_to_play_from_queue_cv_
rclcpp::Publisher<rosgraph_msgs::msg::Clock>::SharedPtr clock_publisher_
std::unordered_map<std::string, std::shared_ptr<PlayerPublisher>> publishers_
struct play_msg_callback_data

Public Members

callback_handle_t handle
play_msg_callback_t callback
class PlayerPublisher

Public Functions

inline explicit PlayerPublisher(std::shared_ptr<rclcpp::GenericPublisher> pub, bool disable_loan_message)
inline ~PlayerPublisher()
inline void publish(const rclcpp::SerializedMessage &message)
inline std::shared_ptr<rclcpp::GenericPublisher> generic_publisher()