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 
89  const std::vector<rclcpp::Parameter> & parameters,
92  > callback = nullptr);
93 
97  const std::vector<rclcpp::Parameter> & parameters,
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 AllocatorT = std::allocator<void>>
116  CallbackT && callback,
117  const rclcpp::QoS & qos = (
118  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default))
119  ),
122  ))
123  {
124  return this->on_parameter_event(
125  this->node_topics_interface_,
126  callback,
127  qos,
128  options);
129  }
130 
136  template<
137  typename CallbackT,
138  typename NodeT,
139  typename AllocatorT = std::allocator<void>>
142  NodeT && node,
143  CallbackT && callback,
144  const rclcpp::QoS & qos = (
145  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default))
146  ),
149  ))
150  {
151  return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
152  node,
153  "parameter_events",
154  qos,
155  std::forward<CallbackT>(callback),
156  options);
157  }
158 
160  bool
161  service_is_ready() const;
162 
163  template<typename RepT = int64_t, typename RatioT = std::milli>
164  bool
167  {
169  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
170  );
171  }
172 
173 protected:
175  bool
177 
178 private:
179  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
182  get_parameter_types_client_;
185  set_parameters_atomically_client_;
188  describe_parameters_client_;
189  std::string remote_node_name_;
190 };
191 
193 {
194 public:
196 
198  explicit SyncParametersClient(
199  rclcpp::Node::SharedPtr node,
200  const std::string & remote_node_name = "",
201  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
202 
204  SyncParametersClient(
205  rclcpp::executor::Executor::SharedPtr executor,
206  rclcpp::Node::SharedPtr node,
207  const std::string & remote_node_name = "",
208  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
209 
211  explicit SyncParametersClient(
212  rclcpp::Node * node,
213  const std::string & remote_node_name = "",
214  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
215 
217  SyncParametersClient(
218  rclcpp::executor::Executor::SharedPtr executor,
219  rclcpp::Node * node,
220  const std::string & remote_node_name = "",
221  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
222 
224  SyncParametersClient(
225  rclcpp::executor::Executor::SharedPtr executor,
226  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
227  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
228  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
229  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
230  const std::string & remote_node_name = "",
231  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
232 
235  get_parameters(const std::vector<std::string> & parameter_names);
236 
238  bool
239  has_parameter(const std::string & parameter_name);
240 
241  template<typename T>
242  T
244  const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
245  {
247  names.push_back(parameter_name);
248  auto vars = get_parameters(names);
249  if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) {
250  return parameter_not_found_handler();
251  } else {
252  return static_cast<T>(vars[0].get_value<T>());
253  }
254  }
255 
256  template<typename T>
257  T
258  get_parameter(const std::string & parameter_name, const T & default_value)
259  {
260  return get_parameter_impl(
261  parameter_name,
262  std::function<T()>([&default_value]() -> T {return default_value;}));
263  }
264 
265  template<typename T>
266  T
267  get_parameter(const std::string & parameter_name)
268  {
269  return get_parameter_impl(
270  parameter_name,
271  std::function<T()>([]() -> T {throw std::runtime_error("Parameter not set");}));
272  }
273 
276  get_parameter_types(const std::vector<std::string> & parameter_names);
277 
281 
283  rcl_interfaces::msg::SetParametersResult
285 
287  rcl_interfaces::msg::ListParametersResult
289  const std::vector<std::string> & parameter_prefixes,
290  uint64_t depth);
291 
292  template<typename CallbackT>
294  on_parameter_event(CallbackT && callback)
295  {
296  return async_parameters_client_->on_parameter_event(
297  std::forward<CallbackT>(callback));
298  }
299 
305  template<
306  typename CallbackT,
307  typename NodeT>
310  NodeT && node,
311  CallbackT && callback)
312  {
314  node,
315  std::forward<CallbackT>(callback));
316  }
317 
319  bool
321  {
322  return async_parameters_client_->service_is_ready();
323  }
324 
325  template<typename RepT = int64_t, typename RatioT = std::milli>
326  bool
329  {
330  return async_parameters_client_->wait_for_service(timeout);
331  }
332 
333 private:
334  rclcpp::executor::Executor::SharedPtr executor_;
335  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
336  AsyncParametersClient::SharedPtr async_parameters_client_;
337 };
338 
339 } // namespace rclcpp
340 
341 #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:294
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:327
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)
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_default))), const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Definition: parameter_client.hpp:141
This header provides the get_node_topics_interface() template function.
Definition: allocator_common.hpp:24
Definition: parameter_client.hpp:44
bool service_is_ready() const
Definition: parameter_client.hpp:320
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...
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_default))), const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Definition: parameter_client.hpp:115
Definition: client.hpp:119
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:59
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:267
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:165
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)
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)
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:46
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(NodeT &&node, CallbackT &&callback)
Definition: parameter_client.hpp:309
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Definition: parameter_client.hpp:192
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:258
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:243