rclcpp
master
C++ ROS Client Library API
|
Go to the documentation of this file.
15 #ifndef RCLCPP__NODE_HPP_
16 #define RCLCPP__NODE_HPP_
19 #include <condition_variable>
32 #include "rcl/error_handling.h"
35 #include "rcl_interfaces/msg/list_parameters_result.hpp"
36 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
37 #include "rcl_interfaces/msg/parameter_event.hpp"
38 #include "rcl_interfaces/msg/set_parameters_result.hpp"
146 rclcpp::CallbackGroup::SharedPtr
149 bool automatically_add_to_executor_with_node =
true);
209 typename CallbackMessageT =
221 CallbackT && callback,
224 typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
225 MessageMemoryStrategyT::create_default()
235 template<
typename DurationRepT =
int64_t,
typename DurationT = std::milli,
typename CallbackT>
240 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
249 template<
typename ServiceT>
254 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
264 template<
typename ServiceT,
typename CallbackT>
268 CallbackT && callback,
270 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
285 template<
typename AllocatorT = std::allocator<
void>>
310 template<
typename AllocatorT = std::allocator<
void>>
368 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
369 rcl_interfaces::msg::ParameterDescriptor(),
370 bool ignore_override =
false);
393 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
394 rcl_interfaces::msg::ParameterDescriptor{},
395 bool ignore_override =
false);
399 "declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \
400 "If you want to declare a parameter that won't change type without a default value use:\n" \
401 "`node->declare_parameter<ParameterT>(name)`, where e.g. ParameterT=int64_t.\n\n" \
402 "If you want to declare a parameter that can dynamically change type use:\n" \
404 "rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
405 "descriptor.dynamic_typing = true;\n" \
406 "node->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \
434 template<
typename ParameterT>
438 const ParameterT & default_value,
439 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
440 rcl_interfaces::msg::ParameterDescriptor(),
441 bool ignore_override =
false);
447 template<
typename ParameterT>
451 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
452 rcl_interfaces::msg::ParameterDescriptor(),
453 bool ignore_override =
false);
491 template<
typename ParameterT>
496 bool ignore_overrides =
false);
505 template<
typename ParameterT>
513 bool ignore_overrides =
false);
569 rcl_interfaces::msg::SetParametersResult
641 rcl_interfaces::msg::SetParametersResult
696 template<
typename ParameterT>
715 template<
typename ParameterT>
719 ParameterT & parameter,
720 const ParameterT & alternative_value)
const;
781 template<
typename ParameterT>
805 rcl_interfaces::msg::ParameterDescriptor
856 rcl_interfaces::msg::ListParametersResult
930 OnSetParametersCallbackHandle::SharedPtr
1078 rclcpp::Event::SharedPtr
1095 rclcpp::Event::SharedPtr event,
1103 rclcpp::Clock::SharedPtr
1111 rclcpp::Clock::ConstSharedPtr
1124 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
1129 rclcpp::node_interfaces::NodeClockInterface::SharedPtr
1134 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
1139 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
1144 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
1149 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
1154 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
1159 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
1164 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
1169 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
1271 rclcpp::Node::SharedPtr
1295 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
1296 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
1297 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
1298 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
1299 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
1300 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
1301 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
1302 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
1303 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
1304 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1313 #ifndef RCLCPP__NODE_IMPL_HPP_
1318 #endif // RCLCPP__NODE_HPP_
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, all at once.
const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
Time now() const
Returns current time from the time source specified by clock_type.
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:53
const std::vector< rclcpp::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
std::vector< rclcpp::TopicEndpointInfo > get_publishers_info_by_topic(const std::string &topic_name, bool no_mangle=false) const
Return the topic endpoint information about publishers on a given topic.
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const
Return a list of parameters with any of the given prefixes, up to the given depth.
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
rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
Definition: service.hpp:144
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
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
size_t count_publishers(const std::string &topic_name) const
Return the number of publishers created for a given topic.
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
rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
const char * get_namespace() const
Get the namespace of the node.
CallbackGroupType
Definition: callback_group.hpp:43
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
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Definition: node_parameters_interface.hpp:36
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
const char * get_name() const
Get the name of the node.
const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
rclcpp::Logger get_logger() const
Get the logger of the node.
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
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
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:77
rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node=true)
Create and return a callback group.
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, one at a time.
Definition: logger.hpp:91
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
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
std::map< std::string, std::vector< std::string > > get_service_names_and_types() const
Return a map of existing service names to list of service types.
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
void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
size_t count_subscribers(const std::string &topic_name) const
Return the number of subscribers created for a given topic.
#define RCUTILS_WARN_UNUSED
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
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
ParameterType
Definition: parameter_value.hpp:32
Structure containing optional configuration for Publishers.
Definition: publisher_options.hpp:65
Definition: client.hpp:178
std::map< std::string, std::vector< std::string > > get_topic_names_and_types() const
Return a map of existing topic names to list of topic types.
const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:41
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const
Return a vector of parameter types, one for each of the given names.
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
Encapsulation of options for node initialization.
Definition: node_options.hpp:34
Definition: timer.hpp:259
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeTimeSourceInterface implementation.
void wait_for_graph_change(rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout)
Wait for a graph event to occur by waiting on an Event to become set.
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:52
rclcpp::Node::SharedPtr create_sub_node(const std::string &sub_namespace)
Create a sub-node, which will extend the namespace of all entities created with it.
std::vector< rclcpp::TopicEndpointInfo > get_subscriptions_info_by_topic(const std::string &topic_name, bool no_mangle=false) const
Return the topic endpoint information about subscriptions on a given topic.
rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter ¶meter)
Set a single parameter.
std::map< std::string, std::vector< std::string > > get_service_names_and_types_by_node(const std::string &node_name, const std::string &namespace_) const
Return the number of publishers that are advertised on a given topic.
RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)
Add a callback for when parameters are being set.
OnSetParametersCallbackHandle::OnParametersSetCallbackType OnParametersSetCallbackType
Definition: node_parameters_interface.hpp:208
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const
Return a vector of parameter descriptors, one for each of the given names.
void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.