ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
parameter_client.hpp
1 // Copyright 2015 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__PARAMETER_CLIENT_HPP_
16 #define RCLCPP__PARAMETER_CLIENT_HPP_
17 
18 #include <functional>
19 #include <future>
20 #include <memory>
21 #include <string>
22 #include <utility>
23 #include <vector>
24 
25 #include "rcl_interfaces/msg/parameter.hpp"
26 #include "rcl_interfaces/msg/parameter_event.hpp"
27 #include "rcl_interfaces/msg/parameter_value.hpp"
28 #include "rcl_interfaces/srv/describe_parameters.hpp"
29 #include "rcl_interfaces/srv/get_parameter_types.hpp"
30 #include "rcl_interfaces/srv/get_parameters.hpp"
31 #include "rcl_interfaces/srv/list_parameters.hpp"
32 #include "rcl_interfaces/srv/set_parameters.hpp"
33 #include "rcl_interfaces/srv/set_parameters_atomically.hpp"
34 #include "rcl_yaml_param_parser/parser.h"
35 #include "rclcpp/exceptions.hpp"
36 #include "rclcpp/executors.hpp"
37 #include "rclcpp/create_subscription.hpp"
38 #include "rclcpp/macros.hpp"
39 #include "rclcpp/node.hpp"
40 #include "rclcpp/parameter.hpp"
41 #include "rclcpp/parameter_map.hpp"
42 #include "rclcpp/type_support_decl.hpp"
43 #include "rclcpp/visibility_control.hpp"
44 #include "rmw/rmw.h"
45 
46 namespace rclcpp
47 {
48 
50 {
51 public:
52  RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient)
53 
54 
64  RCLCPP_PUBLIC
66  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
67  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
68  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
69  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
70  const std::string & remote_node_name = "",
71  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
72  rclcpp::CallbackGroup::SharedPtr group = nullptr);
73 
75 
81  template<typename NodeT>
83  const std::shared_ptr<NodeT> node,
84  const std::string & remote_node_name = "",
85  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
86  rclcpp::CallbackGroup::SharedPtr group = nullptr)
88  node->get_node_base_interface(),
89  node->get_node_topics_interface(),
90  node->get_node_graph_interface(),
91  node->get_node_services_interface(),
92  remote_node_name,
93  qos_profile,
94  group)
95  {}
96 
98 
104  template<typename NodeT>
106  NodeT * node,
107  const std::string & remote_node_name = "",
108  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
109  rclcpp::CallbackGroup::SharedPtr group = nullptr)
111  node->get_node_base_interface(),
112  node->get_node_topics_interface(),
113  node->get_node_graph_interface(),
114  node->get_node_services_interface(),
115  remote_node_name,
116  qos_profile,
117  group)
118  {}
119 
120  RCLCPP_PUBLIC
121  std::shared_future<std::vector<rclcpp::Parameter>>
122  get_parameters(
123  const std::vector<std::string> & names,
124  std::function<
125  void(std::shared_future<std::vector<rclcpp::Parameter>>)
126  > callback = nullptr);
127 
128  RCLCPP_PUBLIC
129  std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>
130  describe_parameters(
131  const std::vector<std::string> & names,
132  std::function<
133  void(std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>)
134  > callback = nullptr);
135 
136  RCLCPP_PUBLIC
137  std::shared_future<std::vector<rclcpp::ParameterType>>
138  get_parameter_types(
139  const std::vector<std::string> & names,
140  std::function<
141  void(std::shared_future<std::vector<rclcpp::ParameterType>>)
142  > callback = nullptr);
143 
144  RCLCPP_PUBLIC
145  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
146  set_parameters(
147  const std::vector<rclcpp::Parameter> & parameters,
148  std::function<
149  void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)
150  > callback = nullptr);
151 
152  RCLCPP_PUBLIC
153  std::shared_future<rcl_interfaces::msg::SetParametersResult>
154  set_parameters_atomically(
155  const std::vector<rclcpp::Parameter> & parameters,
156  std::function<
157  void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)
158  > callback = nullptr);
159 
161 
167  RCLCPP_PUBLIC
168  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
170  const std::vector<std::string> & parameters_names);
171 
173 
179  RCLCPP_PUBLIC
180  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
182  const std::string & yaml_filename);
183 
185 
192  RCLCPP_PUBLIC
193  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
194  load_parameters(const rclcpp::ParameterMap & parameter_map);
195 
196  RCLCPP_PUBLIC
197  std::shared_future<rcl_interfaces::msg::ListParametersResult>
198  list_parameters(
199  const std::vector<std::string> & prefixes,
200  uint64_t depth,
201  std::function<
202  void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)
203  > callback = nullptr);
204 
205  template<
206  typename CallbackT,
207  typename AllocatorT = std::allocator<void>>
209  on_parameter_event(
210  CallbackT && callback,
211  const rclcpp::QoS & qos = (
212  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))
213  ),
216  ))
217  {
218  return this->on_parameter_event(
219  this->node_topics_interface_,
220  callback,
221  qos,
222  options);
223  }
224 
230  template<
231  typename CallbackT,
232  typename NodeT,
233  typename AllocatorT = std::allocator<void>>
236  NodeT && node,
237  CallbackT && callback,
238  const rclcpp::QoS & qos = (
239  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))
240  ),
243  ))
244  {
245  return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
246  node,
247  "/parameter_events",
248  qos,
249  std::forward<CallbackT>(callback),
250  options);
251  }
252 
254 
264  RCLCPP_PUBLIC
265  bool
266  service_is_ready() const;
267 
269 
273  template<typename RepT = int64_t, typename RatioT = std::milli>
274  bool
276  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
277  {
278  return wait_for_service_nanoseconds(
279  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
280  );
281  }
282 
283 protected:
284  RCLCPP_PUBLIC
285  bool
286  wait_for_service_nanoseconds(std::chrono::nanoseconds timeout);
287 
288 private:
289  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
292  get_parameter_types_client_;
295  set_parameters_atomically_client_;
298  describe_parameters_client_;
299  std::string remote_node_name_;
300 };
301 
303 {
304 public:
305  RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient)
306 
307  template<typename NodeT>
308  explicit SyncParametersClient(
309  std::shared_ptr<NodeT> node,
310  const std::string & remote_node_name = "",
311  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
313  std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
314  node,
315  remote_node_name,
316  qos_profile)
317  {}
318 
319  template<typename NodeT>
321  rclcpp::Executor::SharedPtr executor,
322  std::shared_ptr<NodeT> node,
323  const std::string & remote_node_name = "",
324  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
326  executor,
327  node->get_node_base_interface(),
328  node->get_node_topics_interface(),
329  node->get_node_graph_interface(),
330  node->get_node_services_interface(),
331  remote_node_name,
332  qos_profile)
333  {}
334 
335  template<typename NodeT>
336  explicit SyncParametersClient(
337  NodeT * node,
338  const std::string & remote_node_name = "",
339  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
341  std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
342  node,
343  remote_node_name,
344  qos_profile)
345  {}
346 
347  template<typename NodeT>
349  rclcpp::Executor::SharedPtr executor,
350  NodeT * node,
351  const std::string & remote_node_name = "",
352  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
354  executor,
355  node->get_node_base_interface(),
356  node->get_node_topics_interface(),
357  node->get_node_graph_interface(),
358  node->get_node_services_interface(),
359  remote_node_name,
360  qos_profile)
361  {}
362 
363  RCLCPP_PUBLIC
365  rclcpp::Executor::SharedPtr executor,
366  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
367  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
368  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
369  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
370  const std::string & remote_node_name = "",
371  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
372  : executor_(executor), node_base_interface_(node_base_interface)
373  {
374  async_parameters_client_ =
375  std::make_shared<AsyncParametersClient>(
376  node_base_interface,
377  node_topics_interface,
378  node_graph_interface,
379  node_services_interface,
380  remote_node_name,
381  qos_profile);
382  }
383 
384  template<typename RepT = int64_t, typename RatioT = std::milli>
385  std::vector<rclcpp::Parameter>
386  get_parameters(
387  const std::vector<std::string> & parameter_names,
388  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
389  {
390  return get_parameters(
391  parameter_names,
392  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
393  );
394  }
395 
396  RCLCPP_PUBLIC
397  bool
398  has_parameter(const std::string & parameter_name);
399 
400  template<typename T>
401  T
402  get_parameter_impl(
403  const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
404  {
405  std::vector<std::string> names;
406  names.push_back(parameter_name);
407  auto vars = get_parameters(names);
408  if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) {
409  return parameter_not_found_handler();
410  } else {
411  return static_cast<T>(vars[0].get_value<T>());
412  }
413  }
414 
415  template<typename T>
416  T
417  get_parameter(const std::string & parameter_name, const T & default_value)
418  {
419  return get_parameter_impl(
420  parameter_name,
421  std::function<T()>([&default_value]() -> T {return default_value;}));
422  }
423 
424  template<typename T>
425  T
426  get_parameter(const std::string & parameter_name)
427  {
428  return get_parameter_impl(
429  parameter_name,
430  std::function<T()>(
431  [&parameter_name]() -> T
432  {
433  throw std::runtime_error("Parameter '" + parameter_name + "' is not set");
434  })
435  );
436  }
437 
438  template<typename RepT = int64_t, typename RatioT = std::milli>
439  std::vector<rcl_interfaces::msg::ParameterDescriptor>
440  describe_parameters(
441  const std::vector<std::string> & parameter_names,
442  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
443  {
444  return describe_parameters(
445  parameter_names,
446  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
447  );
448  }
449 
450  template<typename RepT = int64_t, typename RatioT = std::milli>
451  std::vector<rclcpp::ParameterType>
452  get_parameter_types(
453  const std::vector<std::string> & parameter_names,
454  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
455  {
456  return get_parameter_types(
457  parameter_names,
458  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
459  );
460  }
461 
462  template<typename RepT = int64_t, typename RatioT = std::milli>
463  std::vector<rcl_interfaces::msg::SetParametersResult>
464  set_parameters(
465  const std::vector<rclcpp::Parameter> & parameters,
466  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
467  {
468  return set_parameters(
469  parameters,
470  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
471  );
472  }
473 
474  template<typename RepT = int64_t, typename RatioT = std::milli>
475  rcl_interfaces::msg::SetParametersResult
476  set_parameters_atomically(
477  const std::vector<rclcpp::Parameter> & parameters,
478  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
479  {
480  return set_parameters_atomically(
481  parameters,
482  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
483  );
484  }
485 
487 
494  template<typename RepT = int64_t, typename RatioT = std::milli>
495  std::vector<rcl_interfaces::msg::SetParametersResult>
497  const std::vector<std::string> & parameters_names,
498  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
499  {
500  return delete_parameters(
501  parameters_names,
502  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
503  );
504  }
505 
507 
514  template<typename RepT = int64_t, typename RatioT = std::milli>
515  std::vector<rcl_interfaces::msg::SetParametersResult>
517  const std::string & yaml_filename,
518  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
519  {
520  return load_parameters(
521  yaml_filename,
522  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
523  );
524  }
525 
526  template<typename RepT = int64_t, typename RatioT = std::milli>
527  rcl_interfaces::msg::ListParametersResult
528  list_parameters(
529  const std::vector<std::string> & parameter_prefixes,
530  uint64_t depth,
531  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
532  {
533  return list_parameters(
534  parameter_prefixes,
535  depth,
536  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
537  );
538  }
539 
540  template<typename CallbackT>
542  on_parameter_event(CallbackT && callback)
543  {
544  return async_parameters_client_->on_parameter_event(
545  std::forward<CallbackT>(callback));
546  }
547 
553  template<
554  typename CallbackT,
555  typename NodeT>
558  NodeT && node,
559  CallbackT && callback)
560  {
561  return AsyncParametersClient::on_parameter_event(
562  node,
563  std::forward<CallbackT>(callback));
564  }
565 
566  RCLCPP_PUBLIC
567  bool
568  service_is_ready() const
569  {
570  return async_parameters_client_->service_is_ready();
571  }
572 
573  template<typename RepT = int64_t, typename RatioT = std::milli>
574  bool
575  wait_for_service(
576  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
577  {
578  return async_parameters_client_->wait_for_service(timeout);
579  }
580 
581 protected:
582  RCLCPP_PUBLIC
583  std::vector<rclcpp::Parameter>
584  get_parameters(
585  const std::vector<std::string> & parameter_names,
586  std::chrono::nanoseconds timeout);
587 
588  RCLCPP_PUBLIC
589  std::vector<rcl_interfaces::msg::ParameterDescriptor>
590  describe_parameters(
591  const std::vector<std::string> & parameter_names,
592  std::chrono::nanoseconds timeout);
593 
594  RCLCPP_PUBLIC
595  std::vector<rclcpp::ParameterType>
596  get_parameter_types(
597  const std::vector<std::string> & parameter_names,
598  std::chrono::nanoseconds timeout);
599 
600  RCLCPP_PUBLIC
601  std::vector<rcl_interfaces::msg::SetParametersResult>
602  set_parameters(
603  const std::vector<rclcpp::Parameter> & parameters,
604  std::chrono::nanoseconds timeout);
605 
606  RCLCPP_PUBLIC
607  std::vector<rcl_interfaces::msg::SetParametersResult>
609  const std::vector<std::string> & parameters_names,
610  std::chrono::nanoseconds timeout);
611 
612  RCLCPP_PUBLIC
613  std::vector<rcl_interfaces::msg::SetParametersResult>
615  const std::string & yaml_filename,
616  std::chrono::nanoseconds timeout);
617 
618  RCLCPP_PUBLIC
619  rcl_interfaces::msg::SetParametersResult
620  set_parameters_atomically(
621  const std::vector<rclcpp::Parameter> & parameters,
622  std::chrono::nanoseconds timeout);
623 
624  RCLCPP_PUBLIC
625  rcl_interfaces::msg::ListParametersResult
626  list_parameters(
627  const std::vector<std::string> & parameter_prefixes,
628  uint64_t depth,
629  std::chrono::nanoseconds timeout);
630 
631 private:
632  rclcpp::Executor::SharedPtr executor_;
633  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
634  AsyncParametersClient::SharedPtr async_parameters_client_;
635 };
636 
637 } // namespace rclcpp
638 
639 #endif // RCLCPP__PARAMETER_CLIENT_HPP_
RCLCPP_PUBLIC std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > load_parameters(const std::string &yaml_filename)
Load parameters from yaml file.
AsyncParametersClient(const std::shared_ptr< NodeT > node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Constructor.
RCLCPP_PUBLIC AsyncParametersClient(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create an async parameters client.
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Wait for the services to be ready.
RCLCPP_PUBLIC bool service_is_ready() const
Return if the parameter services are ready.
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(NodeT &&node, CallbackT &&callback, const rclcpp::QoS &qos=(rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))), const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
RCLCPP_PUBLIC std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > delete_parameters(const std::vector< std::string > &parameters_names)
Delete several parameters at once.
AsyncParametersClient(NodeT *node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Constructor.
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
Subscription implementation, templated on the type of message this subscription receives.
std::vector< rcl_interfaces::msg::SetParametersResult > delete_parameters(const std::vector< std::string > &parameters_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.
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(NodeT &&node, CallbackT &&callback)
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
std::unordered_map< std::string, std::vector< Parameter > > ParameterMap
A map of fully qualified node names to a list of parameters.
static QoSInitialization from_rmw(const rmw_qos_profile_t &rmw_qos)
Create a QoSInitialization from an existing rmw_qos_profile_t, using its history and depth.
Definition: qos.cpp:51
Structure containing optional configuration for Subscriptions.