Class Player
- Defined in File player.hpp 
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. 
 - 
using reader_storage_options_pair_t = std::pair<std::unique_ptr<rosbag2_cpp::Reader>, rosbag2_storage::StorageOptions>
- Utility type for a pair of rosbag2_cpp::Reader and rosbag2_storage::StorageOptions. 
 - Public Functions - 
explicit ROSBAG2_TRANSPORT_PUBLIC Player(const rclcpp::NodeOptions &node_options)
- Constructor and entry point for the composable player. Will call Player(node_name, node_options) constructor with node_name = “rosbag2_player”. - Parameters:
- node_options – Node options which will be used during construction of the underlying node. 
 
 - 
explicit ROSBAG2_TRANSPORT_PUBLIC Player(const std::string &node_name = "rosbag2_player", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())
- Default constructor and entry point for the composable player. Will construct Player class and initialize play_options, storage_options from node parameters. At the end will call Player::play() to automatically start playback in a separate thread. - Parameters:
- node_name – Name for the underlying node. 
- node_options – Node options which will be used during construction of the underlying node. 
 
 
 - 
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())
- Constructor which will construct Player class with provided parameters and default rosbag2_cpp::reader and KeyboardHandler classes. - Note - The KeyboardHandler class will be initialized with parameter which is disabling signal handlers in it. - Parameters:
- storage_options – Storage options which will be applied to the rosbag2_cpp::reader after construction. 
- play_options – Playback settings for Player class. 
- node_name – Name for the underlying node. 
- node_options – Node options which will be used during construction of the underlying node. 
 
 
 - 
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())
- Constructor which will construct Player class with provided parameters and default KeyboardHandler class initialized with parameter which is disabling signal handlers in it. - Parameters:
- reader – Unique pointer to the rosbag2_cpp::Reader class which will be moved to the internal instance of the Player class during construction. 
- storage_options – Storage options which will be applied to the rosbag2_cpp::reader after construction. 
- play_options – Playback settings for Player class. 
- node_name – Name for the underlying node. 
- node_options – Node options which will be used during construction of the underlying node. 
 
 
 - Constructor which will construct Player class with provided parameters. - Parameters:
- keyboard_handler – Keyboard handler class uses to handle user input from keyboard. 
- reader – Unique pointer to the rosbag2_cpp::Reader class which will be moved to the internal instance of the Player class during construction. 
- storage_options – Storage options which will be applied to the rosbag2_cpp::reader after construction. 
- play_options – Playback settings for Player class. 
- node_name – Name for the underlying node. 
- node_options – Node options which will be used during construction of the underlying node. 
 
 
 - 
ROSBAG2_TRANSPORT_PUBLIC Player(const std::vector<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())
- Constructor which will construct Player class with multiple readers and provided storage options for each reader. - Note - The KeyboardHandler class will be initialized with parameter which is disabling signal handlers in it. - Parameters:
- storage_options – Storage options which will each be applied to a rosbag2_cpp::reader after construction. 
- play_options – Playback settings for Player class. 
- node_name – Name for the underlying node. 
- node_options – Node options which will be used during construction of the underlying node. 
 
 
 - 
ROSBAG2_TRANSPORT_PUBLIC Player(std::vector<reader_storage_options_pair_t> &&readers_with_options, const rosbag2_transport::PlayOptions &play_options, const std::string &node_name = "rosbag2_player", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())
- Constructor which will construct Player class with provided parameters. - Parameters:
- readers_with_options – Vector of pairs of unique pointer to the rosbag2_cpp::Reader class (which will be moved to the internal instance of the Player class during construction) and storage options (which will be applied to the rosbag2_cpp::reader when opening it). 
- play_options – Playback settings for Player class. 
- node_name – Name for the underlying node. 
- node_options – Node options which will be used during construction of the underlying node. 
 
 
 - Constructor which will construct Player class with provided parameters. - Parameters:
- readers_with_options – Vector of pairs of unique pointer to the rosbag2_cpp::Reader class (which will be moved to the internal instance of the Player class during construction) and storage options (which will be applied to the rosbag2_cpp::reader when opening it). 
- keyboard_handler – Keyboard handler class uses to handle user input from keyboard. 
- play_options – Playback settings for Player class. 
- node_name – Name for the underlying node. 
- node_options – Node options which will be used during construction of the underlying node. 
 
 
 - 
virtual ROSBAG2_TRANSPORT_PUBLIC ~Player()
- Default destructor. 
 - ROSBAG2_TRANSPORT_PUBLIC bool play ()
- Start playback asynchronously in a separate thread. - Returns:
- false if playback thread already running, otherwise true 
 
 - ROSBAG2_TRANSPORT_PUBLIC bool wait_for_playback_to_start (std::chrono::duration< double > timeout=std::chrono::seconds(-1))
- Waits on the condition variable until the play thread starts and the message’s queue will be filled. - Parameters:
- timeout – Maximum time in the fraction of seconds to wait for player to start. If timeout is negative, the wait_for_playback_to_start will be a blocking call. 
- Returns:
- true if playback successfully started during timeout, otherwise false. 
 
 - ROSBAG2_TRANSPORT_PUBLIC bool wait_for_playback_to_finish (std::chrono::duration< double > timeout=std::chrono::seconds(-1))
- Waits on the condition variable until the play thread finishes. - Parameters:
- timeout – Maximum time in the fraction of seconds to wait for player to finish. If timeout is negative, the wait_for_playback_to_finish will be a blocking call. 
- Returns:
- true if playback finished during timeout, otherwise false. 
 
 - 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 rcutils_time_point_value_t get_starting_time () const
- Getter method for starting time of the playback. - Returns:
- Returns timestamp of the first message in nanoseconds. 
 
 - ROSBAG2_TRANSPORT_PUBLIC rcutils_duration_value_t get_playback_duration () const
- Getter method for playback duration. - Returns:
- Returns duration of the playback in nanoseconds. 
 
 - 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_messagesmessages from the queue when paused.- This call will play the next - num_messagesfrom 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 
 
 - ROSBAG2_TRANSPORT_PUBLIC bool wait_for_sent_service_requests_to_finish (const std::string &service_name, std::chrono::duration< double > timeout=std::chrono::seconds(5))
- Wait until sent service requests will receive responses from service servers. - Note - The player node shall be spun in the executor in a parallel thread to be able to wait for responses. - Note - is service_name is empty the function will wait until all service requests sent to all service servers will finish. Timeout in this cases will be used for each service name. - Parameters:
- service_name – - Name of the service or service event from what to wait responses. 
- timeout – - Timeout in fraction of seconds to wait for. 
 
- Returns:
- true if service requests successfully finished, otherwise false. 
 
 - Public Static Attributes - static ROSBAG2_TRANSPORT_PUBLIC constexpr callback_handle_t invalid_callback_handle = 0
- Const describing invalid value for callback_handle. 
 - Protected Functions - ROSBAG2_TRANSPORT_PUBLIC std::unordered_map< std::string, std::shared_ptr< rclcpp::GenericPublisher > > get_publishers ()
- Getter for publishers corresponding to each topic. - Returns:
- Hashtable representing topic to publisher map excluding inner clock_publisher 
 
 - ROSBAG2_TRANSPORT_PUBLIC std::unordered_map< std::string, std::shared_ptr< rclcpp::GenericClient > > get_service_clients ()
- Getter for clients corresponding to each service name. - Returns:
- Hashtable representing service name to client 
 
 - ROSBAG2_TRANSPORT_PUBLIC std::unordered_map< std::string, std::shared_ptr< rclcpp_action::GenericClient > > get_action_clients ()
- Getter for clients corresponding to each action name. - Returns:
- Hashtable representing action name to client 
 
 - ROSBAG2_TRANSPORT_PUBLIC bool is_goal_handle_in_processing (std::string action_name, const rclcpp_action::GoalUUID &goal_id)
- Goal handle for action client is in processing. - Throws:
- std::exception – No action client is created for this action name. 
- Returns:
- true if goal handle is in processing, otherwise false. 
 
 - ROSBAG2_TRANSPORT_PUBLIC rclcpp::Publisher< rosgraph_msgs::msg::Clock >::SharedPtr get_clock_publisher ()
- Getter for inner clock_publisher. - Returns:
- Shared pointer to the inner clock_publisher 
 
 - ROSBAG2_TRANSPORT_PUBLIC size_t get_number_of_registered_on_play_msg_pre_callbacks ()
- Getter for the number of registered on_play_msg_pre_callbacks. - Returns:
- Number of registered on_play_msg_pre_callbacks 
 
 - ROSBAG2_TRANSPORT_PUBLIC size_t get_number_of_registered_on_play_msg_post_callbacks ()
- Getter for the number of registered on_play_msg_post_callbacks. - Returns:
- Number of registered on_play_msg_post_callbacks 
 
 - ROSBAG2_TRANSPORT_PUBLIC rosbag2_storage::StorageOptions get_storage_options ()
- Getter for the first of the currently stored storage options. - Returns:
- Copy of the first item in the StorageOptions vector 
 
 - ROSBAG2_TRANSPORT_PUBLIC std::vector< rosbag2_storage::StorageOptions > get_all_storage_options ()
- Getter for the currently stored storage options. - Returns:
- Copy of the currently stored storage options 
 
 - ROSBAG2_TRANSPORT_PUBLIC const rosbag2_transport::PlayOptions & get_play_options ()
- Getter for the currently stored play options. - Returns:
- Copy of the currently stored play options 
 
 
- 
using play_msg_callback_t = std::function<void(std::shared_ptr<rosbag2_storage::SerializedBagMessage>)>