Class Recorder

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class Recorder : public rclcpp::Node

Public Functions

explicit ROSBAG2_TRANSPORT_PUBLIC Recorder(const rclcpp::NodeOptions &node_options)

Constructor and entry point for the composable recorder. Will call Recorder(node_name, node_options) constructor with node_name = “rosbag2_recorder”.

Parameters:

node_options – Node options which will be used during construction of the underlying node.

explicit ROSBAG2_TRANSPORT_PUBLIC Recorder(const std::string &node_name = "rosbag2_recorder", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())

Default constructor and entry point for the composable recorder. Will construct Recorder class and initialize record_options, storage_options from node parameters. At the end will call Recorder::record() to automatically start recording 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 Recorder(std::shared_ptr<rosbag2_cpp::Writer> writer, const rosbag2_storage::StorageOptions &storage_options, const rosbag2_transport::RecordOptions &record_options, const std::string &node_name = "rosbag2_recorder", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())

Constructor which will construct Recorder class with provided parameters and default KeyboardHandler class initialized with parameter which is disabling signal handlers in it.

Parameters:
  • writer – Shared pointer to the instance of the rosbag2_cpp::Writer class. Shall not be null_ptr.

  • storage_options – Storage options which will be applied to the rosbag2_cpp::writer class when recording will be started.

  • record_options – Settings for Recorder 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 Recorder(std::shared_ptr<rosbag2_cpp::Writer> writer, std::shared_ptr<KeyboardHandler> keyboard_handler, const rosbag2_storage::StorageOptions &storage_options, const rosbag2_transport::RecordOptions &record_options, const std::string &node_name = "rosbag2_recorder", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())

Constructor which will construct Recorder class with provided parameters.

Parameters:
  • writer – Shared pointer to the instance of the rosbag2_cpp::Writer class. Shall not be null_ptr.

  • keyboard_handler – Keyboard handler class uses to handle user input from keyboard.

  • storage_options – Storage options which will be applied to the rosbag2_cpp::writer class when recording will be started.

  • record_options – Settings for Recorder 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 ~Recorder()

Default destructor.

ROSBAG2_TRANSPORT_PUBLIC void record (const std::string &uri="")

Start recording.

The record() method will return almost immediately and recording will happen in background.

Parameters:

uri – If provided, it will override the storage_options.uri provided during construction.

ROSBAG2_TRANSPORT_PUBLIC void add_channel (const std::string &topic_name, const std::string &topic_type, const std::string &serialization_format="memory_view", const std::string &type_description_hash="", const std::vector< rclcpp::QoS > &offered_qos_profiles={})

Add a new channel (topic) to the rosbag2 writer to be recorded.

This is a direct Recorder API equivalent to the rosbag2_cpp::Writer::add_topic().

Note

This method does not require the message definition. The recorder will try to find the corresponding message definition by the given topic name and type.

Parameters:
  • topic_name – The name of the topic.

  • topic_type – The type of the topic.

  • serialization_format – The serialization format of the topic.

  • type_description_hash – REP-2011 type description hash of the topic.

  • offered_qos_profiles – The list of offered QoS profiles for the topic if available.

ROSBAG2_TRANSPORT_PUBLIC void add_channel (const std::string &topic_name, const std::string &topic_type, const std::string &message_definition_encoding, const std::string &encoded_message_definition, const std::string &serialization_format="memory_view", const std::string &type_description_hash="", const std::vector< rclcpp::QoS > &offered_qos_profiles={})

Add a new channel (topic) to the rosbag2 writer to be recorded.

This is a direct Recorder API equivalent to the rosbag2_cpp::Writer::add_topic().

Parameters:
  • topic_name – The name of the topic.

  • topic_type – The type of the topic.

  • message_definition_encoding – The encoding technique used in the encoded_message_definition e.g. “ros2idl”, “ros2msg”, “apex_json” or “unknown” if encoded_message_definition is empty.

  • encoded_message_definition – The fully encoded message definition for this type.

  • serialization_format – The serialization format of the topic.

  • type_description_hash – REP-2011 type description hash of the topic.

  • offered_qos_profiles – The list of offered QoS profiles for the topic if available.

ROSBAG2_TRANSPORT_PUBLIC void write_message (std::shared_ptr< rcutils_uint8_array_t > serialized_data, const std::string &topic_name, const rcutils_time_point_value_t &pub_timestamp, uint32_t sequence_number=0)

Write a serialized message to the bag file.

This is a direct Recorder API equivalent to the rosbag2_cpp::Writer::write().

Note

This method assumes that the topic has already been created via add_channel().

Note

If recorder is in pause mode, this method will return without writing anything.

Parameters:
  • serialized_data – The serialized message data to write.

  • topic_name – The name of the topic the message belongs to.

  • pub_timestamp – The original or publication timestamp of the message.

  • sequence_number – An optional sequence number of the message. If non-zero, sequence numbers should be unique per channel and increasing over time.

Throws:

std::runtime_error – if topic has not been added via add_channel().

ROSBAG2_TRANSPORT_PUBLIC void write_message (std::shared_ptr< rcutils_uint8_array_t > serialized_data, const std::string &topic_name, const rcutils_time_point_value_t &pub_timestamp, const rcutils_time_point_value_t &recv_timestamp, uint32_t sequence_number=0)

Write a serialized message to the bag file with receive timestamp.

This is a direct Recorder API equivalent to the rosbag2_cpp::Writer::write().

Note

This method assumes that the topic has already been created via add_channel().

Note

If recorder is in pause mode, this method will return without writing anything.

Parameters:
  • serialized_data – The serialized message data to write.

  • topic_name – The name of the topic the message belongs to.

  • pub_timestamp – The original or publication timestamp of the message in nanoseconds.

  • recv_timestamp – The timestamp of the message in nanoseconds when message was received.

  • sequence_number – An optional sequence number of the message. If non-zero, sequence numbers should be unique per channel and increasing over time.

Throws:

std::runtime_error – if topic has not been added via add_channel().

ROSBAG2_TRANSPORT_PUBLIC void on_messages_lost_in_transport (const std::string &topic_name, const rclcpp::QOSMessageLostInfo &qos_msgs_lost_info)

Updates recorder about lost messages on transport layer.

This a direct recorder API and this method is expected to be called when messages are lost in the transport layer. The recorder may use this information for logging or metrics.

Parameters:
  • topic_name – The name of the topic.

  • qos_msgs_lost_info – Information about lost messages.

ROSBAG2_TRANSPORT_PUBLIC uint64_t get_total_num_messages_lost_in_transport () const

Get total number of messages lost in transport layer.

Returns:

Total number of messages lost in transport layer.

ROSBAG2_TRANSPORT_PUBLIC void stop ()

Stopping recording.

The stop() is opposite to the record(uri) operation. It will stop recording, dump all buffers to the disk and close writer. The record(uri) can be called again after stop().

ROSBAG2_TRANSPORT_PUBLIC const std::unordered_set< std::string > & topics_using_fallback_qos () const
ROSBAG2_TRANSPORT_PUBLIC const std::unordered_map< std::string, std::shared_ptr< rclcpp::SubscriptionBase > > & subscriptions () const
ROSBAG2_TRANSPORT_PUBLIC const rosbag2_cpp::Writer & get_writer_handle ()
ROSBAG2_TRANSPORT_PUBLIC void pause ()

Pause the recording.

Will keep writer open and skip messages upon arrival on subscriptions.

ROSBAG2_TRANSPORT_PUBLIC void resume ()

Resume recording.

ROSBAG2_TRANSPORT_PUBLIC void toggle_paused ()

Pause if it was recording, continue recording if paused.

ROSBAG2_TRANSPORT_PUBLIC bool is_paused ()

Return the current paused state.

ROSBAG2_TRANSPORT_PUBLIC void start_discovery ()

Start discovery.

ROSBAG2_TRANSPORT_PUBLIC void stop_discovery ()

Stop discovery.

ROSBAG2_TRANSPORT_PUBLIC bool is_discovery_running () const

Return the current discovery state.

Public Static Attributes

static constexpr const auto kPauseResumeToggleKey = KeyboardHandler::KeyCode::SPACE

Protected Functions

ROSBAG2_TRANSPORT_PUBLIC void read_static_topics () noexcept
ROSBAG2_TRANSPORT_PUBLIC const std::vector< std::pair< std::string, std::string > > & get_static_topics () noexcept
ROSBAG2_TRANSPORT_PUBLIC std::unordered_map< std::string, std::string > get_requested_or_available_topics ()
ROSBAG2_TRANSPORT_PUBLIC rosbag2_cpp::Writer & get_writer ()
ROSBAG2_TRANSPORT_PUBLIC rosbag2_storage::StorageOptions & get_storage_options ()
ROSBAG2_TRANSPORT_PUBLIC rosbag2_transport::RecordOptions & get_record_options ()