rclcpp  master
C++ ROS Client Library API
parameter_client.hpp
Go to the documentation of this file.
1 // Copyright 2015 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__PARAMETER_CLIENT_HPP_
16 #define RCLCPP__PARAMETER_CLIENT_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <utility>
21 #include <vector>
22 
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"
32 #include "rclcpp/executors.hpp"
34 #include "rclcpp/macros.hpp"
35 #include "rclcpp/node.hpp"
36 #include "rclcpp/parameter.hpp"
39 #include "rmw/rmw.h"
40 
41 namespace rclcpp
42 {
43 
45 {
46 public:
48 
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,
55  const std::string & remote_node_name = "",
56  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
57 
60  const rclcpp::Node::SharedPtr node,
61  const std::string & remote_node_name = "",
62  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
63 
66  rclcpp::Node * node,
67  const std::string & remote_node_name = "",
68  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
69 
73  const std::vector<std::string> & names,
76  > callback = nullptr);
77 
81  const std::vector<std::string> & names,
84  > callback = nullptr);
85 
92  > callback = nullptr);
93 
100  > callback = nullptr);
101 
105  const std::vector<std::string> & prefixes,
106  uint64_t depth,
109  > callback = nullptr);
110 
111  template<
112  typename CallbackT,
113  typename Alloc = std::allocator<void>,
114  typename SubscriptionT =
117  on_parameter_event(CallbackT && callback)
118  {
120  auto msg_mem_strat =
121  MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent, Alloc>::create_default();
122 
124  rcl_interfaces::msg::ParameterEvent, CallbackT, Alloc, SubscriptionT>(
125  this->node_topics_interface_.get(),
126  "parameter_events",
127  std::forward<CallbackT>(callback),
128  rmw_qos_profile_default,
129  nullptr, // group,
130  false, // ignore_local_publications,
131  false, // use_intra_process_comms_,
132  msg_mem_strat,
133  std::make_shared<Alloc>());
134  }
135 
137  bool
138  service_is_ready() const;
139 
140  template<typename RatioT = std::milli>
141  bool
144  {
146  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
147  );
148  }
149 
150 protected:
152  bool
154 
155 private:
156  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
159  get_parameter_types_client_;
162  set_parameters_atomically_client_;
165  describe_parameters_client_;
166  std::string remote_node_name_;
167 };
168 
170 {
171 public:
173 
175  explicit SyncParametersClient(
176  rclcpp::Node::SharedPtr node,
177  const std::string & remote_node_name = "",
178  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
179 
182  rclcpp::executor::Executor::SharedPtr executor,
183  rclcpp::Node::SharedPtr node,
184  const std::string & remote_node_name = "",
185  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
186 
189  get_parameters(const std::vector<std::string> & parameter_names);
190 
192  bool
193  has_parameter(const std::string & parameter_name);
194 
195  template<typename T>
196  T
198  const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
199  {
201  names.push_back(parameter_name);
202  auto vars = get_parameters(names);
203  if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::parameter::PARAMETER_NOT_SET)) {
204  return parameter_not_found_handler();
205  } else {
206  return static_cast<T>(vars[0].get_value<T>());
207  }
208  }
209 
210  template<typename T>
211  T
212  get_parameter(const std::string & parameter_name, const T & default_value)
213  {
214  return get_parameter_impl(
215  parameter_name,
216  std::function<T()>([&default_value]() -> T {return default_value;}));
217  }
218 
219  template<typename T>
220  T
221  get_parameter(const std::string & parameter_name)
222  {
223  return get_parameter_impl(
224  parameter_name,
225  std::function<T()>([]() -> T {throw std::runtime_error("Parameter not set");}));
226  }
227 
230  get_parameter_types(const std::vector<std::string> & parameter_names);
231 
235 
237  rcl_interfaces::msg::SetParametersResult
239 
241  rcl_interfaces::msg::ListParametersResult
243  const std::vector<std::string> & parameter_prefixes,
244  uint64_t depth);
245 
246  template<typename CallbackT>
248  on_parameter_event(CallbackT && callback)
249  {
250  return async_parameters_client_->on_parameter_event(std::forward<CallbackT>(callback));
251  }
252 
254  bool
256  {
257  return async_parameters_client_->service_is_ready();
258  }
259 
260  template<typename RatioT = std::milli>
261  bool
264  {
265  return async_parameters_client_->wait_for_service(timeout);
266  }
267 
268 private:
269  rclcpp::executor::Executor::SharedPtr executor_;
270  rclcpp::Node::SharedPtr node_;
271  AsyncParametersClient::SharedPtr async_parameters_client_;
272 };
273 
274 } // namespace rclcpp
275 
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 > &parameter_prefixes, uint64_t depth)
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 &parameter_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 > &parameters)
Definition: allocator_common.hpp:24
Definition: parameter_client.hpp:169
std::vector< rclcpp::parameter::ParameterType > get_parameter_types(const std::vector< std::string > &parameter_names)
bool has_parameter(const std::string &parameter_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 > &parameters, 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)
T push_back(T... args)
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::parameter::ParameterVariant > &parameters)
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
T get_parameter(const std::string &parameter_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 > &parameters, 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 &parameter_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 > &parameter_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