15 #ifndef RCLCPP__NODE_IMPL_HPP_
16 #define RCLCPP__NODE_IMPL_HPP_
18 #include <rmw/error_handling.h>
37 #include "rclcpp/contexts/default_context.hpp"
38 #include "rclcpp/create_client.hpp"
39 #include "rclcpp/create_generic_publisher.hpp"
40 #include "rclcpp/create_generic_subscription.hpp"
41 #include "rclcpp/create_publisher.hpp"
42 #include "rclcpp/create_service.hpp"
43 #include "rclcpp/create_generic_service.hpp"
44 #include "rclcpp/create_subscription.hpp"
45 #include "rclcpp/create_timer.hpp"
46 #include "rclcpp/detail/resolve_enable_topic_statistics.hpp"
47 #include "rclcpp/parameter.hpp"
48 #include "rclcpp/qos.hpp"
49 #include "rclcpp/timer.hpp"
50 #include "rclcpp/type_support_decl.hpp"
51 #include "rclcpp/visibility_control.hpp"
53 #ifndef RCLCPP__NODE_HPP_
63 extend_name_with_sub_namespace(
const std::string & name,
const std::string & sub_namespace)
65 std::string name_with_sub_namespace(name);
66 if (sub_namespace !=
"" && name.front() !=
'/' && name.front() !=
'~') {
67 name_with_sub_namespace = sub_namespace +
"/" + name;
69 return name_with_sub_namespace;
72 template<
typename MessageT,
typename AllocatorT,
typename PublisherT>
73 std::shared_ptr<PublisherT>
75 const std::string & topic_name,
79 return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
90 typename SubscriptionT,
91 typename MessageMemoryStrategyT>
92 std::shared_ptr<SubscriptionT>
94 const std::string & topic_name,
96 CallbackT && callback,
98 typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
100 return rclcpp::create_subscription<MessageT>(
104 std::forward<CallbackT>(callback),
109 template<
typename DurationRepT,
typename DurationT,
typename CallbackT>
112 std::chrono::duration<DurationRepT, DurationT> period,
114 rclcpp::CallbackGroup::SharedPtr group,
121 this->node_base_.get(),
122 this->node_timers_.get(),
126 template<
typename DurationRepT,
typename DurationT,
typename CallbackT>
129 std::chrono::duration<DurationRepT, DurationT> period,
131 rclcpp::CallbackGroup::SharedPtr group)
138 this->node_base_.get(),
139 this->node_timers_.get());
142 template<
typename ServiceT>
145 const std::string & service_name,
147 rclcpp::CallbackGroup::SharedPtr group)
149 return rclcpp::create_client<ServiceT>(
158 template<
typename ServiceT,
typename CallbackT>
161 const std::string & service_name,
162 CallbackT && callback,
164 rclcpp::CallbackGroup::SharedPtr group)
166 return rclcpp::create_service<ServiceT, CallbackT>(
170 std::forward<CallbackT>(callback),
175 template<
typename CallbackT>
176 typename rclcpp::GenericService::SharedPtr
178 const std::string & service_name,
179 const std::string & service_type,
180 CallbackT && callback,
182 rclcpp::CallbackGroup::SharedPtr group)
184 return rclcpp::create_generic_service<CallbackT>(
189 std::forward<CallbackT>(callback),
194 template<
typename AllocatorT>
195 std::shared_ptr<rclcpp::GenericPublisher>
197 const std::string & topic_name,
198 const std::string & topic_type,
211 template<
typename CallbackT,
typename AllocatorT>
212 std::shared_ptr<rclcpp::GenericSubscription>
214 const std::string & topic_name,
215 const std::string & topic_type,
217 CallbackT && callback,
225 std::forward<CallbackT>(callback),
231 template<
typename ParameterT>
234 const std::string & name,
235 const ParameterT & default_value,
236 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
237 bool ignore_override)
243 parameter_descriptor,
251 template<
typename ParameterT>
254 const std::string & name,
255 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
256 bool ignore_override)
265 parameter_descriptor,
273 template<
typename ParameterT>
274 std::vector<ParameterT>
276 const std::string & namespace_,
277 const std::map<std::string, ParameterT> & parameters,
278 bool ignore_overrides)
280 std::vector<ParameterT> result;
281 std::string normalized_namespace = namespace_.empty() ?
"" : (namespace_ +
".");
283 parameters.begin(), parameters.end(), std::back_inserter(result),
284 [
this, &normalized_namespace, ignore_overrides](
auto element) {
285 return this->declare_parameter(
286 normalized_namespace + element.first,
288 rcl_interfaces::msg::ParameterDescriptor(),
295 template<
typename ParameterT>
296 std::vector<ParameterT>
298 const std::string & namespace_,
301 std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
303 bool ignore_overrides)
305 std::vector<ParameterT> result;
306 std::string normalized_namespace = namespace_.empty() ?
"" : (namespace_ +
".");
308 parameters.begin(), parameters.end(), std::back_inserter(result),
309 [
this, &normalized_namespace, ignore_overrides](
auto element) {
310 return static_cast<ParameterT>(
311 this->declare_parameter(
312 normalized_namespace + element.first,
313 element.second.first,
314 element.second.second,
322 template<
typename ParameterT>
330 parameter =
static_cast<ParameterT
>(parameter_variant.
get_value<ParameterT>());
336 template<
typename ParameterT>
339 const std::string & name,
340 ParameterT & parameter,
341 const ParameterT & alternative_value)
const
344 if (!got_parameter) {
345 parameter = alternative_value;
347 return got_parameter;
350 template<
typename ParameterT>
353 const std::string & name,
354 const ParameterT & alternative_value)
const
356 ParameterT parameter;
364 template<
typename ParameterT>
367 const std::string & prefix,
368 std::map<std::string, ParameterT> & values)
const
370 std::map<std::string, rclcpp::Parameter> params;
371 bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
373 for (
const auto & param : params) {
374 values[param.first] =
static_cast<ParameterT
>(param.second.get_value<ParameterT>());
Generic timer. Periodically executes a user-specified callback.
rclcpp::GenericService::SharedPtr create_generic_service(const std::string &service_name, const std::string &service_type, CallbackT &&callback, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a GenericService.
RCLCPP_PUBLIC std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
RCLCPP_PUBLIC const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
bool get_parameter_or(const std::string &name, ParameterT ¶meter, const ParameterT &alternative_value) const
Get the parameter value, or the "alternative_value" if not set, and assign it to "parameter".
rclcpp::GenericTimer< CallbackT >::SharedPtr create_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create a timer that uses the node clock to drive the callback.
std::vector< ParameterT > declare_parameters(const std::string &namespace_, const std::map< std::string, ParameterT > ¶meters, bool ignore_overrides=false)
Declare and initialize several parameters with the same namespace and type.
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
rclcpp::Service< ServiceT >::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
std::shared_ptr< rclcpp::GenericSubscription > create_generic_subscription(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
std::shared_ptr< SubscriptionT > create_subscription(const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const SubscriptionOptionsWithAllocator< AllocatorT > &options=SubscriptionOptionsWithAllocator< AllocatorT >(), typename MessageMemoryStrategyT::SharedPtr msg_mem_strat=(MessageMemoryStrategyT::create_default()))
Create and return a Subscription.
std::shared_ptr< PublisherT > create_publisher(const std::string &topic_name, const rclcpp::QoS &qos, const PublisherOptionsWithAllocator< AllocatorT > &options=PublisherOptionsWithAllocator< AllocatorT >())
Create and return a Publisher.
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr, bool autostart=true)
Create a wall timer that uses the wall clock to drive the callback.
RCLCPP_PUBLIC const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
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.
Indicate the parameter type does not match the expected type.
Store the type and value of a parameter.
Structure to store an arbitrary parameter with templated get/set methods.
decltype(auto) get_value() const
Get value of parameter using rclcpp::ParameterType as template argument.
Encapsulation of Quality of Service settings.
Thrown if requested parameter type is invalid.
Thrown if user attempts to create an uninitialized statically typed parameter.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
rclcpp::TimerBase::SharedPtr create_timer(std::shared_ptr< node_interfaces::NodeBaseInterface > node_base, std::shared_ptr< node_interfaces::NodeTimersInterface > node_timers, rclcpp::Clock::SharedPtr clock, rclcpp::Duration period, CallbackT &&callback, rclcpp::CallbackGroup::SharedPtr group=nullptr, bool autostart=true)
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group, node_interfaces::NodeBaseInterface *node_base, node_interfaces::NodeTimersInterface *node_timers, bool autostart=true)
Convenience method to create a wall timer with node resources.
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 >()))
Create and return a GenericPublisher.
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, CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
Structure containing optional configuration for Publishers.
Structure containing optional configuration for Subscriptions.