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 
49 
50 
61  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
62  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
63  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
64  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
65  const std::string & remote_node_name = "",
66  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
67  rclcpp::CallbackGroup::SharedPtr group = nullptr);
68 
70 
78  const rclcpp::Node::SharedPtr node,
79  const std::string & remote_node_name = "",
80  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
81  rclcpp::CallbackGroup::SharedPtr group = nullptr);
82 
84 
92  rclcpp::Node * node,
93  const std::string & remote_node_name = "",
94  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters,
95  rclcpp::CallbackGroup::SharedPtr group = nullptr);
96 
100  const std::vector<std::string> & names,
103  > callback = nullptr);
104 
108  const std::vector<std::string> & names,
111  > callback = nullptr);
112 
116  const std::vector<rclcpp::Parameter> & parameters,
119  > callback = nullptr);
120 
124  const std::vector<rclcpp::Parameter> & parameters,
127  > callback = nullptr);
128 
132  const std::vector<std::string> & prefixes,
133  uint64_t depth,
136  > callback = nullptr);
137 
138  template<
139  typename CallbackT,
140  typename AllocatorT = std::allocator<void>>
143  CallbackT && callback,
144  const rclcpp::QoS & qos = (
145  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))
146  ),
149  ))
150  {
151  return this->on_parameter_event(
152  this->node_topics_interface_,
153  callback,
154  qos,
155  options);
156  }
157 
163  template<
164  typename CallbackT,
165  typename NodeT,
166  typename AllocatorT = std::allocator<void>>
169  NodeT && node,
170  CallbackT && callback,
171  const rclcpp::QoS & qos = (
172  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events))
173  ),
176  ))
177  {
178  return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
179  node,
180  "parameter_events",
181  qos,
182  std::forward<CallbackT>(callback),
183  options);
184  }
185 
187 
198  bool
199  service_is_ready() const;
200 
202 
206  template<typename RepT = int64_t, typename RatioT = std::milli>
207  bool
210  {
212  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
213  );
214  }
215 
216 protected:
218  bool
220 
221 private:
222  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
225  get_parameter_types_client_;
228  set_parameters_atomically_client_;
231  describe_parameters_client_;
232  std::string remote_node_name_;
233 };
234 
236 {
237 public:
239 
241  explicit SyncParametersClient(
242  rclcpp::Node::SharedPtr node,
243  const std::string & remote_node_name = "",
244  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
245 
248  rclcpp::Executor::SharedPtr executor,
249  rclcpp::Node::SharedPtr node,
250  const std::string & remote_node_name = "",
251  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
252 
254  explicit SyncParametersClient(
255  rclcpp::Node * node,
256  const std::string & remote_node_name = "",
257  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
258 
261  rclcpp::Executor::SharedPtr executor,
262  rclcpp::Node * node,
263  const std::string & remote_node_name = "",
264  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
265 
268  rclcpp::Executor::SharedPtr executor,
269  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
270  const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface,
271  const rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
272  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_interface,
273  const std::string & remote_node_name = "",
274  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
275 
278  get_parameters(const std::vector<std::string> & parameter_names);
279 
281  bool
282  has_parameter(const std::string & parameter_name);
283 
284  template<typename T>
285  T
287  const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
288  {
290  names.push_back(parameter_name);
291  auto vars = get_parameters(names);
292  if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) {
293  return parameter_not_found_handler();
294  } else {
295  return static_cast<T>(vars[0].get_value<T>());
296  }
297  }
298 
299  template<typename T>
300  T
301  get_parameter(const std::string & parameter_name, const T & default_value)
302  {
303  return get_parameter_impl(
304  parameter_name,
305  std::function<T()>([&default_value]() -> T {return default_value;}));
306  }
307 
308  template<typename T>
309  T
310  get_parameter(const std::string & parameter_name)
311  {
312  return get_parameter_impl(
313  parameter_name,
314  std::function<T()>(
315  [&parameter_name]() -> T
316  {
317  throw std::runtime_error("Parameter '" + parameter_name + "' is not set");
318  })
319  );
320  }
321 
324  get_parameter_types(const std::vector<std::string> & parameter_names);
325 
329 
331  rcl_interfaces::msg::SetParametersResult
333 
335  rcl_interfaces::msg::ListParametersResult
337  const std::vector<std::string> & parameter_prefixes,
338  uint64_t depth);
339 
340  template<typename CallbackT>
342  on_parameter_event(CallbackT && callback)
343  {
344  return async_parameters_client_->on_parameter_event(
345  std::forward<CallbackT>(callback));
346  }
347 
353  template<
354  typename CallbackT,
355  typename NodeT>
358  NodeT && node,
359  CallbackT && callback)
360  {
362  node,
363  std::forward<CallbackT>(callback));
364  }
365 
367  bool
369  {
370  return async_parameters_client_->service_is_ready();
371  }
372 
373  template<typename RepT = int64_t, typename RatioT = std::milli>
374  bool
377  {
378  return async_parameters_client_->wait_for_service(timeout);
379  }
380 
381 private:
382  rclcpp::Executor::SharedPtr executor_;
383  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
384  AsyncParametersClient::SharedPtr async_parameters_client_;
385 };
386 
387 } // namespace rclcpp
388 
389 #endif // RCLCPP__PARAMETER_CLIENT_HPP_
std::shared_future
rclcpp::SyncParametersClient::service_is_ready
bool service_is_ready() const
Definition: parameter_client.hpp:368
rclcpp::SyncParametersClient::get_parameters
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &parameter_names)
std::string
rclcpp::AsyncParametersClient::on_parameter_event
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:168
rmw.h
std::vector< std::string >
node.hpp
std::chrono::duration
rclcpp::SubscriptionOptionsWithAllocator
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:79
rclcpp::SyncParametersClient::on_parameter_event
static rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(NodeT &&node, CallbackT &&callback)
Definition: parameter_client.hpp:357
std::function
executors.hpp
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
rclcpp::SyncParametersClient::list_parameters
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &parameter_prefixes, uint64_t depth)
rclcpp::Subscription
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::SyncParametersClient::has_parameter
bool has_parameter(const std::string &parameter_name)
std::vector::push_back
T push_back(T... args)
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:59
rclcpp::SyncParametersClient::wait_for_service
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Definition: parameter_client.hpp:375
RCLCPP_SMART_PTR_DEFINITIONS
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
macros.hpp
rclcpp::QoSInitialization::from_rmw
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::SyncParametersClient::on_parameter_event
rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:342
rclcpp::Node
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:74
rclcpp::AsyncParametersClient::get_parameter_types
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)
rclcpp::AsyncParametersClient::get_parameters
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)
rclcpp::AsyncParametersClient::set_parameters_atomically
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)
rclcpp::AsyncParametersClient::wait_for_service
bool wait_for_service(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Wait for the services to be ready.
Definition: parameter_client.hpp:208
rclcpp::PARAMETER_NOT_SET
@ PARAMETER_NOT_SET
Definition: parameter_value.hpp:34
rclcpp::SyncParametersClient::SyncParametersClient
SyncParametersClient(rclcpp::Node::SharedPtr node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
rclcpp::SyncParametersClient::get_parameter_types
std::vector< rclcpp::ParameterType > get_parameter_types(const std::vector< std::string > &parameter_names)
create_subscription.hpp
rclcpp::AsyncParametersClient
Definition: parameter_client.hpp:44
std::runtime_error
rclcpp::SyncParametersClient::get_parameter_impl
T get_parameter_impl(const std::string &parameter_name, std::function< T()> parameter_not_found_handler)
Definition: parameter_client.hpp:286
rclcpp::AsyncParametersClient::service_is_ready
bool service_is_ready() const
Return if the parameter services are ready.
rclcpp::AsyncParametersClient::set_parameters
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)
parameter.hpp
rclcpp::SyncParametersClient::set_parameters
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters)
rclcpp::AsyncParametersClient::AsyncParametersClient
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::CallbackGroup::SharedPtr group=nullptr)
Create an async parameters client.
rclcpp::Client
Definition: client.hpp:178
rclcpp::SyncParametersClient::get_parameter
T get_parameter(const std::string &parameter_name, const T &default_value)
Definition: parameter_client.hpp:301
type_support_decl.hpp
visibility_control.hpp
rclcpp::AsyncParametersClient::list_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)
rclcpp::AsyncParametersClient::on_parameter_event
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:142
rmw_qos_profile_t
rclcpp::SyncParametersClient
Definition: parameter_client.hpp:235
rclcpp::SyncParametersClient::set_parameters_atomically
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters)
std::allocator
rclcpp::SyncParametersClient::get_parameter
T get_parameter(const std::string &parameter_name)
Definition: parameter_client.hpp:310
rclcpp::AsyncParametersClient::wait_for_service_nanoseconds
bool wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)