rclcpp  master
C++ ROS Client Library API
parameter_client.hpp
Go to the documentation of this file.
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"
38 #include "rclcpp/macros.hpp"
39 #include "rclcpp/node.hpp"
40 #include "rclcpp/parameter.hpp"
41 #include "rclcpp/parameter_map.hpp"
44 #include "rmw/rmw.h"
45 
46 namespace rclcpp
47 {
48 
50 {
51 public:
53 
54 
55 
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)
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(),
113  node->get_node_graph_interface(),
115  remote_node_name,
116  qos_profile,
117  group)
118  {}
119 
123  const std::vector<std::string> & names,
126  > callback = nullptr);
127 
131  const std::vector<std::string> & names,
134  > callback = nullptr);
135 
139  const std::vector<std::string> & names,
142  > callback = nullptr);
143 
147  const std::vector<rclcpp::Parameter> & parameters,
150  > callback = nullptr);
151 
155  const std::vector<rclcpp::Parameter> & parameters,
158  > callback = nullptr);
159 
161 
170  const std::vector<std::string> & parameters_names);
171 
173 
182  const std::string & yaml_filename);
183 
185 
194  load_parameters(const rclcpp::ParameterMap & parameter_map);
195 
199  const std::vector<std::string> & prefixes,
200  uint64_t depth,
203  > callback = nullptr);
204 
205  template<
206  typename CallbackT,
207  typename AllocatorT = std::allocator<void>>
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 
265  bool
266  service_is_ready() const;
267 
269 
273  template<typename RepT = int64_t, typename RatioT = std::milli>
274  bool
277  {
279  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
280  );
281  }
282 
283 protected:
285  bool
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:
306 
307  template<typename NodeT>
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,
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(),
329  node->get_node_graph_interface(),
331  remote_node_name,
332  qos_profile)
333  {}
334 
335  template<typename NodeT>
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(),
357  node->get_node_graph_interface(),
359  remote_node_name,
360  qos_profile)
361  {}
362 
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>
387  const std::vector<std::string> & parameter_names,
389  {
390  return get_parameters(
391  parameter_names,
392  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
393  );
394  }
395 
397  bool
398  has_parameter(const std::string & parameter_name);
399 
400  template<typename T>
401  T
403  const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
404  {
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>
441  const std::vector<std::string> & parameter_names,
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>
453  const std::vector<std::string> & parameter_names,
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>
465  const std::vector<rclcpp::Parameter> & parameters,
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
477  const std::vector<rclcpp::Parameter> & parameters,
479  {
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>
497  const std::vector<std::string> & parameters_names,
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>
517  const std::string & yaml_filename,
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
529  const std::vector<std::string> & parameter_prefixes,
530  uint64_t depth,
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  {
562  node,
563  std::forward<CallbackT>(callback));
564  }
565 
567  bool
569  {
570  return async_parameters_client_->service_is_ready();
571  }
572 
573  template<typename RepT = int64_t, typename RatioT = std::milli>
574  bool
577  {
578  return async_parameters_client_->wait_for_service(timeout);
579  }
580 
581 protected:
585  const std::vector<std::string> & parameter_names,
586  std::chrono::nanoseconds timeout);
587 
591  const std::vector<std::string> & parameter_names,
592  std::chrono::nanoseconds timeout);
593 
597  const std::vector<std::string> & parameter_names,
598  std::chrono::nanoseconds timeout);
599 
603  const std::vector<rclcpp::Parameter> & parameters,
604  std::chrono::nanoseconds timeout);
605 
609  const std::vector<std::string> & parameters_names,
610  std::chrono::nanoseconds timeout);
611 
615  const std::string & yaml_filename,
616  std::chrono::nanoseconds timeout);
617 
619  rcl_interfaces::msg::SetParametersResult
621  const std::vector<rclcpp::Parameter> & parameters,
622  std::chrono::nanoseconds timeout);
623 
625  rcl_interfaces::msg::ListParametersResult
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::node_interfaces::get_node_graph_interface
std::shared_ptr< rclcpp::node_interfaces::NodeGraphInterface > get_node_graph_interface(NodeType &&node)
Get the NodeGraphInterface as a shared pointer from a pointer to a "Node like" object.
Definition: get_node_graph_interface.hpp:72
std::shared_future
exceptions.hpp
rclcpp::SyncParametersClient::service_is_ready
bool service_is_ready() const
Definition: parameter_client.hpp:568
std::string
rclcpp::SyncParametersClient::get_parameters
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &parameter_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:386
std::shared_ptr
rclcpp::node_interfaces::get_node_services_interface
std::shared_ptr< rclcpp::node_interfaces::NodeServicesInterface > get_node_services_interface(NodeType &&node)
Get the NodeServicesInterface as a shared pointer from a pointer to a "Node like" object.
Definition: get_node_services_interface.hpp:72
rclcpp::AsyncParametersClient::on_parameter_event
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 >()))
Definition: parameter_client.hpp:235
rmw.h
rclcpp::SyncParametersClient::set_parameters
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:464
rclcpp::node_interfaces::get_node_base_interface
std::shared_ptr< rclcpp::node_interfaces::NodeBaseInterface > get_node_base_interface(NodeType &&node)
Get the NodeBaseInterface as a shared pointer from a pointer to a "Node like" object.
Definition: get_node_base_interface.hpp:72
std::vector< std::string >
rclcpp::SyncParametersClient::delete_parameters
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.
Definition: parameter_client.hpp:496
node.hpp
std::chrono::duration
rclcpp::SyncParametersClient::get_parameter_types
std::vector< rclcpp::ParameterType > get_parameter_types(const std::vector< std::string > &parameter_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:452
rclcpp::SubscriptionOptionsWithAllocator
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:87
rclcpp::SyncParametersClient::on_parameter_event
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(NodeT &&node, CallbackT &&callback)
Definition: parameter_client.hpp:557
std::function
executors.hpp
rclcpp::AsyncParametersClient::AsyncParametersClient
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.
Definition: parameter_client.hpp:105
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
rclcpp::AsyncParametersClient::delete_parameters
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > delete_parameters(const std::vector< std::string > &parameters_names)
Delete several parameters at once.
rclcpp::Subscription
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::SyncParametersClient::has_parameter
bool has_parameter(const std::string &parameter_name)
parameter_map.hpp
std::vector::push_back
T push_back(T... args)
rclcpp::SyncParametersClient::SyncParametersClient
SyncParametersClient(rclcpp::Executor::SharedPtr executor, NodeT *node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
Definition: parameter_client.hpp:348
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
rclcpp::SyncParametersClient::wait_for_service
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:575
RCLCPP_SMART_PTR_DEFINITIONS
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
macros.hpp
rclcpp::SyncParametersClient::SyncParametersClient
SyncParametersClient(NodeT *node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
Definition: parameter_client.hpp:336
rclcpp::QoSInitialization::from_rmw
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.
rclcpp::SyncParametersClient::on_parameter_event
rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:542
rclcpp::SyncParametersClient::SyncParametersClient
SyncParametersClient(rclcpp::Executor::SharedPtr executor, 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)
Definition: parameter_client.hpp:364
rclcpp::AsyncParametersClient::get_parameter_types
std::shared_future< std::vector< rclcpp::ParameterType > > get_parameter_types(const std::vector< std::string > &names, std::function< void(std::shared_future< std::vector< rclcpp::ParameterType >>) > callback=nullptr)
rclcpp::AsyncParametersClient::get_parameters
std::shared_future< std::vector< rclcpp::Parameter > > get_parameters(const std::vector< std::string > &names, std::function< void(std::shared_future< std::vector< rclcpp::Parameter >>) > callback=nullptr)
rclcpp::AsyncParametersClient::set_parameters_atomically
std::shared_future< rcl_interfaces::msg::SetParametersResult > set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters, std::function< void(std::shared_future< rcl_interfaces::msg::SetParametersResult >) > callback=nullptr)
rclcpp::AsyncParametersClient::wait_for_service
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Wait for the services to be ready.
Definition: parameter_client.hpp:275
rclcpp::AsyncParametersClient::load_parameters
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > load_parameters(const std::string &yaml_filename)
Load parameters from yaml file.
rclcpp::SyncParametersClient::list_parameters
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &parameter_prefixes, uint64_t depth, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:528
rclcpp::PARAMETER_NOT_SET
@ PARAMETER_NOT_SET
Definition: parameter_value.hpp:34
create_subscription.hpp
rclcpp::AsyncParametersClient
Definition: parameter_client.hpp:49
std::runtime_error
rclcpp::SyncParametersClient::get_parameter_impl
T get_parameter_impl(const std::string &parameter_name, std::function< T()> parameter_not_found_handler)
Definition: parameter_client.hpp:402
rclcpp::SyncParametersClient::SyncParametersClient
SyncParametersClient(rclcpp::Executor::SharedPtr executor, std::shared_ptr< NodeT > node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
Definition: parameter_client.hpp:320
rclcpp::node_interfaces::get_node_topics_interface
std::shared_ptr< rclcpp::node_interfaces::NodeTopicsInterface > get_node_topics_interface(NodeType &&node)
Get the NodeTopicsInterface as a shared pointer from a pointer to a "Node like" object.
Definition: get_node_topics_interface.hpp:72
rclcpp::SyncParametersClient::load_parameters
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.
Definition: parameter_client.hpp:516
rclcpp::AsyncParametersClient::service_is_ready
bool service_is_ready() const
Return if the parameter services are ready.
rclcpp::AsyncParametersClient::set_parameters
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > set_parameters(const std::vector< rclcpp::Parameter > &parameters, std::function< void(std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult >>) > callback=nullptr)
parameter.hpp
rclcpp::AsyncParametersClient::AsyncParametersClient
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.
rclcpp::Client
Definition: client.hpp:178
rclcpp::SyncParametersClient::get_parameter
T get_parameter(const std::string &parameter_name, const T &default_value)
Definition: parameter_client.hpp:417
rclcpp::SyncParametersClient::describe_parameters
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &parameter_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:440
type_support_decl.hpp
visibility_control.hpp
std
rclcpp::AsyncParametersClient::describe_parameters
std::shared_future< std::vector< rcl_interfaces::msg::ParameterDescriptor > > describe_parameters(const std::vector< std::string > &names, std::function< void(std::shared_future< std::vector< rcl_interfaces::msg::ParameterDescriptor >>) > callback=nullptr)
rclcpp::AsyncParametersClient::list_parameters
std::shared_future< rcl_interfaces::msg::ListParametersResult > list_parameters(const std::vector< std::string > &prefixes, uint64_t depth, std::function< void(std::shared_future< rcl_interfaces::msg::ListParametersResult >) > callback=nullptr)
rclcpp::AsyncParametersClient::on_parameter_event
rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(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 >()))
Definition: parameter_client.hpp:209
rclcpp::SyncParametersClient::set_parameters_atomically
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:476
rmw_qos_profile_t
rclcpp::SyncParametersClient
Definition: parameter_client.hpp:302
std::allocator
rclcpp::SyncParametersClient::get_parameter
T get_parameter(const std::string &parameter_name)
Definition: parameter_client.hpp:426
std::unordered_map
rclcpp::SyncParametersClient::SyncParametersClient
SyncParametersClient(std::shared_ptr< NodeT > node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
Definition: parameter_client.hpp:308
rclcpp::AsyncParametersClient::wait_for_service_nanoseconds
bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
rclcpp::AsyncParametersClient::AsyncParametersClient
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.
Definition: parameter_client.hpp:82