15 #ifndef RCLCPP__NODE_HPP_ 16 #define RCLCPP__NODE_HPP_ 19 #include <condition_variable> 32 #include "rcl_interfaces/msg/list_parameters_result.hpp" 33 #include "rcl_interfaces/msg/parameter_descriptor.hpp" 34 #include "rcl_interfaces/msg/parameter_event.hpp" 35 #include "rcl_interfaces/msg/set_parameters_result.hpp" 138 rclcpp::callback_group::CallbackGroup::SharedPtr
199 typename CallbackMessageT =
211 CallbackT && callback,
215 MessageMemoryStrategyT::create_default()
225 template<
typename DurationRepT =
int64_t,
typename DurationT = std::milli,
typename CallbackT>
230 rclcpp::callback_group::CallbackGroup::SharedPtr group =
nullptr);
233 template<
typename ServiceT>
238 rclcpp::callback_group::CallbackGroup::SharedPtr group =
nullptr);
241 template<
typename ServiceT,
typename CallbackT>
245 CallbackT && callback,
247 rclcpp::callback_group::CallbackGroup::SharedPtr group =
nullptr);
294 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
295 rcl_interfaces::msg::ParameterDescriptor(),
296 bool ignore_override =
false);
319 template<
typename ParameterT>
323 const ParameterT & default_value,
324 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
325 rcl_interfaces::msg::ParameterDescriptor(),
326 bool ignore_override =
false);
364 template<
typename ParameterT>
369 bool ignore_overrides =
false);
378 template<
typename ParameterT>
386 bool ignore_overrides =
false);
442 rcl_interfaces::msg::SetParametersResult
514 rcl_interfaces::msg::SetParametersResult
569 template<
typename ParameterT>
588 template<
typename ParameterT>
592 ParameterT & parameter,
593 const ParameterT & alternative_value)
const;
654 template<
typename ParameterT>
677 rcl_interfaces::msg::ParameterDescriptor
727 rcl_interfaces::msg::ListParametersResult
903 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
908 rclcpp::node_interfaces::NodeClockInterface::SharedPtr
913 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
918 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
923 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
928 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
933 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
938 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
943 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
948 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
1089 group_in_node(callback_group::CallbackGroup::SharedPtr group);
1091 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
1092 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
1093 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
1094 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
1095 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
1096 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
1097 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
1098 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
1099 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
1100 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1109 #ifndef RCLCPP__NODE_IMPL_HPP_ 1114 #endif // RCLCPP__NODE_HPP_
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
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
Definition: logger.hpp:77
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:40
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::callback_group::CallbackGroup::SharedPtr create_callback_group(rclcpp::callback_group::CallbackGroupType group_type)
Create and return a callback group.
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)
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter ¶meter)
Set a single parameter.
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
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.
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
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
Encapsulation of options for node initialization.
Definition: node_options.hpp:34
rclcpp::Clock::SharedPtr get_clock()
std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.
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
OnParametersSetCallbackType set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback)
Register a callback to be called anytime a parameter is about to be changed.
CallbackGroupType
Definition: callback_group.hpp:46
bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
size_t count_subscribers(const std::string &topic_name) const
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
rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
Definition: service.hpp:89
Definition: client.hpp:119
rclcpp::Logger get_logger() const
Get the logger of the node.
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:67
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
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.
const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, one at a time.
rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
OnSetParametersCallbackHandle::OnParametersSetCallbackType OnParametersSetCallbackType
Definition: node_parameters_interface.hpp:174
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:51
void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
RCUTILS_WARN_UNUSED bool assert_liveliness() const
Manually assert that this Node is alive (for RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE).
Definition: node_parameters_interface.hpp:36
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::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.
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
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
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Set the data type used in the intra-process buffer as std::shared_ptr<MessageT>
size_t count_publishers(const std::string &topic_name) const
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeParametersInterface implementation.
std::map< std::string, std::vector< std::string > > get_topic_names_and_types() const
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
#define RCUTILS_WARN_UNUSED
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
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.
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, all at once.
OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)
Add a callback for when parameters are being set.
const char * get_name() const
Get the name of the node.
const char * get_namespace() const
Get the namespace of the node.
const std::vector< rclcpp::callback_group::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
std::map< std::string, std::vector< std::string > > get_service_names_and_types() const
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:72
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.
const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
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.
Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
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
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.