15 #include "rclcpp/parameter_client.hpp"
27 #include "./parameter_service_names.hpp"
32 AsyncParametersClient::AsyncParametersClient(
33 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
34 const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
35 const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
36 const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
37 const std::string & remote_node_name,
38 const rmw_qos_profile_t & qos_profile,
39 rclcpp::CallbackGroup::SharedPtr group)
40 : node_topics_interface_(node_topics_interface)
42 if (remote_node_name !=
"") {
43 remote_node_name_ = remote_node_name;
45 remote_node_name_ = node_base_interface->get_fully_qualified_name();
49 options.
qos = qos_profile;
55 node_base_interface.get(),
57 remote_node_name_ +
"/" + parameter_service_names::get_parameters,
59 auto get_parameters_base = std::dynamic_pointer_cast<ClientBase>(get_parameters_client_);
60 node_services_interface->add_client(get_parameters_base, group);
63 node_base_interface.get(),
65 remote_node_name_ +
"/" + parameter_service_names::get_parameter_types,
67 auto get_parameter_types_base =
68 std::dynamic_pointer_cast<ClientBase>(get_parameter_types_client_);
69 node_services_interface->add_client(get_parameter_types_base, group);
72 node_base_interface.get(),
74 remote_node_name_ +
"/" + parameter_service_names::set_parameters,
76 auto set_parameters_base = std::dynamic_pointer_cast<ClientBase>(set_parameters_client_);
77 node_services_interface->add_client(set_parameters_base, group);
79 set_parameters_atomically_client_ =
81 node_base_interface.get(),
83 remote_node_name_ +
"/" + parameter_service_names::set_parameters_atomically,
85 auto set_parameters_atomically_base = std::dynamic_pointer_cast<ClientBase>(
86 set_parameters_atomically_client_);
87 node_services_interface->add_client(set_parameters_atomically_base, group);
90 node_base_interface.get(),
92 remote_node_name_ +
"/" + parameter_service_names::list_parameters,
94 auto list_parameters_base = std::dynamic_pointer_cast<ClientBase>(list_parameters_client_);
95 node_services_interface->add_client(list_parameters_base, group);
98 node_base_interface.get(),
100 remote_node_name_ +
"/" + parameter_service_names::describe_parameters,
102 auto describe_parameters_base =
103 std::dynamic_pointer_cast<ClientBase>(describe_parameters_client_);
104 node_services_interface->add_client(describe_parameters_base, group);
107 std::shared_future<std::vector<rclcpp::Parameter>>
108 AsyncParametersClient::get_parameters(
109 const std::vector<std::string> & names,
111 void(std::shared_future<std::vector<rclcpp::Parameter>>)
114 auto promise_result =
115 std::make_shared<std::promise<std::vector<rclcpp::Parameter>>>();
116 auto future_result = promise_result->get_future().share();
118 auto request = std::make_shared<rcl_interfaces::srv::GetParameters::Request>();
119 request->names = names;
123 [request, promise_result, future_result, callback](
124 rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedFuture cb_f)
126 std::vector<rclcpp::Parameter> parameters;
127 auto & pvalues = cb_f.get()->values;
129 for (
auto & pvalue : pvalues) {
130 auto i =
static_cast<size_t>(&pvalue - &pvalues[0]);
131 rcl_interfaces::msg::Parameter parameter;
132 parameter.name = request->names[i];
133 parameter.value = pvalue;
137 promise_result->set_value(parameters);
138 if (callback !=
nullptr) {
139 callback(future_result);
144 return future_result;
147 std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>
148 AsyncParametersClient::describe_parameters(
149 const std::vector<std::string> & names,
151 void(std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>)
154 auto promise_result =
155 std::make_shared<std::promise<std::vector<rcl_interfaces::msg::ParameterDescriptor>>>();
156 auto future_result = promise_result->get_future().share();
158 auto request = std::make_shared<rcl_interfaces::srv::DescribeParameters::Request>();
159 request->names = names;
163 [promise_result, future_result, callback](
164 rclcpp::Client<rcl_interfaces::srv::DescribeParameters>::SharedFuture cb_f)
166 promise_result->set_value(cb_f.get()->descriptors);
167 if (callback !=
nullptr) {
168 callback(future_result);
173 return future_result;
176 std::shared_future<std::vector<rclcpp::ParameterType>>
177 AsyncParametersClient::get_parameter_types(
178 const std::vector<std::string> & names,
180 void(std::shared_future<std::vector<rclcpp::ParameterType>>)
183 auto promise_result =
184 std::make_shared<std::promise<std::vector<rclcpp::ParameterType>>>();
185 auto future_result = promise_result->get_future().share();
187 auto request = std::make_shared<rcl_interfaces::srv::GetParameterTypes::Request>();
188 request->names = names;
192 [promise_result, future_result, callback](
193 rclcpp::Client<rcl_interfaces::srv::GetParameterTypes>::SharedFuture cb_f)
195 std::vector<rclcpp::ParameterType> types;
196 auto & pts = cb_f.get()->types;
197 for (
auto & pt : pts) {
198 types.push_back(
static_cast<rclcpp::ParameterType
>(pt));
200 promise_result->set_value(types);
201 if (callback !=
nullptr) {
202 callback(future_result);
207 return future_result;
210 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
211 AsyncParametersClient::set_parameters(
212 const std::vector<rclcpp::Parameter> & parameters,
214 void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)
217 auto promise_result =
218 std::make_shared<std::promise<std::vector<rcl_interfaces::msg::SetParametersResult>>>();
219 auto future_result = promise_result->get_future().share();
221 auto request = std::make_shared<rcl_interfaces::srv::SetParameters::Request>();
224 parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
230 [promise_result, future_result, callback](
231 rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedFuture cb_f)
233 promise_result->set_value(cb_f.get()->results);
234 if (callback !=
nullptr) {
235 callback(future_result);
240 return future_result;
243 std::shared_future<rcl_interfaces::msg::SetParametersResult>
244 AsyncParametersClient::set_parameters_atomically(
245 const std::vector<rclcpp::Parameter> & parameters,
247 void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)
250 auto promise_result =
251 std::make_shared<std::promise<rcl_interfaces::msg::SetParametersResult>>();
252 auto future_result = promise_result->get_future().share();
254 auto request = std::make_shared<rcl_interfaces::srv::SetParametersAtomically::Request>();
257 parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
263 [promise_result, future_result, callback](
264 rclcpp::Client<rcl_interfaces::srv::SetParametersAtomically>::SharedFuture cb_f)
266 promise_result->set_value(cb_f.get()->result);
267 if (callback !=
nullptr) {
268 callback(future_result);
273 return future_result;
276 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
278 const std::vector<std::string> & parameters_names)
280 std::vector<rclcpp::Parameter> parameters;
281 for (
const std::string & name : parameters_names) {
284 auto future_result = set_parameters(parameters);
286 return future_result;
289 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
291 const std::string & yaml_filename)
297 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
301 std::vector<rclcpp::Parameter> parameters;
302 std::string remote_name = remote_node_name_.substr(remote_node_name_.substr(1).find(
"/") + 2);
303 for (
const auto & params : parameter_map) {
304 std::string node_full_name = params.first;
305 std::string node_name = node_full_name.substr(node_full_name.find(
"/*/") + 3);
306 if (node_full_name == remote_node_name_ ||
307 node_full_name ==
"/**" ||
308 (node_name == remote_name))
310 for (
const auto & param : params.second) {
311 parameters.push_back(param);
316 if (parameters.size() == 0) {
319 auto future_result = set_parameters(parameters);
321 return future_result;
325 std::shared_future<rcl_interfaces::msg::ListParametersResult>
326 AsyncParametersClient::list_parameters(
327 const std::vector<std::string> & prefixes,
330 void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)
333 auto promise_result =
334 std::make_shared<std::promise<rcl_interfaces::msg::ListParametersResult>>();
335 auto future_result = promise_result->get_future().share();
337 auto request = std::make_shared<rcl_interfaces::srv::ListParameters::Request>();
338 request->prefixes = prefixes;
339 request->depth = depth;
343 [promise_result, future_result, callback](
344 rclcpp::Client<rcl_interfaces::srv::ListParameters>::SharedFuture cb_f)
346 promise_result->set_value(cb_f.get()->result);
347 if (callback !=
nullptr) {
348 callback(future_result);
353 return future_result;
368 AsyncParametersClient::wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
370 const std::vector<std::shared_ptr<rclcpp::ClientBase>> clients = {
371 get_parameters_client_,
372 get_parameter_types_client_,
373 set_parameters_client_,
374 list_parameters_client_,
375 describe_parameters_client_
377 for (
auto & client : clients) {
378 auto stamp = std::chrono::steady_clock::now();
379 if (!client->wait_for_service(timeout)) {
382 if (timeout > std::chrono::nanoseconds::zero()) {
383 timeout -= std::chrono::duration_cast<std::chrono::nanoseconds>(
384 std::chrono::steady_clock::now() - stamp);
385 if (timeout < std::chrono::nanoseconds::zero()) {
386 timeout = std::chrono::nanoseconds::zero();
393 std::vector<rclcpp::Parameter>
394 SyncParametersClient::get_parameters(
395 const std::vector<std::string> & parameter_names,
396 std::chrono::nanoseconds timeout)
398 auto f = async_parameters_client_->get_parameters(parameter_names);
399 using rclcpp::executors::spin_node_until_future_complete;
401 spin_node_until_future_complete(
402 *executor_, node_base_interface_, f,
403 timeout) == rclcpp::FutureReturnCode::SUCCESS)
408 return std::vector<rclcpp::Parameter>();
412 SyncParametersClient::has_parameter(
const std::string & parameter_name)
414 std::vector<std::string> names;
415 names.push_back(parameter_name);
416 auto vars = list_parameters(names, 1);
417 return vars.names.size() > 0;
420 std::vector<rcl_interfaces::msg::ParameterDescriptor>
421 SyncParametersClient::describe_parameters(
422 const std::vector<std::string> & parameter_names,
423 std::chrono::nanoseconds timeout)
425 auto f = async_parameters_client_->describe_parameters(parameter_names);
427 using rclcpp::executors::spin_node_until_future_complete;
429 spin_node_until_future_complete(*executor_, node_base_interface_, f, timeout);
430 if (future == rclcpp::FutureReturnCode::SUCCESS) {
433 return std::vector<rcl_interfaces::msg::ParameterDescriptor>();
436 std::vector<rclcpp::ParameterType>
437 SyncParametersClient::get_parameter_types(
438 const std::vector<std::string> & parameter_names,
439 std::chrono::nanoseconds timeout)
441 auto f = async_parameters_client_->get_parameter_types(parameter_names);
443 using rclcpp::executors::spin_node_until_future_complete;
445 spin_node_until_future_complete(
446 *executor_, node_base_interface_, f,
447 timeout) == rclcpp::FutureReturnCode::SUCCESS)
451 return std::vector<rclcpp::ParameterType>();
454 std::vector<rcl_interfaces::msg::SetParametersResult>
455 SyncParametersClient::set_parameters(
456 const std::vector<rclcpp::Parameter> & parameters,
457 std::chrono::nanoseconds timeout)
459 auto f = async_parameters_client_->set_parameters(parameters);
461 using rclcpp::executors::spin_node_until_future_complete;
463 spin_node_until_future_complete(
464 *executor_, node_base_interface_, f,
465 timeout) == rclcpp::FutureReturnCode::SUCCESS)
469 return std::vector<rcl_interfaces::msg::SetParametersResult>();
472 std::vector<rcl_interfaces::msg::SetParametersResult>
474 const std::vector<std::string> & parameters_names,
475 std::chrono::nanoseconds timeout)
477 auto f = async_parameters_client_->delete_parameters(parameters_names);
479 using rclcpp::executors::spin_node_until_future_complete;
481 spin_node_until_future_complete(
482 *executor_, node_base_interface_, f,
483 timeout) == rclcpp::FutureReturnCode::SUCCESS)
487 return std::vector<rcl_interfaces::msg::SetParametersResult>();
490 std::vector<rcl_interfaces::msg::SetParametersResult>
492 const std::string & yaml_filename,
493 std::chrono::nanoseconds timeout)
495 auto f = async_parameters_client_->load_parameters(yaml_filename);
497 using rclcpp::executors::spin_node_until_future_complete;
499 spin_node_until_future_complete(
500 *executor_, node_base_interface_, f,
501 timeout) == rclcpp::FutureReturnCode::SUCCESS)
505 return std::vector<rcl_interfaces::msg::SetParametersResult>();
508 rcl_interfaces::msg::SetParametersResult
509 SyncParametersClient::set_parameters_atomically(
510 const std::vector<rclcpp::Parameter> & parameters,
511 std::chrono::nanoseconds timeout)
513 auto f = async_parameters_client_->set_parameters_atomically(parameters);
515 using rclcpp::executors::spin_node_until_future_complete;
517 spin_node_until_future_complete(
518 *executor_, node_base_interface_, f,
519 timeout) == rclcpp::FutureReturnCode::SUCCESS)
524 throw std::runtime_error(
"Unable to get result of set parameters service call.");
527 rcl_interfaces::msg::ListParametersResult
528 SyncParametersClient::list_parameters(
529 const std::vector<std::string> & parameter_prefixes,
531 std::chrono::nanoseconds timeout)
533 auto f = async_parameters_client_->list_parameters(parameter_prefixes, depth);
535 using rclcpp::executors::spin_node_until_future_complete;
537 spin_node_until_future_complete(
538 *executor_, node_base_interface_, f,
539 timeout) == rclcpp::FutureReturnCode::SUCCESS)
544 throw std::runtime_error(
"Unable to get result of list parameters service call.");
RCLCPP_PUBLIC std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > load_parameters(const std::string &yaml_filename)
Load parameters from yaml file.
RCLCPP_PUBLIC bool service_is_ready() const
Return if the parameter services are ready.
RCLCPP_PUBLIC std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > delete_parameters(const std::vector< std::string > ¶meters_names)
Delete several parameters at once.
RCLCPP_PUBLIC bool service_is_ready() const
Return if the service is ready.
FutureAndRequestId async_send_request(SharedRequest request)
Send a request to the service server.
Structure to store an arbitrary parameter with templated get/set methods.
static RCLCPP_PUBLIC Parameter from_parameter_msg(const rcl_interfaces::msg::Parameter ¶meter)
Convert a parameter message in a Parameter class object.
std::vector< rcl_interfaces::msg::SetParametersResult > delete_parameters(const std::vector< std::string > ¶meters_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Delete several parameters at once.
std::vector< rcl_interfaces::msg::SetParametersResult > load_parameters(const std::string &yaml_filename, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Load parameters from yaml file.
Thrown if passed parameters are inconsistent or invalid.
RCL_PUBLIC RCL_WARN_UNUSED rcl_client_options_t rcl_client_get_default_options(void)
Return the default client options in a rcl_client_options_t.
RCLCPP_PUBLIC ParameterMap parameter_map_from_yaml_file(const std::string &yaml_filename)
FutureReturnCode
Return codes to be used with spin_until_future_complete.
std::unordered_map< std::string, std::vector< Parameter > > ParameterMap
A map of fully qualified node names to a list of parameters.
Options available for a rcl_client_t.
rmw_qos_profile_t qos
Middleware quality of service settings for the client.