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_
23 #include "rcl_interfaces/msg/parameter.hpp"
24 #include "rcl_interfaces/msg/parameter_event.hpp"
25 #include "rcl_interfaces/msg/parameter_value.hpp"
26 #include "rcl_interfaces/srv/describe_parameters.hpp"
27 #include "rcl_interfaces/srv/get_parameter_types.hpp"
28 #include "rcl_interfaces/srv/get_parameters.hpp"
29 #include "rcl_interfaces/srv/list_parameters.hpp"
30 #include "rcl_interfaces/srv/set_parameters.hpp"
31 #include "rcl_interfaces/srv/set_parameters_atomically.hpp"
61 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
62 const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
63 const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
64 const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
67 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
78 const rclcpp::Node::SharedPtr node,
81 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
95 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
103 > callback =
nullptr);
111 > callback =
nullptr);
119 > callback =
nullptr);
127 > callback =
nullptr);
136 > callback =
nullptr);
143 CallbackT && callback,
152 this->node_topics_interface_,
170 CallbackT && callback,
178 return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
182 std::forward<CallbackT>(callback),
206 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
212 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
222 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
225 get_parameter_types_client_;
228 set_parameters_atomically_client_;
231 describe_parameters_client_;
242 rclcpp::Node::SharedPtr node,
248 rclcpp::Executor::SharedPtr executor,
249 rclcpp::Node::SharedPtr node,
261 rclcpp::Executor::SharedPtr executor,
268 rclcpp::Executor::SharedPtr executor,
269 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
270 const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
271 const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
272 const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
293 return parameter_not_found_handler();
295 return static_cast<T
>(vars[0].get_value<T>());
305 std::function<T()>([&default_value]() -> T {
return default_value;}));
315 [¶meter_name]() -> T
331 rcl_interfaces::msg::SetParametersResult
335 rcl_interfaces::msg::ListParametersResult
340 template<
typename CallbackT>
344 return async_parameters_client_->on_parameter_event(
345 std::forward<CallbackT>(callback));
359 CallbackT && callback)
363 std::forward<CallbackT>(callback));
370 return async_parameters_client_->service_is_ready();
373 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
378 return async_parameters_client_->wait_for_service(timeout);
382 rclcpp::Executor::SharedPtr executor_;
383 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
384 AsyncParametersClient::SharedPtr async_parameters_client_;
389 #endif // RCLCPP__PARAMETER_CLIENT_HPP_
bool service_is_ready() const
Definition: parameter_client.hpp:368
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > ¶meter_names)
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:168
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:79
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(NodeT &&node, CallbackT &&callback)
Definition: parameter_client.hpp:357
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > ¶meter_prefixes, uint64_t depth)
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)
Encapsulation of Quality of Service settings.
Definition: qos.hpp:59
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:375
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
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:342
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:74
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:208
@ PARAMETER_NOT_SET
Definition: parameter_value.hpp:34
SyncParametersClient(rclcpp::Node::SharedPtr node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
std::vector< rclcpp::ParameterType > get_parameter_types(const std::vector< std::string > ¶meter_names)
Definition: parameter_client.hpp:44
T get_parameter_impl(const std::string ¶meter_name, std::function< T()> parameter_not_found_handler)
Definition: parameter_client.hpp:286
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)
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > ¶meters)
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:301
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:142
Definition: parameter_client.hpp:235
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > ¶meters)
T get_parameter(const std::string ¶meter_name)
Definition: parameter_client.hpp:310
bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)