@@ -55,13 +55,10 @@ bool operator!=(
5555 Test rosout_qos function with default value.
5656 */
5757TEST (TestRosoutQoS, test_rosout_qos_with_default_value) {
58- rclcpp::QoS rosout_qos_profile = rclcpp::NodeOptions ().rosout_qos ();
58+ rclcpp::NodeOptions node_options;
59+ rclcpp::QoS rosout_qos_profile = node_options.rosout_qos ();
5960 rmw_qos_profile_t rmw_qos_profile = rosout_qos_profile.get_rmw_qos_profile ();
6061 EXPECT_EQ (rcl_qos_profile_rosout_default, rmw_qos_profile);
61-
62- rclcpp::NodeOptions node_options;
63- rosout_qos_profile = rclcpp::RosoutQoS ();
64- node_options.rosout_qos (rosout_qos_profile);
6562 EXPECT_EQ (rcl_qos_profile_rosout_default, node_options.get_rcl_node_options ()->rosout_qos );
6663}
6764
@@ -77,14 +74,6 @@ TEST(TestRosoutQoS, test_rosout_qos_with_custom_value) {
7774 rclcpp::QoS rosout_qos = options.rosout_qos ();
7875 rmw_qos_profile_t rmw_qos_profile = rosout_qos.get_rmw_qos_profile ();
7976
80- EXPECT_EQ ((size_t )1000 , rmw_qos_profile.depth );
81- EXPECT_EQ (RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL, rmw_qos_profile.durability );
82- EXPECT_EQ (life_span, rmw_qos_profile.lifespan );
83-
84- rmw_qos_profile.depth = 10 ;
85- rclcpp::QoS rosout_qos_custom = rclcpp::RosoutQoS (
86- rclcpp::QoSInitialization::from_rmw (rmw_qos_profile)
87- );
88- options.rosout_qos (rosout_qos_custom);
89- EXPECT_NE (rcl_qos_profile_rosout_default, options.get_rcl_node_options ()->rosout_qos );
77+ EXPECT_EQ (rmw_qos_profile, qos_profile.get_rmw_qos_profile ());
78+ EXPECT_EQ (rmw_qos_profile, options.get_rcl_node_options ()->rosout_qos );
9079}
0 commit comments