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_subscription.hpp"
44 #include "rclcpp/create_timer.hpp"
45 #include "rclcpp/detail/resolve_enable_topic_statistics.hpp"
46 #include "rclcpp/parameter.hpp"
47 #include "rclcpp/qos.hpp"
48 #include "rclcpp/timer.hpp"
49 #include "rclcpp/type_support_decl.hpp"
50 #include "rclcpp/visibility_control.hpp"
52 #ifndef RCLCPP__NODE_HPP_
62 extend_name_with_sub_namespace(
const std::string & name,
const std::string & sub_namespace)
64 std::string name_with_sub_namespace(name);
65 if (sub_namespace !=
"" && name.front() !=
'/' && name.front() !=
'~') {
66 name_with_sub_namespace = sub_namespace +
"/" + name;
68 return name_with_sub_namespace;
71 template<
typename MessageT,
typename AllocatorT,
typename PublisherT>
72 std::shared_ptr<PublisherT>
74 const std::string & topic_name,
78 return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
89 typename SubscriptionT,
90 typename MessageMemoryStrategyT>
91 std::shared_ptr<SubscriptionT>
93 const std::string & topic_name,
95 CallbackT && callback,
97 typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
99 return rclcpp::create_subscription<MessageT>(
103 std::forward<CallbackT>(callback),
108 template<
typename DurationRepT,
typename DurationT,
typename CallbackT>
111 std::chrono::duration<DurationRepT, DurationT> period,
113 rclcpp::CallbackGroup::SharedPtr group,
120 this->node_base_.get(),
121 this->node_timers_.get(),
125 template<
typename DurationRepT,
typename DurationT,
typename CallbackT>
128 std::chrono::duration<DurationRepT, DurationT> period,
130 rclcpp::CallbackGroup::SharedPtr group)
137 this->node_base_.get(),
138 this->node_timers_.get());
141 template<
typename ServiceT>
144 const std::string & service_name,
146 rclcpp::CallbackGroup::SharedPtr group)
148 return rclcpp::create_client<ServiceT>(
157 template<
typename ServiceT>
158 typename Client<ServiceT>::SharedPtr
160 const std::string & service_name,
161 const rmw_qos_profile_t & qos_profile,
162 rclcpp::CallbackGroup::SharedPtr group)
164 return rclcpp::create_client<ServiceT>(
173 template<
typename ServiceT,
typename CallbackT>
176 const std::string & service_name,
177 CallbackT && callback,
179 rclcpp::CallbackGroup::SharedPtr group)
181 return rclcpp::create_service<ServiceT, CallbackT>(
185 std::forward<CallbackT>(callback),
190 template<
typename ServiceT,
typename CallbackT>
193 const std::string & service_name,
194 CallbackT && callback,
195 const rmw_qos_profile_t & qos_profile,
196 rclcpp::CallbackGroup::SharedPtr group)
198 return rclcpp::create_service<ServiceT, CallbackT>(
202 std::forward<CallbackT>(callback),
207 template<
typename AllocatorT>
208 std::shared_ptr<rclcpp::GenericPublisher>
210 const std::string & topic_name,
211 const std::string & topic_type,
224 template<
typename CallbackT,
typename AllocatorT>
225 std::shared_ptr<rclcpp::GenericSubscription>
227 const std::string & topic_name,
228 const std::string & topic_type,
230 CallbackT && callback,
238 std::forward<CallbackT>(callback),
244 template<
typename ParameterT>
247 const std::string & name,
248 const ParameterT & default_value,
249 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
250 bool ignore_override)
256 parameter_descriptor,
264 template<
typename ParameterT>
267 const std::string & name,
268 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
269 bool ignore_override)
278 parameter_descriptor,
286 template<
typename ParameterT>
287 std::vector<ParameterT>
289 const std::string & namespace_,
290 const std::map<std::string, ParameterT> & parameters,
291 bool ignore_overrides)
293 std::vector<ParameterT> result;
294 std::string normalized_namespace = namespace_.empty() ?
"" : (namespace_ +
".");
296 parameters.begin(), parameters.end(), std::back_inserter(result),
297 [
this, &normalized_namespace, ignore_overrides](
auto element) {
298 return this->declare_parameter(
299 normalized_namespace + element.first,
301 rcl_interfaces::msg::ParameterDescriptor(),
308 template<
typename ParameterT>
309 std::vector<ParameterT>
311 const std::string & namespace_,
314 std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
316 bool ignore_overrides)
318 std::vector<ParameterT> result;
319 std::string normalized_namespace = namespace_.empty() ?
"" : (namespace_ +
".");
321 parameters.begin(), parameters.end(), std::back_inserter(result),
322 [
this, &normalized_namespace, ignore_overrides](
auto element) {
323 return static_cast<ParameterT>(
324 this->declare_parameter(
325 normalized_namespace + element.first,
326 element.second.first,
327 element.second.second,
335 template<
typename ParameterT>
339 std::string sub_name = extend_name_with_sub_namespace(name, this->
get_sub_namespace());
345 parameter =
static_cast<ParameterT
>(parameter_variant.
get_value<ParameterT>());
351 template<
typename ParameterT>
354 const std::string & name,
355 ParameterT & parameter,
356 const ParameterT & alternative_value)
const
358 std::string sub_name = extend_name_with_sub_namespace(name, this->
get_sub_namespace());
361 if (!got_parameter) {
362 parameter = alternative_value;
364 return got_parameter;
367 template<
typename ParameterT>
370 const std::string & name,
371 const ParameterT & alternative_value)
const
373 ParameterT parameter;
381 template<
typename ParameterT>
384 const std::string & prefix,
385 std::map<std::string, ParameterT> & values)
const
387 std::map<std::string, rclcpp::Parameter> params;
388 bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
390 for (
const auto & param : params) {
391 values[param.first] =
static_cast<ParameterT
>(param.second.get_value<ParameterT>());
Generic timer. Periodically executes a user-specified callback.
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::Service< ServiceT >::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
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_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
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.