diff --git a/ros2bag/ros2bag/verb/record.py b/ros2bag/ros2bag/verb/record.py index 8b491ef07..ac1f6d085 100644 --- a/ros2bag/ros2bag/verb/record.py +++ b/ros2bag/ros2bag/verb/record.py @@ -84,6 +84,10 @@ def add_arguments(self, parser, cli_name): # noqa: D102 '--exclude-regex', default='', help='Exclude topics and services containing provided regular expression. ' 'Works on top of --all, --all-topics, or --regex.') + parser.add_argument( + '--exclude-topic-types', type=str, default=[], metavar='ExcludeTypes', nargs='+', + help='List of topic types not being recorded. ' + 'Works on top of --all, --all-topics, or --regex.') parser.add_argument( '--exclude-topics', type=str, metavar='Topic', nargs='+', help='List of topics not being recorded. ' @@ -230,6 +234,10 @@ def main(self, *, args): # noqa: D102 return print_error('--exclude-topics argument requires either --all, --all-topics ' 'or --regex') + if args.exclude_topic_types and not (args.regex or args.all or args.all_topics): + return print_error('--exclude-topic-types argument requires either --all, ' + '--all-topics or --regex') + if args.exclude_services and not (args.regex or args.all or args.all_services): return print_error('--exclude-services argument requires either --all, --all-services ' 'or --regex') @@ -288,6 +296,7 @@ def main(self, *, args): # noqa: D102 record_options.is_discovery_disabled = args.no_discovery record_options.topics = args.topics record_options.topic_types = args.topic_types + record_options.exclude_topic_types = args.exclude_topic_types record_options.rmw_serialization_format = args.serialization_format record_options.topic_polling_interval = datetime.timedelta( milliseconds=args.polling_interval) diff --git a/rosbag2_py/rosbag2_py/_transport.pyi b/rosbag2_py/rosbag2_py/_transport.pyi index 3ec90a501..ccca99835 100644 --- a/rosbag2_py/rosbag2_py/_transport.pyi +++ b/rosbag2_py/rosbag2_py/_transport.pyi @@ -40,6 +40,7 @@ class RecordOptions: compression_threads: int exclude_regex: str exclude_service_events: List[str] + exclude_topic_types: List[str] exclude_topics: List[str] ignore_leaf_topics: bool include_hidden_topics: bool diff --git a/rosbag2_py/src/rosbag2_py/_transport.cpp b/rosbag2_py/src/rosbag2_py/_transport.cpp index 96f0b5865..ce508e2a2 100644 --- a/rosbag2_py/src/rosbag2_py/_transport.cpp +++ b/rosbag2_py/src/rosbag2_py/_transport.cpp @@ -371,6 +371,7 @@ PYBIND11_MODULE(_transport, m) { .def_readwrite("is_discovery_disabled", &RecordOptions::is_discovery_disabled) .def_readwrite("topics", &RecordOptions::topics) .def_readwrite("topic_types", &RecordOptions::topic_types) + .def_readwrite("exclude_topic_types", &RecordOptions::exclude_topic_types) .def_readwrite("rmw_serialization_format", &RecordOptions::rmw_serialization_format) .def_readwrite("topic_polling_interval", &RecordOptions::topic_polling_interval) .def_readwrite("regex", &RecordOptions::regex) diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp index 3112b0b06..c316eb404 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp @@ -189,7 +189,7 @@ TEST_P(Rosbag2CPPGetServiceInfoTest, get_service_info_for_bag_with_services_only storage_options.storage_id = storage_id; storage_options.uri = bag_path_str; rosbag2_transport::RecordOptions record_options = - {false, true, false, {}, {}, {}, {"/rosout"}, {}, "cdr", 100ms}; + {false, true, false, {}, {}, {}, {"/rosout"}, {}, {}, "cdr", 100ms}; auto recorder = std::make_shared( std::move(writer), storage_options, record_options); recorder->record(); @@ -267,7 +267,7 @@ TEST_P(Rosbag2CPPGetServiceInfoTest, get_service_info_for_bag_with_topics_and_se storage_options.storage_id = storage_id; storage_options.uri = bag_path_str; rosbag2_transport::RecordOptions record_options = - {true, true, false, {}, {}, {}, {"/rosout"}, {}, "cdr", 100ms}; + {true, true, false, {}, {}, {}, {"/rosout"}, {}, {}, "cdr", 100ms}; auto recorder = std::make_shared( std::move(writer), storage_options, record_options); recorder->record(); diff --git a/rosbag2_transport/include/rosbag2_transport/record_options.hpp b/rosbag2_transport/include/rosbag2_transport/record_options.hpp index 044a5da4f..50dbfd30a 100644 --- a/rosbag2_transport/include/rosbag2_transport/record_options.hpp +++ b/rosbag2_transport/include/rosbag2_transport/record_options.hpp @@ -37,6 +37,7 @@ struct RecordOptions std::vector topic_types; std::vector services; // service event topic std::vector exclude_topics; + std::vector exclude_topic_types; std::vector exclude_service_events; // service event topic std::string rmw_serialization_format; std::chrono::milliseconds topic_polling_interval{100}; diff --git a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp index 52408fe02..08b1a50a8 100644 --- a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp +++ b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp @@ -228,6 +228,9 @@ RecordOptions get_record_options_from_node_params(rclcpp::Node & node) record_options.exclude_topics = node.declare_parameter>( "record.exclude_topics", std::vector()); + record_options.exclude_topic_types = node.declare_parameter>( + "record.exclude_topic_types", std::vector()); + // Convert service name to service event topic name auto exclude_service_list = node.declare_parameter>( "record.exclude_services", std::vector()); diff --git a/rosbag2_transport/src/rosbag2_transport/record_options.cpp b/rosbag2_transport/src/rosbag2_transport/record_options.cpp index 090087d5b..ce4ea8ca2 100644 --- a/rosbag2_transport/src/rosbag2_transport/record_options.cpp +++ b/rosbag2_transport/src/rosbag2_transport/record_options.cpp @@ -32,6 +32,7 @@ Node convert::encode( node["is_discovery_disabled"] = record_options.is_discovery_disabled; node["topics"] = record_options.topics; node["topic_types"] = record_options.topic_types; + node["exclude_topic_types"] = record_options.exclude_topic_types; node["services"] = record_options.services; node["rmw_serialization_format"] = record_options.rmw_serialization_format; node["topic_polling_interval"] = record_options.topic_polling_interval; @@ -71,6 +72,9 @@ bool convert::decode( optional_assign(node, "regex", record_options.regex); optional_assign(node, "exclude_regex", record_options.exclude_regex); optional_assign>(node, "exclude_topics", record_options.exclude_topics); + optional_assign>( + node, "exclude_topic_types", + record_options.exclude_topic_types); optional_assign>( node, "exclude_services", record_options.exclude_service_events); optional_assign(node, "node_prefix", record_options.node_prefix); diff --git a/rosbag2_transport/src/rosbag2_transport/topic_filter.cpp b/rosbag2_transport/src/rosbag2_transport/topic_filter.cpp index 933c4a71d..1f184b223 100644 --- a/rosbag2_transport/src/rosbag2_transport/topic_filter.cpp +++ b/rosbag2_transport/src/rosbag2_transport/topic_filter.cpp @@ -170,6 +170,10 @@ bool TopicFilter::take_topic( } } + if (topic_type_in_list(topic_type, record_options_.exclude_topic_types)) { + return false; + } + if (topic_in_list(topic_name, record_options_.exclude_topics)) { return false; } diff --git a/rosbag2_transport/test/resources/recorder_node_params.yaml b/rosbag2_transport/test/resources/recorder_node_params.yaml index 9d321267b..dc9c13c81 100644 --- a/rosbag2_transport/test/resources/recorder_node_params.yaml +++ b/rosbag2_transport/test/resources/recorder_node_params.yaml @@ -9,6 +9,7 @@ recorder_params_node: is_discovery_disabled: true topics: ["topic", "other_topic"] topic_types: ["std_msgs/msg/Header", "geometry_msgs/msg/Pose"] + exclude_topic_types: ["sensor_msgs/msg/Image"] services: ["service", "other_service"] rmw_serialization_format: "cdr" topic_polling_interval: @@ -41,4 +42,4 @@ recorder_params_node: snapshot_mode: false custom_data: ["key1=value1", "key2=value2"] start_time_ns: 0 - end_time_ns: 100000 \ No newline at end of file + end_time_ns: 100000 diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp index 1877bbc91..444581363 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp @@ -216,6 +216,8 @@ TEST_P(ComposableRecorderTests, recorder_can_parse_parameters_from_file) { EXPECT_EQ(record_options.topics, topics); std::vector topic_types {"std_msgs/msg/Header", "geometry_msgs/msg/Pose"}; EXPECT_EQ(record_options.topic_types, topic_types); + std::vector exclude_topic_types {"sensor_msgs/msg/Image"}; + EXPECT_EQ(record_options.exclude_topic_types, exclude_topic_types); std::vector services {"/service/_service_event", "/other_service/_service_event"}; EXPECT_EQ(record_options.services, services); EXPECT_EQ(record_options.rmw_serialization_format, "cdr"); diff --git a/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp b/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp index 67b903f0c..89d043d60 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp @@ -191,7 +191,7 @@ TEST_F(RecordIntegrationTestFixture, test_keyboard_controls) auto keyboard_handler = std::make_shared(); rosbag2_transport::RecordOptions record_options = - {true, false, false, {}, {}, {}, {}, {}, "rmw_format", 100ms}; + {true, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; record_options.start_paused = true; auto recorder = std::make_shared( diff --git a/rosbag2_transport/test/rosbag2_transport/test_record.cpp b/rosbag2_transport/test/rosbag2_transport/test_record.cpp index 520ebb17a..76a280f6c 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record.cpp @@ -47,7 +47,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are pub_manager.setup_publisher(string_topic, string_message, 2); rosbag2_transport::RecordOptions record_options = - {false, false, false, {string_topic, array_topic}, {}, {}, {}, {}, "rmw_format", 50ms}; + {false, false, false, {string_topic, array_topic}, {}, {}, {}, {}, {}, "rmw_format", 50ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -98,7 +98,7 @@ TEST_F(RecordIntegrationTestFixture, can_record_again_after_stop) pub_manager.setup_publisher(string_topic, string_message, 2); rosbag2_transport::RecordOptions record_options = - {false, false, false, {string_topic}, {}, {}, {}, {}, "rmw_format", 50ms}; + {false, false, false, {string_topic}, {}, {}, {}, {}, {}, "rmw_format", 50ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -150,7 +150,7 @@ TEST_F(RecordIntegrationTestFixture, qos_is_stored_in_metadata) pub_manager.setup_publisher(topic, string_message, 2); rosbag2_transport::RecordOptions record_options = - {false, false, false, {topic}, {}, {}, {}, {}, "rmw_format", 100ms}; + {false, false, false, {topic}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -214,7 +214,7 @@ TEST_F(RecordIntegrationTestFixture, records_sensor_data) pub_manager.setup_publisher(topic, string_message, 2, rclcpp::SensorDataQoS()); rosbag2_transport::RecordOptions record_options = - {false, false, false, {topic}, {}, {}, {}, {}, "rmw_format", 100ms}; + {false, false, false, {topic}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -257,7 +257,7 @@ TEST_F(RecordIntegrationTestFixture, receives_latched_messages) pub_manager.run_publishers(); rosbag2_transport::RecordOptions record_options = - {false, false, false, {topic}, {}, {}, {}, {}, "rmw_format", 100ms}; + {false, false, false, {topic}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -302,7 +302,7 @@ TEST_F(RecordIntegrationTestFixture, mixed_qos_subscribes) { topic, profile_transient_local); rosbag2_transport::RecordOptions record_options = - {false, false, false, {topic}, {}, {}, {}, {}, "rmw_format", 100ms}; + {false, false, false, {topic}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -351,7 +351,7 @@ TEST_F(RecordIntegrationTestFixture, duration_and_noncompatibility_policies_mixe auto publisher_liveliness = create_pub(profile_liveliness); rosbag2_transport::RecordOptions record_options = - {false, false, false, {topic}, {}, {}, {}, {}, "rmw_format", 100ms}; + {false, false, false, {topic}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -391,7 +391,7 @@ TEST_F(RecordIntegrationTestFixture, write_split_callback_is_called) mock_writer.set_max_messages_per_file(5); rosbag2_transport::RecordOptions record_options = - {false, false, false, {string_topic}, {}, {}, {}, {}, "rmw_format", 100ms}; + {false, false, false, {string_topic}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp index 706aa055b..c6121bf8f 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp @@ -50,7 +50,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are pub_manager.setup_publisher(string_topic, string_message, 2); rosbag2_transport::RecordOptions record_options = - {true, false, false, {}, {}, {}, {"/rosout"}, {}, "rmw_format", 100ms}; + {true, false, false, {}, {}, {}, {"/rosout"}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -97,7 +97,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a "test_service_2"); rosbag2_transport::RecordOptions record_options = - {false, true, false, {}, {}, {}, {"/rosout"}, {}, "rmw_format", 100ms}; + {false, true, false, {}, {}, {}, {"/rosout"}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -139,7 +139,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a pub_manager.setup_publisher(string_topic, string_message, 1); rosbag2_transport::RecordOptions record_options = - {true, true, false, {}, {}, {}, {"/rosout"}, {}, "rmw_format", 100ms}; + {true, true, false, {}, {}, {}, {"/rosout"}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all_ignore_leaf_topics.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all_ignore_leaf_topics.cpp index 77885e9ff..8fa487b4d 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all_ignore_leaf_topics.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all_ignore_leaf_topics.cpp @@ -52,7 +52,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_two_topics_ignore_l pub_manager.setup_publisher(string_topic, string_message, 2); rosbag2_transport::RecordOptions record_options = - {true, false, false, {}, {}, {}, {}, {}, "rmw_format", 100ms}; + {true, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; record_options.ignore_leaf_topics = true; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all_include_unpublished_topics.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all_include_unpublished_topics.cpp index 1e63fb6da..018e260f4 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all_include_unpublished_topics.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all_include_unpublished_topics.cpp @@ -35,7 +35,7 @@ TEST_F(RecordIntegrationTestFixture, record_all_include_unpublished_false_ignore string_topic, 10, [](test_msgs::msg::Strings::ConstSharedPtr) {}); rosbag2_transport::RecordOptions record_options = - {true, false, false, {}, {}, {}, {}, {}, "rmw_format", 100ms}; + {true, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; record_options.include_unpublished_topics = false; auto recorder = std::make_shared(writer_, storage_options_, record_options); recorder->record(); @@ -53,7 +53,7 @@ TEST_F(RecordIntegrationTestFixture, record_all_include_unpublished_true_include string_topic, 10, [](test_msgs::msg::Strings::ConstSharedPtr) {}); rosbag2_transport::RecordOptions record_options = - {true, false, false, {}, {}, {}, {}, {}, "rmw_format", 100ms}; + {true, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; record_options.include_unpublished_topics = true; auto recorder = std::make_shared(writer_, storage_options_, record_options); recorder->record(); @@ -73,7 +73,7 @@ TEST_F( string_topic, 10, [](test_msgs::msg::Strings::ConstSharedPtr) {}); rosbag2_transport::RecordOptions record_options = - {true, false, false, {}, {}, {}, {}, {}, "rmw_format", 100ms}; + {true, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; record_options.include_unpublished_topics = false; auto recorder = std::make_shared(writer_, storage_options_, record_options); recorder->record(); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp index 9e7a7bd8f..92ac9c1fd 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp @@ -38,7 +38,7 @@ TEST_F(RecordIntegrationTestFixture, record_all_without_discovery_ignores_later_ string_message->string_value = "Hello World"; rosbag2_transport::RecordOptions record_options = - {true, false, true, {}, {}, {}, {}, {}, "rmw_format", 100ms}; + {true, false, true, {}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all_use_sim_time.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all_use_sim_time.cpp index 9250ff4c4..b95635dc7 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all_use_sim_time.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all_use_sim_time.cpp @@ -91,7 +91,7 @@ TEST_F(RecordIntegrationTestFixture, record_all_with_sim_time) rosbag2_transport::RecordOptions record_options = { - false, false, false, {string_topic, clock_topic}, {}, {}, {}, {}, "rmw_format", 100ms + false, false, false, {string_topic, clock_topic}, {}, {}, {}, {}, {}, "rmw_format", 100ms }; record_options.use_sim_time = true; auto recorder = std::make_shared( diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp index 94f7c433f..15770b257 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp @@ -61,7 +61,7 @@ TEST_F(RecordIntegrationTestFixture, regex_topics_recording) ASSERT_FALSE(std::regex_match(b4, re)); rosbag2_transport::RecordOptions record_options = - {false, false, false, {}, {}, {}, {}, {}, "rmw_format", 10ms}; + {false, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 10ms}; record_options.regex = regex; // TODO(karsten1987) Refactor this into publication manager @@ -133,7 +133,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_topic_recording) ASSERT_TRUE(std::regex_match(e1, exclude)); rosbag2_transport::RecordOptions record_options = - {false, false, false, {}, {}, {}, {}, {}, "rmw_format", 10ms}; + {false, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 10ms}; record_options.regex = regex; record_options.exclude_regex = topics_regex_to_exclude; @@ -209,7 +209,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_topic_topic_recording) ASSERT_TRUE(e1 == topics_exclude); rosbag2_transport::RecordOptions record_options = - {false, false, false, {}, {}, {}, {}, {}, "rmw_format", 10ms}; + {false, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 10ms}; record_options.regex = regex; record_options.exclude_topics.emplace_back(topics_exclude); @@ -271,7 +271,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_service_recording) std::string b2 = "/namespace_before/not_nice"; rosbag2_transport::RecordOptions record_options = - {false, false, false, {}, {}, {}, {}, {}, "rmw_format", 10ms}; + {false, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 10ms}; record_options.regex = regex; record_options.exclude_regex = services_regex_to_exclude; @@ -344,7 +344,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_service_service_recording std::string b2 = "/namespace_before/not_nice"; rosbag2_transport::RecordOptions record_options = - {false, false, false, {}, {}, {}, {}, {}, "rmw_format", 10ms}; + {false, false, false, {}, {}, {}, {}, {}, {}, "rmw_format", 10ms}; record_options.regex = regex; record_options.exclude_service_events.emplace_back(services_exclude); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_services.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_services.cpp index c426607cf..f585549bc 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_services.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_services.cpp @@ -68,7 +68,7 @@ class RecordSrvsTest : public RecordIntegrationTestFixture client_node_ = std::make_shared("test_record_client"); rosbag2_transport::RecordOptions record_options = - {false, false, false, {test_topic_}, {}, {}, {}, {}, "rmw_format", 100ms}; + {false, false, false, {test_topic_}, {}, {}, {}, {}, {}, "rmw_format", 100ms}; storage_options_.snapshot_mode = snapshot_mode_; storage_options_.max_cache_size = 200; recorder_ = std::make_shared( diff --git a/rosbag2_transport/test/rosbag2_transport/test_topic_filter.cpp b/rosbag2_transport/test/rosbag2_transport/test_topic_filter.cpp index 86ea92d2f..f4191384d 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_topic_filter.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_topic_filter.cpp @@ -232,6 +232,27 @@ TEST_F(TestTopicFilter, all_topics_and_exclude_topics) } } +TEST_F(TestTopicFilter, all_topics_and_exclude_type_topics) +{ + rosbag2_transport::RecordOptions record_options; + record_options.exclude_topic_types = { + "localization_topic_type", + "status_topic_type"}; + record_options.all_topics = true; + rosbag2_transport::TopicFilter filter{record_options, nullptr, true}; + auto filtered_topics = filter.filter_topics(topics_and_types_with_services_); + + EXPECT_THAT(filtered_topics, SizeIs(5)); + for (const auto & topic : + {"/planning1", "/planning2", "/invisible", "/invalidated_topic", "/invalid_topic"}) + { + EXPECT_TRUE(filtered_topics.find(topic) != filtered_topics.end()) << "Expected topic:" << topic; + } + + EXPECT_TRUE(filtered_topics.find("/localization") == filtered_topics.end()); + EXPECT_TRUE(filtered_topics.find("/status") == filtered_topics.end()); +} + TEST_F(TestTopicFilter, all_services_and_exclude_regex) { rosbag2_transport::RecordOptions record_options;