Class Recorder
Defined in File recorder.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class Recorder : public rclcpp::Node
Public Functions
-
explicit ROSBAG2_TRANSPORT_PUBLIC Recorder(const std::string &node_name = "rosbag2_recorder", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())
-
virtual ROSBAG2_TRANSPORT_PUBLIC ~Recorder()
- ROSBAG2_TRANSPORT_PUBLIC void record ()
-
inline const std::unordered_set<std::string> &topics_using_fallback_qos() const
-
inline const std::unordered_map<std::string, std::shared_ptr<rclcpp::GenericSubscription>> &subscriptions() const
- 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 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_EXPORT std::unordered_map< std::string, std::string > get_requested_or_available_topics ()
-
explicit ROSBAG2_TRANSPORT_PUBLIC Recorder(const std::string &node_name = "rosbag2_recorder", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())