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,
    60     const rclcpp::Node::SharedPtr node,
    76     > callback = 
nullptr);
    84     > callback = 
nullptr);
    92     > callback = 
nullptr);
   100     > callback = 
nullptr);
   109     > callback = 
nullptr);
   114     typename SubscriptionT =
   121       MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent, Alloc>::create_default();
   124       rcl_interfaces::msg::ParameterEvent, CallbackT, Alloc, SubscriptionT>(
   125       this->node_topics_interface_.get(),
   127       std::forward<CallbackT>(callback),
   128       rmw_qos_profile_default,
   133       std::make_shared<Alloc>());
   140   template<
typename RatioT = std::milli>
   146       std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
   156   const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
   159     get_parameter_types_client_;
   162     set_parameters_atomically_client_;
   165     describe_parameters_client_;
   176     rclcpp::Node::SharedPtr node,
   182     rclcpp::executor::Executor::SharedPtr executor,
   183     rclcpp::Node::SharedPtr node,
   204       return parameter_not_found_handler();
   206       return static_cast<T
>(vars[0].get_value<T>());
   216       std::function<T()>([&default_value]() -> T {
return default_value;}));
   237   rcl_interfaces::msg::SetParametersResult
   241   rcl_interfaces::msg::ListParametersResult
   246   template<
typename CallbackT>
   250     return async_parameters_client_->on_parameter_event(std::forward<CallbackT>(callback));
   257     return async_parameters_client_->service_is_ready();
   260   template<
typename RatioT = std::milli>
   265     return async_parameters_client_->wait_for_service(timeout);
   269   rclcpp::executor::Executor::SharedPtr executor_;
   270   rclcpp::Node::SharedPtr node_;
   271   AsyncParametersClient::SharedPtr async_parameters_client_;
   276 #endif  // RCLCPP__PARAMETER_CLIENT_HPP_ 
Subscription implementation, templated on the type of message this subscription receives. 
Definition: subscription.hpp:123
 
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > ¶meter_prefixes, uint64_t depth)
 
bool service_is_ready() const
 
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)
 
bool wait_for_service(std::chrono::duration< int64_t, RatioT > timeout=std::chrono::duration< int64_t, RatioT >(-1))
Definition: parameter_client.hpp:262
 
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)
 
T get_parameter_impl(const std::string ¶meter_name, std::function< T()> parameter_not_found_handler)
Definition: parameter_client.hpp:197
 
rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:117
 
Definition: client.hpp:118
 
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::parameter::ParameterVariant > ¶meters)
 
Definition: allocator_common.hpp:24
 
Definition: parameter_client.hpp:169
 
std::vector< rclcpp::parameter::ParameterType > get_parameter_types(const std::vector< std::string > ¶meter_names)
 
bool has_parameter(const std::string ¶meter_name)
 
SyncParametersClient(rclcpp::Node::SharedPtr node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
 
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)
 
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)
 
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::parameter::ParameterVariant > ¶meters)
 
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
 
T get_parameter(const std::string ¶meter_name, const T &default_value)
Definition: parameter_client.hpp:212
 
bool service_is_ready() const
Definition: parameter_client.hpp:255
 
Default allocation strategy for messages received by subscriptions. 
Definition: message_memory_strategy.hpp:33
 
Node is the single point of entry for creating publishers and subscribers. 
Definition: node.hpp:64
 
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)
 
bool wait_for_service(std::chrono::duration< int64_t, RatioT > timeout=std::chrono::duration< int64_t, RatioT >(-1))
Definition: parameter_client.hpp:142
 
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)
 
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
 
Definition: parameter_client.hpp:44
 
rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:248
 
T get_parameter(const std::string ¶meter_name)
Definition: parameter_client.hpp:221
 
bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
 
Definition: parameter.hpp:36
 
std::vector< rclcpp::parameter::ParameterVariant > get_parameters(const std::vector< std::string > ¶meter_names)
 
rclcpp::Subscription< MessageT, AllocatorT >::SharedPtr create_subscription(rclcpp::node_interfaces::NodeTopicsInterface *node_topics, const std::string &topic_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, rclcpp::callback_group::CallbackGroup::SharedPtr group, bool ignore_local_publications, bool use_intra_process_comms, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, AllocatorT >::SharedPtr msg_mem_strat, typename std::shared_ptr< AllocatorT > allocator)
Definition: create_subscription.hpp:31