rclcpp  beta1
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 <string>
19 #include <utility>
20 #include <vector>
21 
22 #include "rcl_interfaces/msg/parameter.hpp"
23 #include "rcl_interfaces/msg/parameter_event.hpp"
24 #include "rcl_interfaces/msg/parameter_value.hpp"
25 #include "rcl_interfaces/srv/describe_parameters.hpp"
26 #include "rcl_interfaces/srv/get_parameter_types.hpp"
27 #include "rcl_interfaces/srv/get_parameters.hpp"
28 #include "rcl_interfaces/srv/list_parameters.hpp"
29 #include "rcl_interfaces/srv/set_parameters.hpp"
30 #include "rcl_interfaces/srv/set_parameters_atomically.hpp"
31 #include "rclcpp/executors.hpp"
32 #include "rclcpp/macros.hpp"
33 #include "rclcpp/node.hpp"
34 #include "rclcpp/parameter.hpp"
37 #include "rmw/rmw.h"
38 
39 namespace rclcpp
40 {
41 namespace parameter_client
42 {
43 
45 {
46 public:
48 
51  const rclcpp::node::Node::SharedPtr node,
52  const std::string & remote_node_name = "",
53  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
54 
58  const std::vector<std::string> & names,
61  > callback = nullptr);
62 
66  const std::vector<std::string> & names,
69  > callback = nullptr);
70 
77  > callback = nullptr);
78 
85  > callback = nullptr);
86 
90  const std::vector<std::string> & prefixes,
91  uint64_t depth,
94  > callback = nullptr);
95 
96  template<typename CallbackT>
98  on_parameter_event(CallbackT && callback)
99  {
100  return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>(
101  "parameter_events", std::forward<CallbackT>(callback), rmw_qos_profile_parameter_events);
102  }
103 
104 private:
105  const rclcpp::node::Node::SharedPtr node_;
108  get_parameter_types_client_;
111  set_parameters_atomically_client_;
114  describe_parameters_client_;
115  std::string remote_node_name_;
116 };
117 
119 {
120 public:
122 
124  explicit SyncParametersClient(
125  rclcpp::node::Node::SharedPtr node,
126  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
127 
129  SyncParametersClient(
130  rclcpp::executor::Executor::SharedPtr executor,
131  rclcpp::node::Node::SharedPtr node,
132  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
133 
136  get_parameters(const std::vector<std::string> & parameter_names);
137 
139  bool
140  has_parameter(const std::string & parameter_name);
141 
142  template<typename T>
143  T
145  const std::string & parameter_name, std::function<T()> parameter_not_found_handler)
146  {
148  names.push_back(parameter_name);
149  auto vars = get_parameters(names);
150  if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::parameter::PARAMETER_NOT_SET)) {
151  return parameter_not_found_handler();
152  } else {
153  return static_cast<T>(vars[0].get_value<T>());
154  }
155  }
156 
157  template<typename T>
158  T
159  get_parameter(const std::string & parameter_name, const T & default_value)
160  {
161  // *INDENT-OFF*
162  return get_parameter_impl(parameter_name,
163  std::function<T()>([&default_value]() -> T {return default_value; }));
164  // *INDENT-ON*
165  }
166 
167  template<typename T>
168  T
169  get_parameter(const std::string & parameter_name)
170  {
171  // *INDENT-OFF*
172  return get_parameter_impl(parameter_name,
173  std::function<T()>([]() -> T {throw std::runtime_error("Parameter not set"); }));
174  // *INDENT-ON*
175  }
176 
179  get_parameter_types(const std::vector<std::string> & parameter_names);
180 
184 
186  rcl_interfaces::msg::SetParametersResult
188 
190  rcl_interfaces::msg::ListParametersResult
192  const std::vector<std::string> & parameter_prefixes,
193  uint64_t depth);
194 
195  template<typename CallbackT>
197  on_parameter_event(CallbackT && callback)
198  {
199  return async_parameters_client_->on_parameter_event(std::forward<CallbackT>(callback));
200  }
201 
202 private:
203  rclcpp::executor::Executor::SharedPtr executor_;
204  rclcpp::node::Node::SharedPtr node_;
205  AsyncParametersClient::SharedPtr async_parameters_client_;
206 };
207 
208 } // namespace parameter_client
209 } // namespace rclcpp
210 
211 #endif // RCLCPP__PARAMETER_CLIENT_HPP_
rclcpp::subscription::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:197
Definition: client.hpp:111
Definition: allocator_common.hpp:24
Definition: parameter_client.hpp:118
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:122
T get_parameter(const std::string &parameter_name)
Definition: parameter_client.hpp:169
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 push_back(T... args)
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)
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
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)
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)
rclcpp::subscription::Subscription< rcl_interfaces::msg::ParameterEvent >::SharedPtr on_parameter_event(CallbackT &&callback)
Definition: parameter_client.hpp:98
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)
T get_parameter(const std::string &parameter_name, const T &default_value)
Definition: parameter_client.hpp:159
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
AsyncParametersClient(const rclcpp::node::Node::SharedPtr node, const std::string &remote_node_name="", const rmw_qos_profile_t &qos_profile=rmw_qos_profile_parameters)
T get_parameter_impl(const std::string &parameter_name, std::function< T()> parameter_not_found_handler)
Definition: parameter_client.hpp:144
Definition: parameter.hpp:36
Definition: parameter_client.hpp:44