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" 51 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
52 const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
53 const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
54 const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
57 rclcpp::callback_group::CallbackGroup::SharedPtr group =
nullptr);
64 rclcpp::callback_group::CallbackGroup::SharedPtr group =
nullptr);
71 rclcpp::callback_group::CallbackGroup::SharedPtr group =
nullptr);
79 > callback =
nullptr);
87 > callback =
nullptr);
95 > callback =
nullptr);
103 > callback =
nullptr);
112 > callback =
nullptr);
119 CallbackT && callback,
128 this->node_topics_interface_,
146 CallbackT && callback,
154 return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
158 std::forward<CallbackT>(callback),
166 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
172 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
182 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
185 get_parameter_types_client_;
188 set_parameters_atomically_client_;
191 describe_parameters_client_;
207 SyncParametersClient(
208 rclcpp::executor::Executor::SharedPtr executor,
214 explicit SyncParametersClient(
220 SyncParametersClient(
221 rclcpp::executor::Executor::SharedPtr executor,
227 SyncParametersClient(
228 rclcpp::executor::Executor::SharedPtr executor,
229 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
230 const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
231 const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
232 const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
253 return parameter_not_found_handler();
255 return static_cast<T
>(vars[0].get_value<T>());
263 return get_parameter_impl(
265 std::function<T()>([&default_value]() -> T {
return default_value;}));
272 return get_parameter_impl(
290 rcl_interfaces::msg::SetParametersResult
294 rcl_interfaces::msg::ListParametersResult
299 template<
typename CallbackT>
303 return async_parameters_client_->on_parameter_event(
304 std::forward<CallbackT>(callback));
318 CallbackT && callback)
322 std::forward<CallbackT>(callback));
329 return async_parameters_client_->service_is_ready();
332 template<
typename RepT =
int64_t,
typename RatioT = std::milli>
337 return async_parameters_client_->wait_for_service(timeout);
341 rclcpp::executor::Executor::SharedPtr executor_;
342 const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
348 #endif // RCLCPP__PARAMETER_CLIENT_HPP_ bool service_is_ready() const
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)
Definition: parameter_value.hpp:34
rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:301
Encapsulation of Quality of Service settings.
Definition: qos.hpp:55
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:334
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)
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
Definition: parameter_client.hpp:44
bool service_is_ready() const
Definition: parameter_client.hpp:327
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...
Definition: client.hpp:119
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:67
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
T get_parameter(const std::string ¶meter_name)
Definition: parameter_client.hpp:270
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:168
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:118
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::callback_group::CallbackGroup::SharedPtr group=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)
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_nanoseconds(std::chrono::nanoseconds timeout)
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(NodeT &&node, CallbackT &&callback)
Definition: parameter_client.hpp:316
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Set the data type used in the intra-process buffer as std::shared_ptr<MessageT>
Definition: parameter_client.hpp:195
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:144
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)
T get_parameter(const std::string ¶meter_name, const T &default_value)
Definition: parameter_client.hpp:261
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:72
T get_parameter_impl(const std::string ¶meter_name, std::function< T()> parameter_not_found_handler)
Definition: parameter_client.hpp:246