15 #ifndef RCLCPP__PARAMETER_CLIENT_HPP_ 16 #define RCLCPP__PARAMETER_CLIENT_HPP_ 22 #include "rcl_interfaces/msg/parameter.hpp" 23 #include "rcl_interfaces/msg/parameter_event.hpp" 24 #include "rcl_interfaces/msg/parameter_value.hpp" 25 #include "rcl_interfaces/srv/describe_parameters.hpp" 26 #include "rcl_interfaces/srv/get_parameter_types.hpp" 27 #include "rcl_interfaces/srv/get_parameters.hpp" 28 #include "rcl_interfaces/srv/list_parameters.hpp" 29 #include "rcl_interfaces/srv/set_parameters.hpp" 30 #include "rcl_interfaces/srv/set_parameters_atomically.hpp" 41 namespace parameter_client
51 const rclcpp::node::Node::SharedPtr node,
61 > callback =
nullptr);
69 > callback =
nullptr);
77 > callback =
nullptr);
85 > callback =
nullptr);
94 > callback =
nullptr);
96 template<
typename CallbackT>
100 return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>(
101 "parameter_events", std::forward<CallbackT>(callback), rmw_qos_profile_parameter_events);
105 const rclcpp::node::Node::SharedPtr node_;
108 get_parameter_types_client_;
111 set_parameters_atomically_client_;
114 describe_parameters_client_;
125 rclcpp::node::Node::SharedPtr node,
129 SyncParametersClient(
130 rclcpp::executor::Executor::SharedPtr executor,
131 rclcpp::node::Node::SharedPtr node,
151 return parameter_not_found_handler();
153 return static_cast<T
>(vars[0].get_value<T>());
162 return get_parameter_impl(parameter_name,
163 std::function<T()>([&default_value]() -> T {
return default_value; }));
172 return get_parameter_impl(parameter_name,
186 rcl_interfaces::msg::SetParametersResult
190 rcl_interfaces::msg::ListParametersResult
195 template<
typename CallbackT>
199 return async_parameters_client_->on_parameter_event(std::forward<CallbackT>(callback));
203 rclcpp::executor::Executor::SharedPtr executor_;
204 rclcpp::node::Node::SharedPtr node_;
205 AsyncParametersClient::SharedPtr async_parameters_client_;
211 #endif // RCLCPP__PARAMETER_CLIENT_HPP_ rclcpp::subscription::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:197
Definition: client.hpp:111
Definition: allocator_common.hpp:24
Definition: parameter_client.hpp:118
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:122
T get_parameter(const std::string ¶meter_name)
Definition: parameter_client.hpp:169
std::shared_future< std::vector< rclcpp::parameter::ParameterVariant > > get_parameters(const std::vector< std::string > &names, std::function< void(std::shared_future< std::vector< rclcpp::parameter::ParameterVariant >>) > callback=nullptr)
std::shared_future< rcl_interfaces::msg::SetParametersResult > set_parameters_atomically(const std::vector< rclcpp::parameter::ParameterVariant > ¶meters, std::function< void(std::shared_future< rcl_interfaces::msg::SetParametersResult >) > callback=nullptr)
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
std::shared_future< std::vector< rclcpp::parameter::ParameterType > > get_parameter_types(const std::vector< std::string > &names, std::function< void(std::shared_future< std::vector< rclcpp::parameter::ParameterType >>) > callback=nullptr)
std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult > > set_parameters(const std::vector< rclcpp::parameter::ParameterVariant > ¶meters, std::function< void(std::shared_future< std::vector< rcl_interfaces::msg::SetParametersResult >>) > callback=nullptr)
rclcpp::subscription::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:98
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)
T get_parameter(const std::string ¶meter_name, const T &default_value)
Definition: parameter_client.hpp:159
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
AsyncParametersClient(const rclcpp::node::Node::SharedPtr node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
T get_parameter_impl(const std::string ¶meter_name, std::function< T()> parameter_not_found_handler)
Definition: parameter_client.hpp:144
Definition: parameter.hpp:36
Definition: parameter_client.hpp:44