rclcpp_lifecycle  master
C++ ROS Lifecycle Library API
lifecycle_node_impl.hpp
Go to the documentation of this file.
1 // Copyright 2016 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_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
16 #define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
17 
18 #include <map>
19 #include <memory>
20 #include <string>
21 #include <utility>
22 #include <vector>
23 
30 #include "rclcpp/event.hpp"
32 #include "rclcpp/parameter.hpp"
35 
36 #include "lifecycle_publisher.hpp"
38 
40 
41 namespace rclcpp_lifecycle
42 {
43 
44 template<typename MessageT, typename AllocatorT>
47  const std::string & topic_name,
48  const rclcpp::QoS & qos,
50 {
52  return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
53  *this,
54  topic_name,
55  qos,
56  options);
57 }
58 
59 // TODO(karsten1987): Create LifecycleSubscriber
60 template<
61  typename MessageT,
62  typename CallbackT,
63  typename AllocatorT,
64  typename CallbackMessageT,
65  typename SubscriptionT,
66  typename MessageMemoryStrategyT>
69  const std::string & topic_name,
70  const rclcpp::QoS & qos,
71  CallbackT && callback,
73  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
74 {
75  return rclcpp::create_subscription<MessageT>(
76  *this,
77  topic_name,
78  qos,
79  std::forward<CallbackT>(callback),
80  options,
81  msg_mem_strat);
82 }
83 
84 template<typename DurationRepT, typename DurationT, typename CallbackT>
88  CallbackT callback,
89  rclcpp::CallbackGroup::SharedPtr group)
90 {
92  std::chrono::duration_cast<std::chrono::nanoseconds>(period),
93  std::move(callback), this->node_base_->get_context());
94  node_timers_->add_timer(timer, group);
95  return timer;
96 }
97 
98 template<typename ServiceT>
101  const std::string & service_name,
102  const rmw_qos_profile_t & qos_profile,
103  rclcpp::CallbackGroup::SharedPtr group)
104 {
105  rcl_client_options_t options = rcl_client_get_default_options();
106  options.qos = qos_profile;
107 
108  using rclcpp::Client;
109  using rclcpp::ClientBase;
110 
111  auto cli = Client<ServiceT>::make_shared(
112  node_base_.get(),
113  node_graph_,
114  service_name,
115  options);
116 
117  auto cli_base_ptr = std::dynamic_pointer_cast<ClientBase>(cli);
118  node_services_->add_client(cli_base_ptr, group);
119  return cli;
120 }
121 
122 template<typename ServiceT, typename CallbackT>
125  const std::string & service_name,
126  CallbackT && callback,
127  const rmw_qos_profile_t & qos_profile,
128  rclcpp::CallbackGroup::SharedPtr group)
129 {
130  return rclcpp::create_service<ServiceT, CallbackT>(
131  node_base_, node_services_,
132  service_name, std::forward<CallbackT>(callback), qos_profile, group);
133 }
134 
135 template<typename AllocatorT>
138  const std::string & topic_name,
139  const std::string & topic_type,
140  const rclcpp::QoS & qos,
142 {
144  node_topics_,
145  // TODO(karsten1987): LifecycleNode is currently not supporting subnamespaces
146  // see https://github.com/ros2/rclcpp/issues/1614
147  topic_name,
148  topic_type,
149  qos,
150  options
151  );
152 }
153 
154 template<typename AllocatorT>
157  const std::string & topic_name,
158  const std::string & topic_type,
159  const rclcpp::QoS & qos,
162 {
164  node_topics_,
165  // TODO(karsten1987): LifecycleNode is currently not supporting subnamespaces
166  // see https://github.com/ros2/rclcpp/issues/1614
167  topic_name,
168  topic_type,
169  qos,
170  std::move(callback),
171  options
172  );
173 }
174 
175 template<typename ParameterT>
176 auto
178  const std::string & name,
179  const ParameterT & default_value,
180  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
181  bool ignore_override)
182 {
183  return this->declare_parameter(
184  name,
185  rclcpp::ParameterValue(default_value),
186  parameter_descriptor,
187  ignore_override
188  ).get<ParameterT>();
189 }
190 
191 template<typename ParameterT>
192 auto
194  const std::string & name,
195  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
196  bool ignore_override)
197 {
198  // get advantage of parameter value template magic to get
199  // the correct rclcpp::ParameterType from ParameterT
200  rclcpp::ParameterValue value{ParameterT{}};
201  return this->declare_parameter(
202  name,
203  value.get_type(),
204  parameter_descriptor,
205  ignore_override
206  ).get<ParameterT>();
207 }
208 
209 template<typename ParameterT>
212  const std::string & namespace_,
213  const std::map<std::string, ParameterT> & parameters)
214 {
216  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
218  parameters.begin(), parameters.end(), std::back_inserter(result),
219  [this, &normalized_namespace](auto element) {
220  return this->declare_parameter(normalized_namespace + element.first, element.second);
221  }
222  );
223  return result;
224 }
225 
226 template<typename ParameterT>
229  const std::string & namespace_,
230  const std::map<
231  std::string,
233  > & parameters)
234 {
236  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
238  parameters.begin(), parameters.end(), std::back_inserter(result),
239  [this, &normalized_namespace](auto element) {
240  return static_cast<ParameterT>(
241  this->declare_parameter(
242  normalized_namespace + element.first,
243  element.second.first,
244  element.second.second)
245  );
246  }
247  );
248  return result;
249 }
250 
251 template<typename ParameterT>
252 bool
253 LifecycleNode::get_parameter(const std::string & name, ParameterT & parameter) const
254 {
255  rclcpp::Parameter param(name, parameter);
256  bool result = get_parameter(name, param);
257  parameter = param.get_value<ParameterT>();
258 
259  return result;
260 }
261 
262 // this is a partially-specialized version of get_parameter above,
263 // where our concrete type for ParameterT is std::map, but the to-be-determined
264 // type is the value in the map.
265 template<typename MapValueT>
266 bool
268  const std::string & prefix,
269  std::map<std::string, MapValueT> & values) const
270 {
272  bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
273  if (result) {
274  for (const auto & param : params) {
275  values[param.first] = param.second.get_value<MapValueT>();
276  }
277  }
278 
279  return result;
280 }
281 
282 template<typename ParameterT>
283 bool
285  const std::string & name,
286  ParameterT & value,
287  const ParameterT & alternative_value) const
288 {
289  bool got_parameter = get_parameter(name, value);
290  if (!got_parameter) {
291  value = alternative_value;
292  }
293  return got_parameter;
294 }
295 
296 } // namespace rclcpp_lifecycle
297 #endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
default_context.hpp
lifecycle_node.hpp
rclcpp::ParameterValue
std::string
std::shared_ptr
rclcpp::create_generic_publisher
std::shared_ptr< GenericPublisher > create_generic_publisher(rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=(rclcpp::PublisherOptionsWithAllocator< AllocatorT >()))
std::move
T move(T... args)
create_publisher.hpp
rclcpp_lifecycle::LifecycleNode::declare_parameters
std::vector< ParameterT > declare_parameters(const std::string &namespace_, const std::map< std::string, ParameterT > &parameters)
Declare and initialize several parameters with the same namespace and type.
Definition: lifecycle_node_impl.hpp:211
std::pair
lifecycle_publisher.hpp
std::vector
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL, const bool & >::type get() const
std::back_inserter
T back_inserter(T... args)
rclcpp::Parameter::get_value
decltype(auto) get_value() const
std::chrono::duration
create_subscription.hpp
rclcpp::Service
rclcpp::SubscriptionOptionsWithAllocator
type_support_decl.hpp
rclcpp_lifecycle::LifecycleNode::get_parameter
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
std::function
rclcpp_lifecycle::LifecycleNode::create_generic_publisher
std::shared_ptr< rclcpp::GenericPublisher > create_generic_publisher(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=(rclcpp::PublisherOptionsWithAllocator< AllocatorT >()))
Create and return a GenericPublisher.
Definition: lifecycle_node_impl.hpp:137
create_service.hpp
rclcpp_lifecycle::LifecycleNode::create_publisher
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< MessageT, AllocatorT > > create_publisher(const std::string &topic_name, const rclcpp::QoS &qos, const PublisherOptionsWithAllocator< AllocatorT > &options=(create_default_publisher_options< AllocatorT >()))
Create and return a Publisher.
Definition: lifecycle_node_impl.hpp:46
rclcpp_lifecycle::LifecycleNode::create_wall_timer
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create a timer.
Definition: lifecycle_node_impl.hpp:86
subscription_options.hpp
rclcpp::QoS
rclcpp_lifecycle
Definition: lifecycle_node.hpp:92
rclcpp::ClientBase
rclcpp_lifecycle::LifecycleNode::create_subscription
std::shared_ptr< SubscriptionT > create_subscription(const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const SubscriptionOptionsWithAllocator< AllocatorT > &options=create_default_subscription_options< AllocatorT >(), typename MessageMemoryStrategyT::SharedPtr msg_mem_strat=(MessageMemoryStrategyT::create_default()))
Create and return a Subscription.
rclcpp_lifecycle::LifecycleNode::create_service
rclcpp::Service< ServiceT >::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
Definition: lifecycle_node_impl.hpp:124
create_generic_publisher.hpp
std::map
std::transform
T transform(T... args)
parameter.hpp
visibility_control.h
rclcpp_lifecycle::LifecycleNode::declare_parameter
const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
rclcpp::PublisherOptionsWithAllocator< AllocatorT >
rclcpp::Client
event.hpp
std::map::begin
T begin(T... args)
rclcpp_lifecycle::LifecycleNode::create_generic_subscription
std::shared_ptr< rclcpp::GenericSubscription > create_generic_subscription(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, std::function< void(std::shared_ptr< rclcpp::SerializedMessage >)> callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
Definition: lifecycle_node_impl.hpp:156
rmw_qos_profile_t
std::string::empty
T empty(T... args)
rclcpp::WallTimer
intra_process_manager.hpp
rclcpp::Parameter
std::map::end
T end(T... args)
rclcpp_lifecycle::LifecycleNode::create_client
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
Definition: lifecycle_node_impl.hpp:100
rclcpp_lifecycle::LifecycleNode::get_parameters
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
rclcpp_lifecycle::LifecycleNode::get_parameter_or
bool get_parameter_or(const std::string &name, ParameterT &value, const ParameterT &alternative_value) const
Get the parameter value, or the "alternative_value" if not set, and assign it to "parameter".
Definition: lifecycle_node_impl.hpp:284
create_generic_subscription.hpp
rclcpp::create_generic_subscription
std::shared_ptr< GenericSubscription > create_generic_subscription(rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, std::function< void(std::shared_ptr< rclcpp::SerializedMessage >)> callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
rclcpp_lifecycle::LifecyclePublisher
brief child class of rclcpp Publisher class.
Definition: lifecycle_publisher.hpp:50