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  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
58 
61  const rclcpp::Node::SharedPtr node,
62  const std::string & remote_node_name = "",
63  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
64  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
65 
68  rclcpp::Node * node,
69  const std::string & remote_node_name = "",
70  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
71  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
72 
76  const std::vector<std::string> & names,
79  > callback = nullptr);
80 
84  const std::vector<std::string> & names,
87  > callback = nullptr);
88 
92  const std::vector<rclcpp::Parameter> & parameters,
95  > callback = nullptr);
96 
100  const std::vector<rclcpp::Parameter> & parameters,
103  > callback = nullptr);
104 
108  const std::vector<std::string> & prefixes,
109  uint64_t depth,
112  > callback = nullptr);
113 
114  template<
115  typename CallbackT,
116  typename AllocatorT = std::allocator<void>>
119  CallbackT && callback,
120  const rclcpp::QoS & qos = (
121  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))
122  ),
125  ))
126  {
127  return this->on_parameter_event(
128  this->node_topics_interface_,
129  callback,
130  qos,
131  options);
132  }
133 
139  template<
140  typename CallbackT,
141  typename NodeT,
142  typename AllocatorT = std::allocator<void>>
145  NodeT && node,
146  CallbackT && callback,
147  const rclcpp::QoS & qos = (
148  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))
149  ),
152  ))
153  {
154  return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
155  node,
156  "parameter_events",
157  qos,
158  std::forward<CallbackT>(callback),
159  options);
160  }
161 
163  bool
164  service_is_ready() const;
165 
166  template<typename RepT = int64_t, typename RatioT = std::milli>
167  bool
170  {
172  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
173  );
174  }
175 
176 protected:
178  bool
180 
181 private:
182  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
185  get_parameter_types_client_;
188  set_parameters_atomically_client_;
191  describe_parameters_client_;
192  std::string remote_node_name_;
193 };
194 
196 {
197 public:
199 
201  explicit SyncParametersClient(
203  const std::string & remote_node_name = "",
204  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
205 
207  SyncParametersClient(
208  rclcpp::executor::Executor::SharedPtr executor,
210  const std::string & remote_node_name = "",
211  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
212 
214  explicit SyncParametersClient(
215  rclcpp::Node * node,
216  const std::string & remote_node_name = "",
217  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
218 
220  SyncParametersClient(
221  rclcpp::executor::Executor::SharedPtr executor,
222  rclcpp::Node * node,
223  const std::string & remote_node_name = "",
224  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
225 
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,
233  const std::string & remote_node_name = "",
234  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
235 
238  get_parameters(const std::vector<std::string> & parameter_names);
239 
241  bool
242  has_parameter(const std::string & parameter_name);
243 
244  template<typename T>
245  T
247  const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
248  {
250  names.push_back(parameter_name);
251  auto vars = get_parameters(names);
252  if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) {
253  return parameter_not_found_handler();
254  } else {
255  return static_cast<T>(vars[0].get_value<T>());
256  }
257  }
258 
259  template<typename T>
260  T
261  get_parameter(const std::string & parameter_name, const T & default_value)
262  {
263  return get_parameter_impl(
264  parameter_name,
265  std::function<T()>([&default_value]() -> T {return default_value;}));
266  }
267 
268  template<typename T>
269  T
270  get_parameter(const std::string & parameter_name)
271  {
272  return get_parameter_impl(
273  parameter_name,
274  std::function<T()>([&parameter_name]() -> T
275  {
276  throw std::runtime_error("Parameter '" + parameter_name + "' is not set");
277  })
278  );
279  }
280 
283  get_parameter_types(const std::vector<std::string> & parameter_names);
284 
288 
290  rcl_interfaces::msg::SetParametersResult
292 
294  rcl_interfaces::msg::ListParametersResult
296  const std::vector<std::string> & parameter_prefixes,
297  uint64_t depth);
298 
299  template<typename CallbackT>
301  on_parameter_event(CallbackT && callback)
302  {
303  return async_parameters_client_->on_parameter_event(
304  std::forward<CallbackT>(callback));
305  }
306 
312  template<
313  typename CallbackT,
314  typename NodeT>
317  NodeT && node,
318  CallbackT && callback)
319  {
321  node,
322  std::forward<CallbackT>(callback));
323  }
324 
326  bool
328  {
329  return async_parameters_client_->service_is_ready();
330  }
331 
332  template<typename RepT = int64_t, typename RatioT = std::milli>
333  bool
336  {
337  return async_parameters_client_->wait_for_service(timeout);
338  }
339 
340 private:
341  rclcpp::executor::Executor::SharedPtr executor_;
342  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
343  AsyncParametersClient::SharedPtr async_parameters_client_;
344 };
345 
346 } // namespace rclcpp
347 
348 #endif // RCLCPP__PARAMETER_CLIENT_HPP_
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 > &parameters, 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
T push_back(T... args)
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
T get_parameter(const std::string &parameter_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 > &parameters, 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 &parameter_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 &parameter_name, std::function< T()> parameter_not_found_handler)
Definition: parameter_client.hpp:246