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/qos.hpp"
43 #include "rclcpp/type_support_decl.hpp"
44 #include "rclcpp/visibility_control.hpp"
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 =
"",
73 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
81 template<
typename NodeT>
83 const std::shared_ptr<NodeT> node,
84 const std::string & remote_node_name =
"",
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(),
103 template<
typename NodeT>
106 const std::string & remote_node_name =
"",
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(),
120 std::shared_future<std::vector<rclcpp::Parameter>>
122 const std::vector<std::string> & names,
124 void(std::shared_future<std::vector<rclcpp::Parameter>>)
125 > callback =
nullptr);
128 std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>
130 const std::vector<std::string> & names,
132 void(std::shared_future<std::vector<rcl_interfaces::msg::ParameterDescriptor>>)
133 > callback =
nullptr);
136 std::shared_future<std::vector<rclcpp::ParameterType>>
138 const std::vector<std::string> & names,
140 void(std::shared_future<std::vector<rclcpp::ParameterType>>)
141 > callback =
nullptr);
144 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
146 const std::vector<rclcpp::Parameter> & parameters,
148 void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)
149 > callback =
nullptr);
152 std::shared_future<rcl_interfaces::msg::SetParametersResult>
153 set_parameters_atomically(
154 const std::vector<rclcpp::Parameter> & parameters,
156 void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)
157 > callback =
nullptr);
167 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
169 const std::vector<std::string> & parameters_names);
179 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
181 const std::string & yaml_filename);
195 std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
199 std::shared_future<rcl_interfaces::msg::ListParametersResult>
201 const std::vector<std::string> & prefixes,
204 void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)
205 > callback =
nullptr);
209 typename AllocatorT = std::allocator<void>>
212 CallbackT && callback,
218 return this->on_parameter_event(
219 this->node_topics_interface_,
233 typename AllocatorT = std::allocator<void>>
237 CallbackT && callback,
243 return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
247 std::forward<CallbackT>(callback),
271 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
274 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
276 return wait_for_service_nanoseconds(
277 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
284 wait_for_service_nanoseconds(std::chrono::nanoseconds timeout);
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_;
305 template<
typename NodeT>
307 std::shared_ptr<NodeT> node,
308 const std::string & remote_node_name =
"",
311 std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
317 template<
typename NodeT>
319 rclcpp::Executor::SharedPtr executor,
320 std::shared_ptr<NodeT> node,
321 const std::string & remote_node_name =
"",
325 node->get_node_base_interface(),
326 node->get_node_topics_interface(),
327 node->get_node_graph_interface(),
328 node->get_node_services_interface(),
333 template<
typename NodeT>
336 const std::string & remote_node_name =
"",
339 std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
345 template<
typename NodeT>
347 rclcpp::Executor::SharedPtr executor,
349 const std::string & remote_node_name =
"",
353 node->get_node_base_interface(),
354 node->get_node_topics_interface(),
355 node->get_node_graph_interface(),
356 node->get_node_services_interface(),
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 =
"",
370 : executor_(executor), node_base_interface_(node_base_interface)
372 async_parameters_client_ =
373 std::make_shared<AsyncParametersClient>(
375 node_topics_interface,
376 node_graph_interface,
377 node_services_interface,
382 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
383 std::vector<rclcpp::Parameter>
385 const std::vector<std::string> & parameter_names,
386 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
388 return get_parameters(
390 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
396 has_parameter(
const std::string & parameter_name);
401 const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
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();
409 return static_cast<T
>(vars[0].get_value<T>());
415 get_parameter(
const std::string & parameter_name,
const T & default_value)
417 return get_parameter_impl(
419 std::function<T()>([&default_value]() -> T {
return default_value;}));
424 get_parameter(
const std::string & parameter_name)
426 return get_parameter_impl(
429 [¶meter_name]() -> T
431 throw std::runtime_error(
"Parameter '" + parameter_name +
"' is not set");
436 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
437 std::vector<rcl_interfaces::msg::ParameterDescriptor>
439 const std::vector<std::string> & parameter_names,
440 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
442 return describe_parameters(
444 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
448 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
449 std::vector<rclcpp::ParameterType>
451 const std::vector<std::string> & parameter_names,
452 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
454 return get_parameter_types(
456 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
460 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
461 std::vector<rcl_interfaces::msg::SetParametersResult>
463 const std::vector<rclcpp::Parameter> & parameters,
464 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
466 return set_parameters(
468 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
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))
478 return set_parameters_atomically(
480 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
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))
500 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
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))
520 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
524 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
525 rcl_interfaces::msg::ListParametersResult
527 const std::vector<std::string> & parameter_prefixes,
529 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
531 return list_parameters(
534 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
538 template<
typename CallbackT>
540 on_parameter_event(CallbackT && callback)
542 return async_parameters_client_->on_parameter_event(
543 std::forward<CallbackT>(callback));
557 CallbackT && callback)
559 return AsyncParametersClient::on_parameter_event(
561 std::forward<CallbackT>(callback));
566 service_is_ready()
const
568 return async_parameters_client_->service_is_ready();
571 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
574 std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
576 return async_parameters_client_->wait_for_service(timeout);
581 std::vector<rclcpp::Parameter>
583 const std::vector<std::string> & parameter_names,
584 std::chrono::nanoseconds timeout);
587 std::vector<rcl_interfaces::msg::ParameterDescriptor>
589 const std::vector<std::string> & parameter_names,
590 std::chrono::nanoseconds timeout);
593 std::vector<rclcpp::ParameterType>
595 const std::vector<std::string> & parameter_names,
596 std::chrono::nanoseconds timeout);
599 std::vector<rcl_interfaces::msg::SetParametersResult>
601 const std::vector<rclcpp::Parameter> & parameters,
602 std::chrono::nanoseconds timeout);
605 std::vector<rcl_interfaces::msg::SetParametersResult>
607 const std::vector<std::string> & parameters_names,
608 std::chrono::nanoseconds timeout);
611 std::vector<rcl_interfaces::msg::SetParametersResult>
613 const std::string & yaml_filename,
614 std::chrono::nanoseconds timeout);
617 rcl_interfaces::msg::SetParametersResult
618 set_parameters_atomically(
619 const std::vector<rclcpp::Parameter> & parameters,
620 std::chrono::nanoseconds timeout);
623 rcl_interfaces::msg::ListParametersResult
625 const std::vector<std::string> & parameter_prefixes,
627 std::chrono::nanoseconds timeout);
630 rclcpp::Executor::SharedPtr executor_;
631 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
632 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.
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 > ¶meters_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.
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.
Structure containing optional configuration for Subscriptions.