From 2c40733222d722a20b4a0966d6e8c389be0ca954 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Wed, 6 Nov 2024 12:45:34 -0800 Subject: [PATCH] use rmw_qos_profile_rosout_default instead of rcl. Signed-off-by: Tomoya Fujita --- rclcpp/include/rclcpp/qos.hpp | 2 +- rclcpp/src/rclcpp/qos.cpp | 2 +- rclcpp/test/rclcpp/test_qos.cpp | 2 +- rclcpp/test/rclcpp/test_rosout_qos.cpp | 4 ++-- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/rclcpp/include/rclcpp/qos.hpp b/rclcpp/include/rclcpp/qos.hpp index 2ad49487c5..5d9bdcafdf 100644 --- a/rclcpp/include/rclcpp/qos.hpp +++ b/rclcpp/include/rclcpp/qos.hpp @@ -475,7 +475,7 @@ class RCLCPP_PUBLIC RosoutQoS : public QoS explicit RosoutQoS( const QoSInitialization & rosout_qos_initialization = ( - QoSInitialization::from_rmw(rcl_qos_profile_rosout_default) + QoSInitialization::from_rmw(rmw_qos_profile_rosout_default) )); }; diff --git a/rclcpp/src/rclcpp/qos.cpp b/rclcpp/src/rclcpp/qos.cpp index 2453149aa4..10cf6df15c 100644 --- a/rclcpp/src/rclcpp/qos.cpp +++ b/rclcpp/src/rclcpp/qos.cpp @@ -407,7 +407,7 @@ ParameterEventsQoS::ParameterEventsQoS(const QoSInitialization & qos_initializat {} RosoutQoS::RosoutQoS(const QoSInitialization & rosout_initialization) -: QoS(rosout_initialization, rcl_qos_profile_rosout_default) +: QoS(rosout_initialization, rmw_qos_profile_rosout_default) {} SystemDefaultsQoS::SystemDefaultsQoS(const QoSInitialization & qos_initialization) diff --git a/rclcpp/test/rclcpp/test_qos.cpp b/rclcpp/test/rclcpp/test_qos.cpp index eecfaf97a7..cd8f186144 100644 --- a/rclcpp/test/rclcpp/test_qos.cpp +++ b/rclcpp/test/rclcpp/test_qos.cpp @@ -184,7 +184,7 @@ TEST(TestQoS, DerivedTypes) { EXPECT_EQ(rmw_qos_profile_parameter_events, parameter_events_qos.get_rmw_qos_profile()); rclcpp::RosoutQoS rosout_qos; - EXPECT_EQ(rcl_qos_profile_rosout_default, rosout_qos.get_rmw_qos_profile()); + EXPECT_EQ(rmw_qos_profile_rosout_default, rosout_qos.get_rmw_qos_profile()); rclcpp::SystemDefaultsQoS system_default_qos; const rclcpp::KeepLast expected_initialization(RMW_QOS_POLICY_DEPTH_SYSTEM_DEFAULT); diff --git a/rclcpp/test/rclcpp/test_rosout_qos.cpp b/rclcpp/test/rclcpp/test_rosout_qos.cpp index aacaf84189..f33f8b74a9 100644 --- a/rclcpp/test/rclcpp/test_rosout_qos.cpp +++ b/rclcpp/test/rclcpp/test_rosout_qos.cpp @@ -58,8 +58,8 @@ TEST(TestRosoutQoS, test_rosout_qos_with_default_value) { rclcpp::NodeOptions node_options; rclcpp::QoS rosout_qos_profile = node_options.rosout_qos(); rmw_qos_profile_t rmw_qos_profile = rosout_qos_profile.get_rmw_qos_profile(); - EXPECT_EQ(rcl_qos_profile_rosout_default, rmw_qos_profile); - EXPECT_EQ(rcl_qos_profile_rosout_default, node_options.get_rcl_node_options()->rosout_qos); + EXPECT_EQ(rmw_qos_profile_rosout_default, rmw_qos_profile); + EXPECT_EQ(rmw_qos_profile_rosout_default, node_options.get_rcl_node_options()->rosout_qos); } /*