Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions rosbag2_transport/src/rosbag2_transport/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,9 +102,11 @@ void Recorder::topics_discovery(
while (rclcpp::ok()) {
auto topics_to_subscribe =
get_requested_or_available_topics(requested_topics, include_hidden_topics);
#ifdef ROSBAG2_ENABLE_ADAPTIVE_QOS_SUBSCRIPTION
for (const auto & topic_and_type : topics_to_subscribe) {
warn_if_new_qos_for_subscribed_topic(topic_and_type.first);
}
#endif // ROSBAG2_ENABLE_ADAPTIVE_QOS_SUBSCRIPTION
auto missing_topics = get_missing_topics(topics_to_subscribe);
subscribe_topics(missing_topics);

Expand Down Expand Up @@ -160,7 +162,12 @@ void Recorder::subscribe_topic(const rosbag2_storage::TopicMetadata & topic)
// that callback called before we reached out the line: writer_->create_topic(topic)
writer_->create_topic(topic);

// TODO(emersonknapp) re-enable common_qos_or_fallback once the cyclone situation is resolved
#ifdef ROSBAG2_ENABLE_ADAPTIVE_QOS_SUBSCRIPTION
Rosbag2QoS subscription_qos{};
#else
Rosbag2QoS subscription_qos{common_qos_or_fallback(topic.name)};
#endif // ROSBAG2_ENABLE_ADAPTIVE_QOS_SUBSCRIPTION
auto subscription = create_subscription(topic.name, topic.type, subscription_qos);
if (subscription) {
subscriptions_.insert({topic.name, subscription});
Expand Down
4 changes: 2 additions & 2 deletions rosbag2_transport/test/rosbag2_transport/test_record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are
EXPECT_THAT(array_messages[0]->float32_values, Eq(array_message->float32_values));
}

#ifdef ENABLE_TEST_QOS_IS_STORED_IN_METADATA
#ifdef ROSBAG2_ENABLE_ADAPTIVE_QOS_SUBSCRIPTION
TEST_F(RecordIntegrationTestFixture, qos_is_stored_in_metadata)
{
auto string_message = get_messages_strings()[1];
Expand Down Expand Up @@ -99,7 +99,6 @@ TEST_F(RecordIntegrationTestFixture, qos_is_stored_in_metadata)
" avoid_ros_namespace_conventions: false"
));
}
#endif // ENABLE_TEST_QOS_IS_STORED_IN_METADATA

TEST_F(RecordIntegrationTestFixture, records_sensor_data)
{
Expand Down Expand Up @@ -141,3 +140,4 @@ TEST_F(RecordIntegrationTestFixture, records_sensor_data)
EXPECT_EQ(recorded_topics.size(), 1u);
EXPECT_FALSE(recorded_messages.empty());
}
#endif // ROSBAG2_ENABLE_ADAPTIVE_QOS_SUBSCRIPTION
Original file line number Diff line number Diff line change
Expand Up @@ -260,6 +260,7 @@ TEST_F(RosBag2NodeFixture, get_all_topics_with_types_returns_all_topics)
EXPECT_THAT(topics_and_types.find(third_topic)->second, StrEq("test_msgs/msg/Strings"));
}

#ifdef ROSBAG2_ENABLE_ADAPTIVE_QOS_SUBSCRIPTION
TEST_F(RosBag2NodeFixture, mixed_qos_falls_back_to_default)
{
using clock = std::chrono::system_clock;
Expand Down Expand Up @@ -306,3 +307,4 @@ TEST_F(RosBag2NodeFixture, mixed_qos_falls_back_to_default)
rclcpp::shutdown();
recording_future.get();
}
#endif // ROSBAG2_ENABLE_ADAPTIVE_QOS_SUBSCRIPTION