15 #ifndef RCLCPP__NODE_IMPL_HPP_ 16 #define RCLCPP__NODE_IMPL_HPP_ 36 #include "rcl_interfaces/msg/intra_process_message.hpp" 46 #ifndef RCLCPP__NODE_HPP_ 55 template<
typename MessageT,
typename Alloc,
typename PublisherT>
58 const std::string & topic_name,
size_t qos_history_depth,
62 allocator = std::make_shared<Alloc>();
65 qos.
depth = qos_history_depth;
66 return this->create_publisher<MessageT, Alloc, PublisherT>(topic_name, qos, allocator);
69 template<
typename MessageT,
typename Alloc,
typename PublisherT>
76 allocator = std::make_shared<Alloc>();
78 return rclcpp::create_publisher<MessageT, Alloc, PublisherT>(
79 this->node_topics_.get(),
82 use_intra_process_comms_,
86 template<
typename MessageT,
typename CallbackT,
typename Alloc,
typename SubscriptionT>
90 CallbackT && callback,
92 rclcpp::callback_group::CallbackGroup::SharedPtr group,
93 bool ignore_local_publications,
99 allocator = std::make_shared<Alloc>();
102 if (!msg_mem_strat) {
104 msg_mem_strat = MessageMemoryStrategy<MessageT, Alloc>::create_default();
107 return rclcpp::create_subscription<MessageT, CallbackT, Alloc, SubscriptionT>(
108 this->node_topics_.get(),
110 std::forward<CallbackT>(callback),
113 ignore_local_publications,
114 use_intra_process_comms_,
119 template<
typename MessageT,
typename CallbackT,
typename Alloc,
typename SubscriptionT>
123 size_t qos_history_depth,
124 CallbackT && callback,
125 rclcpp::callback_group::CallbackGroup::SharedPtr group,
126 bool ignore_local_publications,
132 qos.
depth = qos_history_depth;
133 return this->create_subscription<MessageT, CallbackT, Alloc, SubscriptionT>(
135 std::forward<CallbackT>(callback),
138 ignore_local_publications,
143 template<
typename DurationT,
typename CallbackT>
148 rclcpp::callback_group::CallbackGroup::SharedPtr group)
151 std::chrono::duration_cast<std::chrono::nanoseconds>(period),
153 node_timers_->add_timer(timer, group);
157 template<
typename ServiceT>
162 rclcpp::callback_group::CallbackGroup::SharedPtr group)
165 options.
qos = qos_profile;
170 auto cli = Client<ServiceT>::make_shared(
177 node_services_->add_client(cli_base_ptr, group);
181 template<
typename ServiceT,
typename CallbackT>
185 CallbackT && callback,
187 rclcpp::callback_group::CallbackGroup::SharedPtr group)
190 any_service_callback.
set(std::forward<CallbackT>(callback));
193 service_options.
qos = qos_profile;
196 node_base_->get_shared_rcl_node_handle(),
197 service_name, any_service_callback, service_options);
199 node_services_->add_service(serv_base_ptr, group);
203 template<
typename CallbackT>
207 this->node_parameters_->register_param_change_callback(std::forward<CallbackT>(callback));
210 template<
typename ParameterT>
216 parameter = parameter_variant.
get_value<ParameterT>();
224 #endif // RCLCPP__NODE_IMPL_HPP_
Definition: client.hpp:111
std::shared_ptr< PublisherT > create_publisher(const std::string &topic_name, size_t qos_history_depth, std::shared_ptr< Alloc > allocator=nullptr)
Create and return a Publisher.
Definition: node_impl.hpp:57
std::shared_ptr< SubscriptionT > create_subscription(const std::string &topic_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_default, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr, bool ignore_local_publications=false, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr msg_mem_strat=nullptr, std::shared_ptr< Alloc > allocator=nullptr)
Create and return a Subscription.
Definition: node_impl.hpp:88
Generic timer templated on the clock type. Periodically executes a user-specified callback...
Definition: timer.hpp:103
Definition: allocator_common.hpp:24
rclcpp::service::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::callback_group::CallbackGroup::SharedPtr group=nullptr)
Definition: node_impl.hpp:183
std::enable_if< type==ParameterType::PARAMETER_INTEGER, int64_t >::type get_value() const
Definition: parameter.hpp:87
Definition: service.hpp:83
Definition: client.hpp:51
rclcpp::client::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
rcl_client_options_t rcl_client_get_default_options(void)
T dynamic_pointer_cast(T... args)
void register_param_change_callback(CallbackT &&callback)
Register the callback for parameter changes.
Definition: node_impl.hpp:205
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:33
Definition: service.hpp:39
void set(CallbackT callback)
Definition: any_service_callback.hpp:66
rcl_service_options_t rcl_service_get_default_options(void)
rclcpp::timer::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< int64_t, DurationT > period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
Create a timer.
Definition: node_impl.hpp:145
rclcpp::parameter::ParameterVariant get_parameter(const std::string &name) const
Definition: any_service_callback.hpp:34
Definition: parameter.hpp:45