Skip to content

Commit

Permalink
allow for implementation of composable recorder via inheritance (#892)
Browse files Browse the repository at this point in the history
Signed-off-by: Bernd Pfrommer <bernd.pfrommer@gmail.com>
  • Loading branch information
berndpfrommer committed Oct 29, 2021
1 parent 3e311d9 commit ecf8313
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 5 deletions.
10 changes: 6 additions & 4 deletions rosbag2_transport/include/rosbag2_transport/recorder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,12 @@ class Recorder : public rclcpp::Node
ROSBAG2_TRANSPORT_PUBLIC
const rosbag2_cpp::Writer & get_writer_handle();

protected:
std::shared_ptr<rosbag2_cpp::Writer> writer_;
rosbag2_storage::StorageOptions storage_options_;
rosbag2_transport::RecordOptions record_options_;
std::atomic<bool> stop_discovery_;

private:
void topics_discovery();

Expand Down Expand Up @@ -111,10 +117,6 @@ class Recorder : public rclcpp::Node

void warn_if_new_qos_for_subscribed_topic(const std::string & topic_name);

std::shared_ptr<rosbag2_cpp::Writer> writer_;
rosbag2_storage::StorageOptions storage_options_;
rosbag2_transport::RecordOptions record_options_;
std::atomic<bool> stop_discovery_;
std::future<void> discovery_future_;
std::unordered_map<std::string, std::shared_ptr<rclcpp::GenericSubscription>> subscriptions_;
std::unordered_set<std::string> topics_warned_about_incompatibility_;
Expand Down
1 change: 0 additions & 1 deletion rosbag2_transport/src/rosbag2_transport/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,6 @@ Recorder::Recorder(
// TODO(karsten1987): Use this constructor later with parameter parsing.
// The reader, storage_options as well as record_options can be loaded via parameter.
// That way, the recorder can be used as a simple component in a component manager.
throw rclcpp::exceptions::UnimplementedError();
}

Recorder::Recorder(
Expand Down

1 comment on commit ecf8313

@ros-discourse
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This commit has been mentioned on ROS Discourse. There might be relevant details there:

https://discourse.ros.org/t/preparing-for-galactic-sync-2022-08-05/26737/3

Please sign in to comment.