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 ()
ROSBAG2_TRANSPORT_PUBLIC void stop ()

Stopping recording.

The stop() is opposite to the record() operation. It will stop recording, dump all buffers to the disk and close writer. The record() 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.

Public Static Attributes

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

Protected Functions

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 ()
ROSBAG2_TRANSPORT_PUBLIC void start_discovery ()
ROSBAG2_TRANSPORT_PUBLIC void stop_discovery ()