15 #ifndef RCLCPP__NODE_IMPL_HPP_ 16 #define RCLCPP__NODE_IMPL_HPP_ 36 #include "rcl_interfaces/msg/intra_process_message.hpp" 48 #ifndef RCLCPP__NODE_HPP_ 61 if (sub_namespace !=
"" && name.
front() !=
'/' && name.
front() !=
'~') {
62 name_with_sub_namespace = sub_namespace +
"/" + name;
64 return name_with_sub_namespace;
67 template<
typename MessageT,
typename AllocatorT,
typename PublisherT>
74 return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
85 typename CallbackMessageT,
86 typename SubscriptionT,
87 typename MessageMemoryStrategyT>
92 CallbackT && callback,
96 return rclcpp::create_subscription<MessageT>(
100 std::forward<CallbackT>(callback),
105 template<
typename DurationRepT,
typename DurationT,
typename CallbackT>
110 rclcpp::callback_group::CallbackGroup::SharedPtr group)
113 std::chrono::duration_cast<std::chrono::nanoseconds>(period),
115 this->node_base_->get_context());
116 node_timers_->add_timer(timer, group);
120 template<
typename ServiceT>
125 rclcpp::callback_group::CallbackGroup::SharedPtr group)
127 return rclcpp::create_client<ServiceT>(
136 template<
typename ServiceT,
typename CallbackT>
140 CallbackT && callback,
142 rclcpp::callback_group::CallbackGroup::SharedPtr group)
144 return rclcpp::create_service<ServiceT, CallbackT>(
148 std::forward<CallbackT>(callback),
153 template<
typename ParameterT>
157 const ParameterT & default_value,
158 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
159 bool ignore_override)
164 parameter_descriptor,
169 template<
typename ParameterT>
174 bool ignore_overrides)
177 std::string normalized_namespace = namespace_.
empty() ?
"" : (namespace_ +
".");
180 [
this, &normalized_namespace, ignore_overrides](
auto element) {
182 normalized_namespace + element.first,
184 rcl_interfaces::msg::ParameterDescriptor(),
191 template<
typename ParameterT>
199 bool ignore_overrides)
202 std::string normalized_namespace = namespace_.
empty() ?
"" : (namespace_ +
".");
205 [
this, &normalized_namespace, ignore_overrides](
auto element) {
206 return static_cast<ParameterT
>(
208 normalized_namespace + element.first,
209 element.second.first,
210 element.second.second,
218 template<
typename ParameterT>
228 parameter =
static_cast<ParameterT
>(parameter_variant.
get_value<ParameterT>());
234 template<
typename ParameterT>
238 ParameterT & parameter,
239 const ParameterT & alternative_value)
const 244 if (!got_parameter) {
245 parameter = alternative_value;
247 return got_parameter;
253 template<
typename ParameterT>
260 bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
262 for (
const auto & param : params) {
263 values[param.first] =
static_cast<ParameterT
>(param.second.get_value<ParameterT>());
272 #endif // RCLCPP__NODE_IMPL_HPP_ 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.
Definition: node_impl.hpp:171
rclcpp::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)
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".
Definition: node_impl.hpp:236
Encapsulation of Quality of Service settings.
Definition: qos.hpp:55
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:51
Definition: timer.hpp:214
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.
Definition: node_impl.hpp:89
const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
Definition: service.hpp:89
RCLCPP_LOCAL std::string extend_name_with_sub_namespace(const std::string &name, const std::string &sub_namespace)
Definition: node_impl.hpp:58
Definition: client.hpp:119
decltype(auto) get_value() const
Get value of parameter using rclcpp::ParameterType as template argument.
Definition: parameter.hpp:109
const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value=rclcpp::ParameterValue(), const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
#define RCLCPP_LOCAL
Definition: visibility_control.hpp:51
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.
Definition: node_impl.hpp:69
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
Create a timer.
Definition: node_impl.hpp:107
Set the data type used in the intra-process buffer as std::shared_ptr<MessageT>
T back_inserter(T... args)
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL, const bool & >::type get() const
Definition: parameter_value.hpp:148
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
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::callback_group::CallbackGroup::SharedPtr group=nullptr)
Definition: node_impl.hpp:138