Skip to content

Commit

Permalink
Update qos for deprecation (#695)
Browse files Browse the repository at this point in the history
Signed-off-by: Lucas Wendland <[email protected]>
  • Loading branch information
CursedRock17 authored Jun 6, 2024
1 parent ad72a82 commit 18ed7cd
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion tf2_ros/test/message_filter_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<geometry_msgs::msg::PointStamped> sub;
sub.subscribe(node, "point");
sub.subscribe(node, "point", default_qos);

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
Expand Down

0 comments on commit 18ed7cd

Please sign in to comment.