2525#include < rclcpp/serialized_message.hpp>
2626#include < rosbag2_cpp/reader.hpp>
2727#include < rosbag2_cpp/readers/sequential_reader.hpp>
28+ #include < set>
29+ #include < vector>
2830
2931using rclcpp::Time;
3032using bag_time_t = rcutils_time_point_value_t ;
@@ -36,24 +38,26 @@ class BagProcessor
3638{
3739public:
3840 BagProcessor (
39- const std::string & bag_name, const std::string & topic, const std::string & topic_type ,
40- bag_time_t start_time, bag_time_t end_time)
41- : topic_(topic), start_time_(start_time), end_time_(end_time)
41+ const std::string & bag_name, const std::vector< std::string> & topics ,
42+ const std::string & topic_type, bag_time_t start_time, bag_time_t end_time)
43+ : start_time_(start_time), end_time_(end_time)
4244 {
4345 std::cout << " opening bag: " << bag_name << std::endl;
44- std::cout << " topic: " << topic << std::endl;
4546 reader_.open (bag_name);
4647 const auto meta = reader_.get_all_topics_and_types ();
47- const auto it = std::find_if (
48- meta.begin (), meta.end (), [topic, topic_type](const rosbag2_storage::TopicMetadata & m) {
49- return (m.name == topic && m.type == topic_type);
50- });
51- if (it == meta.end ()) {
52- std::cerr << " topic " << topic << " with type " << topic_type << " not found!" << std::endl;
53- throw (std::runtime_error (" topic not found!" ));
48+ for (const auto & topic : topics) {
49+ topics_.insert (topic);
50+ const auto it = std::find_if (
51+ meta.begin (), meta.end (), [topic, topic_type](const rosbag2_storage::TopicMetadata & m) {
52+ return (m.name == topic && m.type == topic_type);
53+ });
54+ if (it == meta.end ()) {
55+ std::cerr << " topic " << topic << " with type " << topic_type << " not found!" << std::endl;
56+ throw (std::runtime_error (" topic not found!" ));
57+ }
58+ std::cout << " found topic: " << it->name << " with type: " << it->type << std::endl;
59+ filter_.topics .push_back (topic);
5460 }
55-
56- filter_.topics .push_back (topic);
5761 reader_.set_filter (filter_);
5862 }
5963
@@ -68,7 +72,7 @@ class BagProcessor
6872
6973 while (reader_.has_next ()) {
7074 auto msg = reader_.read_next ();
71- if (!msg || topic_ != msg->topic_name ) {
75+ if (!msg || (topics_. find ( msg->topic_name ) == topics_. end ()) ) {
7276 continue ;
7377 }
7478 rclcpp::SerializedMessage serialized_msg (*msg->serialized_data );
@@ -82,7 +86,7 @@ class BagProcessor
8286 if (t > end_time_) {
8387 break ;
8488 }
85- mp->process (t, m);
89+ mp->process (t, msg-> topic_name , m);
8690 message_number++;
8791 }
8892 const auto stop = std::chrono::high_resolution_clock::now ();
@@ -95,7 +99,7 @@ class BagProcessor
9599private:
96100 rosbag2_cpp::Reader reader_;
97101 rosbag2_storage::StorageFilter filter_;
98- std::string topic_ ;
102+ std::set<std:: string> topics_ ;
99103 bag_time_t start_time_;
100104 bag_time_t end_time_;
101105 rclcpp::Serialization<T> serialization_;
0 commit comments