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)
119 this->node_base_.get(),
120 this->node_timers_.get());
123 template<
typename ServiceT>
126 const std::string & service_name,
127 const rmw_qos_profile_t & qos_profile,
128 rclcpp::CallbackGroup::SharedPtr group)
130 return rclcpp::create_client<ServiceT>(
139 template<
typename ServiceT,
typename CallbackT>
142 const std::string & service_name,
143 CallbackT && callback,
144 const rmw_qos_profile_t & qos_profile,
145 rclcpp::CallbackGroup::SharedPtr group)
147 return rclcpp::create_service<ServiceT, CallbackT>(
151 std::forward<CallbackT>(callback),
156 template<
typename AllocatorT>
157 std::shared_ptr<rclcpp::GenericPublisher>
159 const std::string & topic_name,
160 const std::string & topic_type,
173 template<
typename AllocatorT>
174 std::shared_ptr<rclcpp::GenericSubscription>
176 const std::string & topic_name,
177 const std::string & topic_type,
179 std::function<
void(std::shared_ptr<rclcpp::SerializedMessage>)> callback,
193 template<
typename ParameterT>
196 const std::string & name,
197 const ParameterT & default_value,
198 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
199 bool ignore_override)
205 parameter_descriptor,
213 template<
typename ParameterT>
216 const std::string & name,
217 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
218 bool ignore_override)
227 parameter_descriptor,
235 template<
typename ParameterT>
236 std::vector<ParameterT>
238 const std::string & namespace_,
239 const std::map<std::string, ParameterT> & parameters,
240 bool ignore_overrides)
242 std::vector<ParameterT> result;
243 std::string normalized_namespace = namespace_.empty() ?
"" : (namespace_ +
".");
245 parameters.begin(), parameters.end(), std::back_inserter(result),
246 [
this, &normalized_namespace, ignore_overrides](
auto element) {
247 return this->declare_parameter(
248 normalized_namespace + element.first,
250 rcl_interfaces::msg::ParameterDescriptor(),
257 template<
typename ParameterT>
258 std::vector<ParameterT>
260 const std::string & namespace_,
263 std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
265 bool ignore_overrides)
267 std::vector<ParameterT> result;
268 std::string normalized_namespace = namespace_.empty() ?
"" : (namespace_ +
".");
270 parameters.begin(), parameters.end(), std::back_inserter(result),
271 [
this, &normalized_namespace, ignore_overrides](
auto element) {
272 return static_cast<ParameterT>(
273 this->declare_parameter(
274 normalized_namespace + element.first,
275 element.second.first,
276 element.second.second,
284 template<
typename ParameterT>
288 std::string sub_name = extend_name_with_sub_namespace(name, this->
get_sub_namespace());
294 parameter =
static_cast<ParameterT
>(parameter_variant.
get_value<ParameterT>());
300 template<
typename ParameterT>
303 const std::string & name,
304 ParameterT & parameter,
305 const ParameterT & alternative_value)
const
307 std::string sub_name = extend_name_with_sub_namespace(name, this->
get_sub_namespace());
310 if (!got_parameter) {
311 parameter = alternative_value;
313 return got_parameter;
316 template<
typename ParameterT>
319 const std::string & name,
320 const ParameterT & alternative_value)
const
322 ParameterT parameter;
330 template<
typename ParameterT>
333 const std::string & prefix,
334 std::map<std::string, ParameterT> & values)
const
336 std::map<std::string, rclcpp::Parameter> params;
337 bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
339 for (
const auto & param : params) {
340 values[param.first] =
static_cast<ParameterT
>(param.second.get_value<ParameterT>());
RCLCPP_PUBLIC std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
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.
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".
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.
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< 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)
Create a timer.
RCLCPP_PUBLIC const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
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.
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.
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 >()))
Create and return a GenericSubscription.
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.
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)
Convenience method to create a timer with node resources.
Structure containing optional configuration for Publishers.
Structure containing optional configuration for Subscriptions.