rclcpp
master
C++ ROS Client Library API
|
Go to the documentation of this file.
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"
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,
72 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
81 template<
typename NodeT>
86 rclcpp::CallbackGroup::SharedPtr group =
nullptr)
104 template<
typename NodeT>
109 rclcpp::CallbackGroup::SharedPtr group =
nullptr)
126 > callback =
nullptr);
134 > callback =
nullptr);
142 > callback =
nullptr);
150 > callback =
nullptr);
158 > callback =
nullptr);
203 > callback =
nullptr);
210 CallbackT && callback,
219 this->node_topics_interface_,
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>
279 std::chrono::duration_cast<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_;
307 template<
typename NodeT>
313 std::make_shared<
rclcpp::executors::SingleThreadedExecutor>(),
319 template<
typename NodeT>
321 rclcpp::Executor::SharedPtr executor,
335 template<
typename NodeT>
341 std::make_shared<
rclcpp::executors::SingleThreadedExecutor>(),
347 template<
typename NodeT>
349 rclcpp::Executor::SharedPtr executor,
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,
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>
392 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
409 return parameter_not_found_handler();
411 return static_cast<T
>(vars[0].get_value<T>());
421 std::function<T()>([&default_value]() -> T {
return default_value;}));
431 [¶meter_name]() -> T
438 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
446 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
450 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
458 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
462 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
470 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
474 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
475 rcl_interfaces::msg::SetParametersResult
482 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
494 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
502 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
514 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
522 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
526 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
527 rcl_interfaces::msg::ListParametersResult
536 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
540 template<
typename CallbackT>
544 return async_parameters_client_->on_parameter_event(
545 std::forward<CallbackT>(callback));
559 CallbackT && callback)
563 std::forward<CallbackT>(callback));
570 return async_parameters_client_->service_is_ready();
573 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
578 return async_parameters_client_->wait_for_service(timeout);
619 rcl_interfaces::msg::SetParametersResult
625 rcl_interfaces::msg::ListParametersResult
632 rclcpp::Executor::SharedPtr executor_;
633 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
634 AsyncParametersClient::SharedPtr async_parameters_client_;
639 #endif // RCLCPP__PARAMETER_CLIENT_HPP_
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
bool service_is_ready() const
Definition: parameter_client.hpp:568
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > ¶meter_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:386
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
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
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > ¶meters, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:464
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< 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.
Definition: parameter_client.hpp:496
std::vector< rclcpp::ParameterType > get_parameter_types(const std::vector< std::string > ¶meter_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:452
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:87
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(NodeT &&node, CallbackT &&callback)
Definition: parameter_client.hpp:557
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
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > delete_parameters(const std::vector< std::string > ¶meters_names)
Delete several parameters at once.
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
bool has_parameter(const std::string ¶meter_name)
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
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:575
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
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
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::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:542
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
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)
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)
std::shared_future< rcl_interfaces::msg::SetParametersResult > set_parameters_atomically(const std::vector< rclcpp::Parameter > ¶meters, std::function< void(std::shared_future< rcl_interfaces::msg::SetParametersResult >) > callback=nullptr)
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
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > load_parameters(const std::string &yaml_filename)
Load parameters from yaml file.
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > ¶meter_prefixes, uint64_t depth, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:528
@ PARAMETER_NOT_SET
Definition: parameter_value.hpp:34
Definition: parameter_client.hpp:49
T get_parameter_impl(const std::string ¶meter_name, std::function< T()> parameter_not_found_handler)
Definition: parameter_client.hpp:402
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
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
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
bool service_is_ready() const
Return if the parameter services are ready.
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > set_parameters(const std::vector< rclcpp::Parameter > ¶meters, std::function< void(std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult >>) > callback=nullptr)
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.
Definition: client.hpp:178
T get_parameter(const std::string ¶meter_name, const T &default_value)
Definition: parameter_client.hpp:417
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > ¶meter_names, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:440
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)
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::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
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > ¶meters, std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:476
Definition: parameter_client.hpp:302
T get_parameter(const std::string ¶meter_name)
Definition: parameter_client.hpp:426
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
bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
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