rclcpp
master
C++ ROS Client Library API
|
Go to the documentation of this file.
15 #ifndef RCLCPP__NODE_IMPL_HPP_
16 #define RCLCPP__NODE_IMPL_HPP_
52 #ifndef RCLCPP__NODE_HPP_
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>
78 return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
89 typename CallbackMessageT,
90 typename SubscriptionT,
91 typename MessageMemoryStrategyT>
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>
114 rclcpp::CallbackGroup::SharedPtr group)
120 this->node_base_.get(),
121 this->node_timers_.get());
124 template<
typename ServiceT>
129 rclcpp::CallbackGroup::SharedPtr group)
131 return rclcpp::create_client<ServiceT>(
140 template<
typename ServiceT,
typename CallbackT>
144 CallbackT && callback,
146 rclcpp::CallbackGroup::SharedPtr group)
148 return rclcpp::create_service<ServiceT, CallbackT>(
152 std::forward<CallbackT>(callback),
157 template<
typename AllocatorT>
174 template<
typename AllocatorT>
194 template<
typename ParameterT>
198 const ParameterT & default_value,
199 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
200 bool ignore_override)
206 parameter_descriptor,
214 template<
typename ParameterT>
218 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
219 bool ignore_override)
227 parameter_descriptor,
232 template<
typename ParameterT>
237 bool ignore_overrides)
240 std::string normalized_namespace = namespace_.
empty() ?
"" : (namespace_ +
".");
243 [
this, &normalized_namespace, ignore_overrides](
auto element) {
244 return this->declare_parameter(
245 normalized_namespace + element.first,
247 rcl_interfaces::msg::ParameterDescriptor(),
254 template<
typename ParameterT>
262 bool ignore_overrides)
265 std::string normalized_namespace = namespace_.
empty() ?
"" : (namespace_ +
".");
268 [
this, &normalized_namespace, ignore_overrides](
auto element) {
269 return static_cast<ParameterT>(
270 this->declare_parameter(
271 normalized_namespace + element.first,
272 element.second.first,
273 element.second.second,
281 template<
typename ParameterT>
291 parameter =
static_cast<ParameterT
>(parameter_variant.
get_value<ParameterT>());
297 template<
typename ParameterT>
301 ParameterT & parameter,
302 const ParameterT & alternative_value)
const
307 if (!got_parameter) {
308 parameter = alternative_value;
310 return got_parameter;
316 template<
typename ParameterT>
323 bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
325 for (
const auto & param : params) {
326 values[param.first] =
static_cast<ParameterT
>(param.second.get_value<ParameterT>());
335 #endif // RCLCPP__NODE_IMPL_HPP_
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
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.
Definition: create_timer.hpp:90
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.
Definition: create_generic_publisher.hpp:45
#define RCLCPP_LOCAL
Definition: visibility_control.hpp:51
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create a timer.
Definition: node_impl.hpp:111
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL, const bool & >::type get() const
Definition: parameter_value.hpp:148
T back_inserter(T... args)
decltype(auto) get_value() const
Get value of parameter using rclcpp::ParameterType as template argument.
Definition: parameter.hpp:117
Definition: service.hpp:144
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:93
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.
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:87
Indicate the parameter type does not match the expected type.
Definition: parameter_value.hpp:56
RCLCPP_LOCAL std::string extend_name_with_sub_namespace(const std::string &name, const std::string &sub_namespace)
Definition: node_impl.hpp:62
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
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:73
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
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.
Definition: node_impl.hpp:176
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.
Definition: node_impl.hpp:142
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.
Definition: node_impl.hpp:159
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:299
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.
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:234
Structure containing optional configuration for Publishers.
Definition: publisher_options.hpp:65
Definition: client.hpp:178
const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
Definition: timer.hpp:259
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:52
Thrown if requested parameter type is invalid.
Definition: exceptions.hpp:243
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.
Definition: create_generic_subscription.hpp:49