15 #ifndef RCLCPP__PARAMETER_CLIENT_HPP_
16 #define RCLCPP__PARAMETER_CLIENT_HPP_
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"
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);
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(),
104 template<
typename NodeT>
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(),
121 std::shared_future<std::vector<rclcpp::Parameter>>
123 const std::vector<std::string> & names,
125 void(std::shared_future<std::vector<rclcpp::Parameter>>)
126 > callback =
nullptr);
129 std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>
131 const std::vector<std::string> & names,
133 void(std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>)
134 > callback =
nullptr);
137 std::shared_future<std::vector<rclcpp::ParameterType>>
139 const std::vector<std::string> & names,
141 void(std::shared_future<std::vector<rclcpp::ParameterType>>)
142 > callback =
nullptr);
145 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
147 const std::vector<rclcpp::Parameter> & parameters,
149 void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)
150 > callback =
nullptr);
153 std::shared_future<rcl_interfaces::msg::SetParametersResult>
154 set_parameters_atomically(
155 const std::vector<rclcpp::Parameter> & parameters,
157 void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)
158 > callback =
nullptr);
168 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
170 const std::vector<std::string> & parameters_names);
180 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
182 const std::string & yaml_filename);
193 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
197 std::shared_future<rcl_interfaces::msg::ListParametersResult>
199 const std::vector<std::string> & prefixes,
202 void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)
203 > callback =
nullptr);
207 typename AllocatorT = std::allocator<void>>
210 CallbackT && callback,
218 return this->on_parameter_event(
219 this->node_topics_interface_,
233 typename AllocatorT = std::allocator<void>>
237 CallbackT && callback,
245 return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
249 std::forward<CallbackT>(callback),
273 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
276 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
278 return wait_for_service_nanoseconds(
279 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
286 wait_for_service_nanoseconds(std::chrono::nanoseconds timeout);
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_;
307 template<
typename NodeT>
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>(),
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)
327 node->get_node_base_interface(),
328 node->get_node_topics_interface(),
329 node->get_node_graph_interface(),
330 node->get_node_services_interface(),
335 template<
typename NodeT>
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>(),
347 template<
typename NodeT>
349 rclcpp::Executor::SharedPtr executor,
351 const std::string & remote_node_name =
"",
352 const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)
355 node->get_node_base_interface(),
356 node->get_node_topics_interface(),
357 node->get_node_graph_interface(),
358 node->get_node_services_interface(),
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)
374 async_parameters_client_ =
375 std::make_shared<AsyncParametersClient>(
377 node_topics_interface,
378 node_graph_interface,
379 node_services_interface,
384 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
385 std::vector<rclcpp::Parameter>
387 const std::vector<std::string> & parameter_names,
388 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
390 return get_parameters(
392 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
398 has_parameter(
const std::string & parameter_name);
403 const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
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();
411 return static_cast<T
>(vars[0].get_value<T>());
417 get_parameter(
const std::string & parameter_name,
const T & default_value)
419 return get_parameter_impl(
421 std::function<T()>([&default_value]() -> T {
return default_value;}));
426 get_parameter(
const std::string & parameter_name)
428 return get_parameter_impl(
431 [¶meter_name]() -> T
433 throw std::runtime_error(
"Parameter '" + parameter_name +
"' is not set");
438 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
439 std::vector<rcl_interfaces::msg::ParameterDescriptor>
441 const std::vector<std::string> & parameter_names,
442 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
444 return describe_parameters(
446 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
450 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
451 std::vector<rclcpp::ParameterType>
453 const std::vector<std::string> & parameter_names,
454 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
456 return get_parameter_types(
458 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
462 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
463 std::vector<rcl_interfaces::msg::SetParametersResult>
465 const std::vector<rclcpp::Parameter> & parameters,
466 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
468 return set_parameters(
470 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
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))
480 return set_parameters_atomically(
482 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
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))
502 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
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))
522 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
526 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
527 rcl_interfaces::msg::ListParametersResult
529 const std::vector<std::string> & parameter_prefixes,
531 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
533 return list_parameters(
536 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
540 template<
typename CallbackT>
542 on_parameter_event(CallbackT && callback)
544 return async_parameters_client_->on_parameter_event(
545 std::forward<CallbackT>(callback));
559 CallbackT && callback)
561 return AsyncParametersClient::on_parameter_event(
563 std::forward<CallbackT>(callback));
568 service_is_ready()
const
570 return async_parameters_client_->service_is_ready();
573 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
576 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
578 return async_parameters_client_->wait_for_service(timeout);
583 std::vector<rclcpp::Parameter>
585 const std::vector<std::string> & parameter_names,
586 std::chrono::nanoseconds timeout);
589 std::vector<rcl_interfaces::msg::ParameterDescriptor>
591 const std::vector<std::string> & parameter_names,
592 std::chrono::nanoseconds timeout);
595 std::vector<rclcpp::ParameterType>
597 const std::vector<std::string> & parameter_names,
598 std::chrono::nanoseconds timeout);
601 std::vector<rcl_interfaces::msg::SetParametersResult>
603 const std::vector<rclcpp::Parameter> & parameters,
604 std::chrono::nanoseconds timeout);
607 std::vector<rcl_interfaces::msg::SetParametersResult>
609 const std::vector<std::string> & parameters_names,
610 std::chrono::nanoseconds timeout);
613 std::vector<rcl_interfaces::msg::SetParametersResult>
615 const std::string & yaml_filename,
616 std::chrono::nanoseconds timeout);
619 rcl_interfaces::msg::SetParametersResult
620 set_parameters_atomically(
621 const std::vector<rclcpp::Parameter> & parameters,
622 std::chrono::nanoseconds timeout);
625 rcl_interfaces::msg::ListParametersResult
627 const std::vector<std::string> & parameter_prefixes,
629 std::chrono::nanoseconds timeout);
632 rclcpp::Executor::SharedPtr executor_;
633 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
634 AsyncParametersClient::SharedPtr async_parameters_client_;
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 > ¶meters_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.
Subscription implementation, templated on the type of message this subscription receives.
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.
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.
Structure containing optional configuration for Subscriptions.