@@ -101,41 +101,21 @@ TEST_F(TestParameterService, list_parameters) {
101101}
102102
103103TEST_F (TestParameterService, describe_parameters) {
104- // There is no current API in ParameterClient for calling the describe_parameters service
105- // Update this test when https://github.com/ros2/rclcpp/issues/1354 is resolved
106-
107- const std::string describe_parameters_service_name =
108- node->get_fully_qualified_name () + std::string (" /" ) +
109- rclcpp::parameter_service_names::describe_parameters;
110- using ServiceT = rcl_interfaces::srv::DescribeParameters;
111- auto client =
112- node->create_client <ServiceT>(describe_parameters_service_name);
113-
114- ASSERT_TRUE (client->wait_for_service (std::chrono::seconds (1 )));
115104 node->declare_parameter (" parameter1" , rclcpp::ParameterValue (42 ));
116105
117106 {
118- auto request = std::make_shared<rcl_interfaces::srv::DescribeParameters::Request>();
119- request->names .push_back (" parameter1" );
120- auto future = client->async_send_request (request);
121-
122- rclcpp::spin_until_future_complete (node, future, std::chrono::seconds (1 ));
123- auto response = future.get ();
124- ASSERT_NE (nullptr , response);
125- EXPECT_EQ (1u , response->descriptors .size ());
126-
127- auto descriptor = response->descriptors [0 ];
128- EXPECT_EQ (" parameter1" , descriptor.name );
129- EXPECT_EQ (rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, descriptor.type );
107+ const std::vector<std::string> names{" parameter1" };
108+ std::vector<rcl_interfaces::msg::ParameterDescriptor> parameter_descs =
109+ client->describe_parameters (names, 10s);
110+ ASSERT_EQ (1u , parameter_descs.size ());
111+ EXPECT_EQ (" parameter1" , parameter_descs[0 ].name );
112+ EXPECT_EQ (rclcpp::ParameterType::PARAMETER_INTEGER, parameter_descs[0 ].type );
130113 }
114+
131115 {
132- auto request = std::make_shared<rcl_interfaces::srv::DescribeParameters::Request>();
133- request->names .push_back (" undeclared_parameter" );
134- auto future = client->async_send_request (request);
135-
136- rclcpp::spin_until_future_complete (node, future, std::chrono::seconds (1 ));
137- auto response = future.get ();
138- ASSERT_NE (nullptr , response);
139- EXPECT_EQ (0u , response->descriptors .size ());
116+ const std::vector<std::string> names{" undeclared_parameter" };
117+ std::vector<rcl_interfaces::msg::ParameterDescriptor> parameter_descs =
118+ client->describe_parameters (names, 10s);
119+ EXPECT_EQ (0u , parameter_descs.size ());
140120 }
141121}
0 commit comments