ROS 2 rclcpp + rcl - jazzy  jazzy
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 
66  [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
67  RCLCPP_PUBLIC
69  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
70  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
71  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
72  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
73  const std::string & remote_node_name,
74  const rmw_qos_profile_t & qos_profile,
75  rclcpp::CallbackGroup::SharedPtr group = nullptr)
77  node_base_interface,
78  node_topics_interface,
79  node_graph_interface,
80  node_services_interface,
81  remote_node_name,
82  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)),
83  group)
84  {}
85 
87 
96  RCLCPP_PUBLIC
98  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
99  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
100  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
101  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
102  const std::string & remote_node_name = "",
103  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(),
104  rclcpp::CallbackGroup::SharedPtr group = nullptr);
105 
107 
114  template<typename NodeT>
115  [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
117  const std::shared_ptr<NodeT> node,
118  const std::string & remote_node_name,
119  const rmw_qos_profile_t & qos_profile,
120  rclcpp::CallbackGroup::SharedPtr group = nullptr)
122  node->get_node_base_interface(),
123  node->get_node_topics_interface(),
124  node->get_node_graph_interface(),
125  node->get_node_services_interface(),
126  remote_node_name,
127  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)),
128  group)
129  {}
130 
137  template<typename NodeT>
139  const std::shared_ptr<NodeT> node,
140  const std::string & remote_node_name = "",
141  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(),
142  rclcpp::CallbackGroup::SharedPtr group = nullptr)
144  node->get_node_base_interface(),
145  node->get_node_topics_interface(),
146  node->get_node_graph_interface(),
147  node->get_node_services_interface(),
148  remote_node_name,
149  qos_profile,
150  group)
151  {}
152 
154 
161  template<typename NodeT>
162  [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
164  NodeT * node,
165  const std::string & remote_node_name,
166  const rmw_qos_profile_t & qos_profile,
167  rclcpp::CallbackGroup::SharedPtr group = nullptr)
169  node->get_node_base_interface(),
170  node->get_node_topics_interface(),
171  node->get_node_graph_interface(),
172  node->get_node_services_interface(),
173  remote_node_name,
174  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)),
175  group)
176  {}
177 
184  template<typename NodeT>
186  NodeT * node,
187  const std::string & remote_node_name = "",
188  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS(),
189  rclcpp::CallbackGroup::SharedPtr group = nullptr)
191  node->get_node_base_interface(),
192  node->get_node_topics_interface(),
193  node->get_node_graph_interface(),
194  node->get_node_services_interface(),
195  remote_node_name,
196  qos_profile,
197  group)
198  {}
199 
200  RCLCPP_PUBLIC
201  std::shared_future<std::vector<rclcpp::Parameter>>
202  get_parameters(
203  const std::vector<std::string> & names,
204  std::function<
205  void(std::shared_future<std::vector<rclcpp::Parameter>>)
206  > callback = nullptr);
207 
208  RCLCPP_PUBLIC
209  std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>
210  describe_parameters(
211  const std::vector<std::string> & names,
212  std::function<
213  void(std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>)
214  > callback = nullptr);
215 
216  RCLCPP_PUBLIC
217  std::shared_future<std::vector<rclcpp::ParameterType>>
218  get_parameter_types(
219  const std::vector<std::string> & names,
220  std::function<
221  void(std::shared_future<std::vector<rclcpp::ParameterType>>)
222  > callback = nullptr);
223 
224  RCLCPP_PUBLIC
225  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
226  set_parameters(
227  const std::vector<rclcpp::Parameter> & parameters,
228  std::function<
229  void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)
230  > callback = nullptr);
231 
232  RCLCPP_PUBLIC
233  std::shared_future<rcl_interfaces::msg::SetParametersResult>
234  set_parameters_atomically(
235  const std::vector<rclcpp::Parameter> & parameters,
236  std::function<
237  void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)
238  > callback = nullptr);
239 
241 
247  RCLCPP_PUBLIC
248  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
250  const std::vector<std::string> & parameters_names);
251 
253 
259  RCLCPP_PUBLIC
260  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
262  const std::string & yaml_filename);
263 
265 
275  RCLCPP_PUBLIC
276  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
277  load_parameters(const rclcpp::ParameterMap & parameter_map);
278 
279  RCLCPP_PUBLIC
280  std::shared_future<rcl_interfaces::msg::ListParametersResult>
281  list_parameters(
282  const std::vector<std::string> & prefixes,
283  uint64_t depth,
284  std::function<
285  void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)
286  > callback = nullptr);
287 
288  template<
289  typename CallbackT,
290  typename AllocatorT = std::allocator<void>>
292  on_parameter_event(
293  CallbackT && callback,
294  const rclcpp::QoS & qos = rclcpp::ParameterEventsQoS(),
297  ))
298  {
299  return this->on_parameter_event(
300  this->node_topics_interface_,
301  callback,
302  qos,
303  options);
304  }
305 
311  template<
312  typename CallbackT,
313  typename NodeT,
314  typename AllocatorT = std::allocator<void>>
317  NodeT && node,
318  CallbackT && callback,
319  const rclcpp::QoS & qos = rclcpp::ParameterEventsQoS(),
322  ))
323  {
324  return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
325  node,
326  "/parameter_events",
327  qos,
328  std::forward<CallbackT>(callback),
329  options);
330  }
331 
333 
343  RCLCPP_PUBLIC
344  bool
345  service_is_ready() const;
346 
348 
352  template<typename RepT = int64_t, typename RatioT = std::milli>
353  bool
355  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
356  {
357  return wait_for_service_nanoseconds(
358  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
359  );
360  }
361 
362 protected:
363  RCLCPP_PUBLIC
364  bool
365  wait_for_service_nanoseconds(std::chrono::nanoseconds timeout);
366 
367 private:
368  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
371  get_parameter_types_client_;
374  set_parameters_atomically_client_;
377  describe_parameters_client_;
378  std::string remote_node_name_;
379 };
380 
382 {
383 public:
384  RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient)
385 
386  template<typename NodeT>
387  [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
389  std::shared_ptr<NodeT> node,
390  const std::string & remote_node_name,
391  const rmw_qos_profile_t & qos_profile)
393  std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
394  node,
395  remote_node_name,
397  {}
398 
399  template<typename NodeT>
400  explicit SyncParametersClient(
401  std::shared_ptr<NodeT> node,
402  const std::string & remote_node_name = "",
403  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
405  std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
406  node,
407  remote_node_name,
408  qos_profile)
409  {}
410 
411  template<typename NodeT>
412  [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
414  rclcpp::Executor::SharedPtr executor,
415  std::shared_ptr<NodeT> node,
416  const std::string & remote_node_name,
417  const rmw_qos_profile_t & qos_profile)
419  executor,
420  node->get_node_base_interface(),
421  node->get_node_topics_interface(),
422  node->get_node_graph_interface(),
423  node->get_node_services_interface(),
424  remote_node_name,
426  {}
427 
428  template<typename NodeT>
430  rclcpp::Executor::SharedPtr executor,
431  std::shared_ptr<NodeT> node,
432  const std::string & remote_node_name = "",
433  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
435  executor,
436  node->get_node_base_interface(),
437  node->get_node_topics_interface(),
438  node->get_node_graph_interface(),
439  node->get_node_services_interface(),
440  remote_node_name,
441  qos_profile)
442  {}
443 
444  template<typename NodeT>
445  [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
447  NodeT * node,
448  const std::string & remote_node_name,
449  const rmw_qos_profile_t & qos_profile)
451  std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
452  node,
453  remote_node_name,
455  {}
456 
457  template<typename NodeT>
458  explicit SyncParametersClient(
459  NodeT * node,
460  const std::string & remote_node_name = "",
461  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
463  std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
464  node,
465  remote_node_name,
466  qos_profile)
467  {}
468 
469  template<typename NodeT>
470  [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
472  rclcpp::Executor::SharedPtr executor,
473  NodeT * node,
474  const std::string & remote_node_name,
475  const rmw_qos_profile_t & qos_profile)
477  executor,
478  node->get_node_base_interface(),
479  node->get_node_topics_interface(),
480  node->get_node_graph_interface(),
481  node->get_node_services_interface(),
482  remote_node_name,
484  {}
485 
486  template<typename NodeT>
488  rclcpp::Executor::SharedPtr executor,
489  NodeT * node,
490  const std::string & remote_node_name = "",
491  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
493  executor,
494  node->get_node_base_interface(),
495  node->get_node_topics_interface(),
496  node->get_node_graph_interface(),
497  node->get_node_services_interface(),
498  remote_node_name,
499  qos_profile)
500  {}
501 
502  [[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
503  RCLCPP_PUBLIC
505  rclcpp::Executor::SharedPtr executor,
506  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
507  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
508  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
509  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
510  const std::string & remote_node_name,
511  const rmw_qos_profile_t & qos_profile)
512  : executor_(executor), node_base_interface_(node_base_interface)
513  {
514  async_parameters_client_ =
515  std::make_shared<AsyncParametersClient>(
516  node_base_interface,
517  node_topics_interface,
518  node_graph_interface,
519  node_services_interface,
520  remote_node_name,
522  }
523 
524  RCLCPP_PUBLIC
526  rclcpp::Executor::SharedPtr executor,
527  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
528  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
529  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
530  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
531  const std::string & remote_node_name = "",
532  const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
533  : executor_(executor), node_base_interface_(node_base_interface)
534  {
535  async_parameters_client_ =
536  std::make_shared<AsyncParametersClient>(
537  node_base_interface,
538  node_topics_interface,
539  node_graph_interface,
540  node_services_interface,
541  remote_node_name,
542  qos_profile);
543  }
544 
545  template<typename RepT = int64_t, typename RatioT = std::milli>
546  std::vector<rclcpp::Parameter>
547  get_parameters(
548  const std::vector<std::string> & parameter_names,
549  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
550  {
551  return get_parameters(
552  parameter_names,
553  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
554  );
555  }
556 
557  RCLCPP_PUBLIC
558  bool
559  has_parameter(const std::string & parameter_name);
560 
561  template<typename T>
562  T
563  get_parameter_impl(
564  const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
565  {
566  std::vector<std::string> names;
567  names.push_back(parameter_name);
568  auto vars = get_parameters(names);
569  if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) {
570  return parameter_not_found_handler();
571  } else {
572  return static_cast<T>(vars[0].get_value<T>());
573  }
574  }
575 
576  template<typename T>
577  T
578  get_parameter(const std::string & parameter_name, const T & default_value)
579  {
580  return get_parameter_impl(
581  parameter_name,
582  std::function<T()>([&default_value]() -> T {return default_value;}));
583  }
584 
585  template<typename T>
586  T
587  get_parameter(const std::string & parameter_name)
588  {
589  return get_parameter_impl(
590  parameter_name,
591  std::function<T()>(
592  [&parameter_name]() -> T
593  {
594  throw std::runtime_error("Parameter '" + parameter_name + "' is not set");
595  })
596  );
597  }
598 
599  template<typename RepT = int64_t, typename RatioT = std::milli>
600  std::vector<rcl_interfaces::msg::ParameterDescriptor>
601  describe_parameters(
602  const std::vector<std::string> & parameter_names,
603  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
604  {
605  return describe_parameters(
606  parameter_names,
607  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
608  );
609  }
610 
611  template<typename RepT = int64_t, typename RatioT = std::milli>
612  std::vector<rclcpp::ParameterType>
613  get_parameter_types(
614  const std::vector<std::string> & parameter_names,
615  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
616  {
617  return get_parameter_types(
618  parameter_names,
619  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
620  );
621  }
622 
623  template<typename RepT = int64_t, typename RatioT = std::milli>
624  std::vector<rcl_interfaces::msg::SetParametersResult>
625  set_parameters(
626  const std::vector<rclcpp::Parameter> & parameters,
627  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
628  {
629  return set_parameters(
630  parameters,
631  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
632  );
633  }
634 
635  template<typename RepT = int64_t, typename RatioT = std::milli>
636  rcl_interfaces::msg::SetParametersResult
637  set_parameters_atomically(
638  const std::vector<rclcpp::Parameter> & parameters,
639  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
640  {
641  return set_parameters_atomically(
642  parameters,
643  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
644  );
645  }
646 
648 
655  template<typename RepT = int64_t, typename RatioT = std::milli>
656  std::vector<rcl_interfaces::msg::SetParametersResult>
658  const std::vector<std::string> & parameters_names,
659  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
660  {
661  return delete_parameters(
662  parameters_names,
663  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
664  );
665  }
666 
668 
675  template<typename RepT = int64_t, typename RatioT = std::milli>
676  std::vector<rcl_interfaces::msg::SetParametersResult>
678  const std::string & yaml_filename,
679  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
680  {
681  return load_parameters(
682  yaml_filename,
683  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
684  );
685  }
686 
687  template<typename RepT = int64_t, typename RatioT = std::milli>
688  rcl_interfaces::msg::ListParametersResult
689  list_parameters(
690  const std::vector<std::string> & parameter_prefixes,
691  uint64_t depth,
692  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
693  {
694  return list_parameters(
695  parameter_prefixes,
696  depth,
697  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
698  );
699  }
700 
701  template<typename CallbackT>
703  on_parameter_event(CallbackT && callback)
704  {
705  return async_parameters_client_->on_parameter_event(
706  std::forward<CallbackT>(callback));
707  }
708 
714  template<
715  typename CallbackT,
716  typename NodeT>
719  NodeT && node,
720  CallbackT && callback)
721  {
722  return AsyncParametersClient::on_parameter_event(
723  node,
724  std::forward<CallbackT>(callback));
725  }
726 
727  RCLCPP_PUBLIC
728  bool
729  service_is_ready() const
730  {
731  return async_parameters_client_->service_is_ready();
732  }
733 
734  template<typename RepT = int64_t, typename RatioT = std::milli>
735  bool
736  wait_for_service(
737  std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
738  {
739  return async_parameters_client_->wait_for_service(timeout);
740  }
741 
742 protected:
743  RCLCPP_PUBLIC
744  std::vector<rclcpp::Parameter>
745  get_parameters(
746  const std::vector<std::string> & parameter_names,
747  std::chrono::nanoseconds timeout);
748 
749  RCLCPP_PUBLIC
750  std::vector<rcl_interfaces::msg::ParameterDescriptor>
751  describe_parameters(
752  const std::vector<std::string> & parameter_names,
753  std::chrono::nanoseconds timeout);
754 
755  RCLCPP_PUBLIC
756  std::vector<rclcpp::ParameterType>
757  get_parameter_types(
758  const std::vector<std::string> & parameter_names,
759  std::chrono::nanoseconds timeout);
760 
761  RCLCPP_PUBLIC
762  std::vector<rcl_interfaces::msg::SetParametersResult>
763  set_parameters(
764  const std::vector<rclcpp::Parameter> & parameters,
765  std::chrono::nanoseconds timeout);
766 
767  RCLCPP_PUBLIC
768  std::vector<rcl_interfaces::msg::SetParametersResult>
770  const std::vector<std::string> & parameters_names,
771  std::chrono::nanoseconds timeout);
772 
773  RCLCPP_PUBLIC
774  std::vector<rcl_interfaces::msg::SetParametersResult>
776  const std::string & yaml_filename,
777  std::chrono::nanoseconds timeout);
778 
779  RCLCPP_PUBLIC
780  rcl_interfaces::msg::SetParametersResult
781  set_parameters_atomically(
782  const std::vector<rclcpp::Parameter> & parameters,
783  std::chrono::nanoseconds timeout);
784 
785  RCLCPP_PUBLIC
786  rcl_interfaces::msg::ListParametersResult
787  list_parameters(
788  const std::vector<std::string> & parameter_prefixes,
789  uint64_t depth,
790  std::chrono::nanoseconds timeout);
791 
792 private:
793  rclcpp::Executor::SharedPtr executor_;
794  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
795  AsyncParametersClient::SharedPtr async_parameters_client_;
796 };
797 
798 } // namespace rclcpp
799 
800 #endif // RCLCPP__PARAMETER_CLIENT_HPP_
AsyncParametersClient(NodeT *node, const std::string &remote_node_name, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Constructor.
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 >()))
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, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create an async parameters client.
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.
AsyncParametersClient(const std::shared_ptr< NodeT > node, const std::string &remote_node_name, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Constructor.
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)
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.
QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
Definition: qos.hpp:78
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:63
Structure containing optional configuration for Subscriptions.