From 18ed7cdacf859ea446cf1d09024a97c01076f023 Mon Sep 17 00:00:00 2001 From: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Date: Thu, 6 Jun 2024 10:17:15 -0400 Subject: [PATCH] Update qos for deprecation (#695) Signed-off-by: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> --- tf2_ros/test/message_filter_test.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/tf2_ros/test/message_filter_test.cpp b/tf2_ros/test/message_filter_test.cpp index 051656287..19026de81 100644 --- a/tf2_ros/test/message_filter_test.cpp +++ b/tf2_ros/test/message_filter_test.cpp @@ -127,8 +127,10 @@ TEST(tf2_ros_message_filter, multiple_frames_and_time_tolerance) node->get_node_base_interface(), node->get_node_timers_interface()); + rclcpp::QoS default_qos = + rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)); message_filters::Subscriber sub; - sub.subscribe(node, "point"); + sub.subscribe(node, "point", default_qos); rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_SYSTEM_TIME); tf2_ros::Buffer buffer(clock);