Skip to content

Commit

Permalink
Added exclude-topic-types to record (#1582)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Mar 28, 2024
1 parent a780acb commit 34ccb39
Show file tree
Hide file tree
Showing 20 changed files with 74 additions and 27 deletions.
9 changes: 9 additions & 0 deletions ros2bag/ros2bag/verb/record.py
Original file line number Diff line number Diff line change
Expand Up @@ -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. '
Expand Down Expand Up @@ -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')
Expand Down Expand Up @@ -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)
Expand Down
1 change: 1 addition & 0 deletions rosbag2_py/rosbag2_py/_transport.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
1 change: 1 addition & 0 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer), storage_options, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer), storage_options, record_options);
recorder->record();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ struct RecordOptions
std::vector<std::string> topic_types;
std::vector<std::string> services; // service event topic
std::vector<std::string> exclude_topics;
std::vector<std::string> exclude_topic_types;
std::vector<std::string> exclude_service_events; // service event topic
std::string rmw_serialization_format;
std::chrono::milliseconds topic_polling_interval{100};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -228,6 +228,9 @@ RecordOptions get_record_options_from_node_params(rclcpp::Node & node)
record_options.exclude_topics = node.declare_parameter<std::vector<std::string>>(
"record.exclude_topics", std::vector<std::string>());

record_options.exclude_topic_types = node.declare_parameter<std::vector<std::string>>(
"record.exclude_topic_types", std::vector<std::string>());

// Convert service name to service event topic name
auto exclude_service_list = node.declare_parameter<std::vector<std::string>>(
"record.exclude_services", std::vector<std::string>());
Expand Down
4 changes: 4 additions & 0 deletions rosbag2_transport/src/rosbag2_transport/record_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ Node convert<rosbag2_transport::RecordOptions>::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;
Expand Down Expand Up @@ -71,6 +72,9 @@ bool convert<rosbag2_transport::RecordOptions>::decode(
optional_assign<std::string>(node, "regex", record_options.regex);
optional_assign<std::string>(node, "exclude_regex", record_options.exclude_regex);
optional_assign<std::vector<std::string>>(node, "exclude_topics", record_options.exclude_topics);
optional_assign<std::vector<std::string>>(
node, "exclude_topic_types",
record_options.exclude_topic_types);
optional_assign<std::vector<std::string>>(
node, "exclude_services", record_options.exclude_service_events);
optional_assign<std::string>(node, "node_prefix", record_options.node_prefix);
Expand Down
4 changes: 4 additions & 0 deletions rosbag2_transport/src/rosbag2_transport/topic_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down
3 changes: 2 additions & 1 deletion rosbag2_transport/test/resources/recorder_node_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down Expand Up @@ -41,4 +42,4 @@ recorder_params_node:
snapshot_mode: false
custom_data: ["key1=value1", "key2=value2"]
start_time_ns: 0
end_time_ns: 100000
end_time_ns: 100000
Original file line number Diff line number Diff line change
Expand Up @@ -216,6 +216,8 @@ TEST_P(ComposableRecorderTests, recorder_can_parse_parameters_from_file) {
EXPECT_EQ(record_options.topics, topics);
std::vector<std::string> topic_types {"std_msgs/msg/Header", "geometry_msgs/msg/Pose"};
EXPECT_EQ(record_options.topic_types, topic_types);
std::vector<std::string> exclude_topic_types {"sensor_msgs/msg/Image"};
EXPECT_EQ(record_options.exclude_topic_types, exclude_topic_types);
std::vector<std::string> services {"/service/_service_event", "/other_service/_service_event"};
EXPECT_EQ(record_options.services, services);
EXPECT_EQ(record_options.rmw_serialization_format, "cdr");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ TEST_F(RecordIntegrationTestFixture, test_keyboard_controls)
auto keyboard_handler = std::make_shared<MockKeyboardHandler>();

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<Recorder>(
Expand Down
16 changes: 8 additions & 8 deletions rosbag2_transport/test/rosbag2_transport/test_record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down
6 changes: 3 additions & 3 deletions rosbag2_transport/test/rosbag2_transport/test_record_all.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<MockRecorder>(writer_, storage_options_, record_options);
recorder->record();
Expand All @@ -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<MockRecorder>(writer_, storage_options_, record_options);
recorder->record();
Expand All @@ -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<MockRecorder>(writer_, storage_options_, record_options);
recorder->record();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<rosbag2_transport::Recorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<MockRecorder>(
Expand Down
10 changes: 5 additions & 5 deletions rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;

Expand Down Expand Up @@ -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);

Expand Down Expand Up @@ -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;

Expand Down Expand Up @@ -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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class RecordSrvsTest : public RecordIntegrationTestFixture
client_node_ = std::make_shared<rclcpp::Node>("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<rosbag2_transport::Recorder>(
Expand Down
21 changes: 21 additions & 0 deletions rosbag2_transport/test/rosbag2_transport/test_topic_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 34ccb39

Please sign in to comment.