ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
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/qos.hpp"
43 #include "rclcpp/type_support_decl.hpp"
44 #include "rclcpp/visibility_control.hpp"
45 #include "rmw/rmw.h"
46 
47 namespace rclcpp
48 {
49 
51 {
52 public:
53  RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient)
54 
55 
65  RCLCPP_PUBLIC
67  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
68  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
69  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
70  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
71  const std::string & remote_node_name = "",
72  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(),
73  rclcpp::CallbackGroup::SharedPtr group = nullptr);
74 
81  template<typename NodeT>
83  const std::shared_ptr<NodeT> node,
84  const std::string & remote_node_name = "",
85  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(),
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 
103  template<typename NodeT>
105  NodeT * node,
106  const std::string & remote_node_name = "",
107  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(),
108  rclcpp::CallbackGroup::SharedPtr group = nullptr)
110  node->get_node_base_interface(),
111  node->get_node_topics_interface(),
112  node->get_node_graph_interface(),
113  node->get_node_services_interface(),
114  remote_node_name,
115  qos_profile,
116  group)
117  {}
118 
119  RCLCPP_PUBLIC
120  std::shared_future<std::vector<rclcpp::Parameter>>
121  get_parameters(
122  const std::vector<std::string> & names,
123  std::function<
124  void(std::shared_future<std::vector<rclcpp::Parameter>>)
125  > callback = nullptr);
126 
127  RCLCPP_PUBLIC
128  std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>
129  describe_parameters(
130  const std::vector<std::string> & names,
131  std::function<
132  void(std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>)
133  > callback = nullptr);
134 
135  RCLCPP_PUBLIC
136  std::shared_future<std::vector<rclcpp::ParameterType>>
137  get_parameter_types(
138  const std::vector<std::string> & names,
139  std::function<
140  void(std::shared_future<std::vector<rclcpp::ParameterType>>)
141  > callback = nullptr);
142 
143  RCLCPP_PUBLIC
144  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
145  set_parameters(
146  const std::vector<rclcpp::Parameter> & parameters,
147  std::function<
148  void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)
149  > callback = nullptr);
150 
151  RCLCPP_PUBLIC
152  std::shared_future<rcl_interfaces::msg::SetParametersResult>
153  set_parameters_atomically(
154  const std::vector<rclcpp::Parameter> & parameters,
155  std::function<
156  void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)
157  > callback = nullptr);
158 
160 
166  RCLCPP_PUBLIC
167  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
169  const std::vector<std::string> & parameters_names);
170 
172 
178  RCLCPP_PUBLIC
179  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
181  const std::string & yaml_filename);
182 
184 
194  RCLCPP_PUBLIC
195  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
196  load_parameters(const rclcpp::ParameterMap & parameter_map);
197 
198  RCLCPP_PUBLIC
199  std::shared_future<rcl_interfaces::msg::ListParametersResult>
200  list_parameters(
201  const std::vector<std::string> & prefixes,
202  uint64_t depth,
203  std::function<
204  void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)
205  > callback = nullptr);
206 
207  template<
208  typename CallbackT,
209  typename AllocatorT = std::allocator<void>>
211  on_parameter_event(
212  CallbackT && callback,
213  const rclcpp::QoS & qos = rclcpp::ParameterEventsQoS(),
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 = rclcpp::ParameterEventsQoS(),
241  ))
242  {
243  return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
244  node,
245  "/parameter_events",
246  qos,
247  std::forward<CallbackT>(callback),
248  options);
249  }
250 
252 
262  RCLCPP_PUBLIC
263  bool
264  service_is_ready() const;
265 
267 
271  template<typename RepT = int64_t, typename RatioT = std::milli>
272  bool
274  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
275  {
276  return wait_for_service_nanoseconds(
277  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
278  );
279  }
280 
281 protected:
282  RCLCPP_PUBLIC
283  bool
284  wait_for_service_nanoseconds(std::chrono::nanoseconds timeout);
285 
286 private:
287  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
290  get_parameter_types_client_;
293  set_parameters_atomically_client_;
296  describe_parameters_client_;
297  std::string remote_node_name_;
298 };
299 
301 {
302 public:
303  RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient)
304 
305  template<typename NodeT>
306  explicit SyncParametersClient(
307  std::shared_ptr<NodeT> node,
308  const std::string & remote_node_name = "",
309  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
311  std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
312  node,
313  remote_node_name,
314  qos_profile)
315  {}
316 
317  template<typename NodeT>
319  rclcpp::Executor::SharedPtr executor,
320  std::shared_ptr<NodeT> node,
321  const std::string & remote_node_name = "",
322  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
324  executor,
325  node->get_node_base_interface(),
326  node->get_node_topics_interface(),
327  node->get_node_graph_interface(),
328  node->get_node_services_interface(),
329  remote_node_name,
330  qos_profile)
331  {}
332 
333  template<typename NodeT>
334  explicit SyncParametersClient(
335  NodeT * node,
336  const std::string & remote_node_name = "",
337  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
339  std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
340  node,
341  remote_node_name,
342  qos_profile)
343  {}
344 
345  template<typename NodeT>
347  rclcpp::Executor::SharedPtr executor,
348  NodeT * node,
349  const std::string & remote_node_name = "",
350  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
352  executor,
353  node->get_node_base_interface(),
354  node->get_node_topics_interface(),
355  node->get_node_graph_interface(),
356  node->get_node_services_interface(),
357  remote_node_name,
358  qos_profile)
359  {}
360 
361  RCLCPP_PUBLIC
363  rclcpp::Executor::SharedPtr executor,
364  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
365  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
366  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
367  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
368  const std::string & remote_node_name = "",
369  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
370  : executor_(executor), node_base_interface_(node_base_interface)
371  {
372  async_parameters_client_ =
373  std::make_shared<AsyncParametersClient>(
374  node_base_interface,
375  node_topics_interface,
376  node_graph_interface,
377  node_services_interface,
378  remote_node_name,
379  qos_profile);
380  }
381 
382  template<typename RepT = int64_t, typename RatioT = std::milli>
383  std::vector<rclcpp::Parameter>
384  get_parameters(
385  const std::vector<std::string> & parameter_names,
386  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
387  {
388  return get_parameters(
389  parameter_names,
390  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
391  );
392  }
393 
394  RCLCPP_PUBLIC
395  bool
396  has_parameter(const std::string & parameter_name);
397 
398  template<typename T>
399  T
400  get_parameter_impl(
401  const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
402  {
403  std::vector<std::string> names;
404  names.push_back(parameter_name);
405  auto vars = get_parameters(names);
406  if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) {
407  return parameter_not_found_handler();
408  } else {
409  return static_cast<T>(vars[0].get_value<T>());
410  }
411  }
412 
413  template<typename T>
414  T
415  get_parameter(const std::string & parameter_name, const T & default_value)
416  {
417  return get_parameter_impl(
418  parameter_name,
419  std::function<T()>([&default_value]() -> T {return default_value;}));
420  }
421 
422  template<typename T>
423  T
424  get_parameter(const std::string & parameter_name)
425  {
426  return get_parameter_impl(
427  parameter_name,
428  std::function<T()>(
429  [&parameter_name]() -> T
430  {
431  throw std::runtime_error("Parameter '" + parameter_name + "' is not set");
432  })
433  );
434  }
435 
436  template<typename RepT = int64_t, typename RatioT = std::milli>
437  std::vector<rcl_interfaces::msg::ParameterDescriptor>
438  describe_parameters(
439  const std::vector<std::string> & parameter_names,
440  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
441  {
442  return describe_parameters(
443  parameter_names,
444  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
445  );
446  }
447 
448  template<typename RepT = int64_t, typename RatioT = std::milli>
449  std::vector<rclcpp::ParameterType>
450  get_parameter_types(
451  const std::vector<std::string> & parameter_names,
452  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
453  {
454  return get_parameter_types(
455  parameter_names,
456  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
457  );
458  }
459 
460  template<typename RepT = int64_t, typename RatioT = std::milli>
461  std::vector<rcl_interfaces::msg::SetParametersResult>
462  set_parameters(
463  const std::vector<rclcpp::Parameter> & parameters,
464  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
465  {
466  return set_parameters(
467  parameters,
468  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
469  );
470  }
471 
472  template<typename RepT = int64_t, typename RatioT = std::milli>
473  rcl_interfaces::msg::SetParametersResult
474  set_parameters_atomically(
475  const std::vector<rclcpp::Parameter> & parameters,
476  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
477  {
478  return set_parameters_atomically(
479  parameters,
480  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
481  );
482  }
483 
485 
492  template<typename RepT = int64_t, typename RatioT = std::milli>
493  std::vector<rcl_interfaces::msg::SetParametersResult>
495  const std::vector<std::string> & parameters_names,
496  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
497  {
498  return delete_parameters(
499  parameters_names,
500  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
501  );
502  }
503 
505 
512  template<typename RepT = int64_t, typename RatioT = std::milli>
513  std::vector<rcl_interfaces::msg::SetParametersResult>
515  const std::string & yaml_filename,
516  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
517  {
518  return load_parameters(
519  yaml_filename,
520  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
521  );
522  }
523 
524  template<typename RepT = int64_t, typename RatioT = std::milli>
525  rcl_interfaces::msg::ListParametersResult
526  list_parameters(
527  const std::vector<std::string> & parameter_prefixes,
528  uint64_t depth,
529  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
530  {
531  return list_parameters(
532  parameter_prefixes,
533  depth,
534  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
535  );
536  }
537 
538  template<typename CallbackT>
540  on_parameter_event(CallbackT && callback)
541  {
542  return async_parameters_client_->on_parameter_event(
543  std::forward<CallbackT>(callback));
544  }
545 
551  template<
552  typename CallbackT,
553  typename NodeT>
556  NodeT && node,
557  CallbackT && callback)
558  {
559  return AsyncParametersClient::on_parameter_event(
560  node,
561  std::forward<CallbackT>(callback));
562  }
563 
564  RCLCPP_PUBLIC
565  bool
566  service_is_ready() const
567  {
568  return async_parameters_client_->service_is_ready();
569  }
570 
571  template<typename RepT = int64_t, typename RatioT = std::milli>
572  bool
573  wait_for_service(
574  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
575  {
576  return async_parameters_client_->wait_for_service(timeout);
577  }
578 
579 protected:
580  RCLCPP_PUBLIC
581  std::vector<rclcpp::Parameter>
582  get_parameters(
583  const std::vector<std::string> & parameter_names,
584  std::chrono::nanoseconds timeout);
585 
586  RCLCPP_PUBLIC
587  std::vector<rcl_interfaces::msg::ParameterDescriptor>
588  describe_parameters(
589  const std::vector<std::string> & parameter_names,
590  std::chrono::nanoseconds timeout);
591 
592  RCLCPP_PUBLIC
593  std::vector<rclcpp::ParameterType>
594  get_parameter_types(
595  const std::vector<std::string> & parameter_names,
596  std::chrono::nanoseconds timeout);
597 
598  RCLCPP_PUBLIC
599  std::vector<rcl_interfaces::msg::SetParametersResult>
600  set_parameters(
601  const std::vector<rclcpp::Parameter> & parameters,
602  std::chrono::nanoseconds timeout);
603 
604  RCLCPP_PUBLIC
605  std::vector<rcl_interfaces::msg::SetParametersResult>
607  const std::vector<std::string> & parameters_names,
608  std::chrono::nanoseconds timeout);
609 
610  RCLCPP_PUBLIC
611  std::vector<rcl_interfaces::msg::SetParametersResult>
613  const std::string & yaml_filename,
614  std::chrono::nanoseconds timeout);
615 
616  RCLCPP_PUBLIC
617  rcl_interfaces::msg::SetParametersResult
618  set_parameters_atomically(
619  const std::vector<rclcpp::Parameter> & parameters,
620  std::chrono::nanoseconds timeout);
621 
622  RCLCPP_PUBLIC
623  rcl_interfaces::msg::ListParametersResult
624  list_parameters(
625  const std::vector<std::string> & parameter_prefixes,
626  uint64_t depth,
627  std::chrono::nanoseconds timeout);
628 
629 private:
630  rclcpp::Executor::SharedPtr executor_;
631  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
632  AsyncParametersClient::SharedPtr async_parameters_client_;
633 };
634 
635 } // namespace rclcpp
636 
637 #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.
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(NodeT &&node, CallbackT &&callback, const rclcpp::QoS &qos=rclcpp::ParameterEventsQoS(), const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
AsyncParametersClient(const std::shared_ptr< NodeT > node, const std::string &remote_node_name="", const rclcpp::QoS &qos_profile=rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
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.
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 rclcpp::QoS &qos_profile=rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
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 rclcpp::QoS &qos_profile=rclcpp::ParametersQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create an async parameters client.
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
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.
Structure containing optional configuration for Subscriptions.