26 #include "rclcpp/detail/qos_parameters.hpp"
27 #include "rclcpp/exceptions.hpp"
28 #include "rclcpp/graph_listener.hpp"
29 #include "rclcpp/node.hpp"
30 #include "rclcpp/node_interfaces/node_base.hpp"
31 #include "rclcpp/node_interfaces/node_clock.hpp"
32 #include "rclcpp/node_interfaces/node_graph.hpp"
33 #include "rclcpp/node_interfaces/node_logging.hpp"
34 #include "rclcpp/node_interfaces/node_parameters.hpp"
35 #include "rclcpp/node_interfaces/node_services.hpp"
36 #include "rclcpp/node_interfaces/node_time_source.hpp"
37 #include "rclcpp/node_interfaces/node_timers.hpp"
38 #include "rclcpp/node_interfaces/node_topics.hpp"
39 #include "rclcpp/node_interfaces/node_waitables.hpp"
40 #include "rclcpp/qos_overriding_options.hpp"
42 #include "rmw/validate_namespace.h"
44 #include "./detail/resolve_parameter_overrides.hpp"
48 using rclcpp::exceptions::throw_from_rcl_error;
55 extend_sub_namespace(
const std::string & existing_sub_namespace,
const std::string & extension)
60 if (extension.empty()) {
64 "sub-nodes should not extend nodes by an empty sub-namespace",
66 }
else if (extension.front() ==
'/') {
71 "a sub-namespace should not have a leading /",
75 std::string new_sub_namespace;
76 if (existing_sub_namespace.empty()) {
77 new_sub_namespace = extension;
79 new_sub_namespace = existing_sub_namespace +
"/" + extension;
83 if (new_sub_namespace.back() ==
'/') {
84 new_sub_namespace = new_sub_namespace.substr(0, new_sub_namespace.size() - 1);
87 return new_sub_namespace;
92 create_effective_namespace(
const std::string & node_namespace,
const std::string & sub_namespace)
100 if (sub_namespace.empty()) {
101 return node_namespace;
102 }
else if (node_namespace.back() ==
'/') {
104 return node_namespace + sub_namespace;
106 return node_namespace +
"/" + sub_namespace;
113 const std::string & node_name,
115 :
Node(node_name,
"", options)
121 get_parameter_events_qos(
128 if (rcl_options->use_global_arguments) {
129 auto context_ptr = node_base.
get_context()->get_rcl_context();
130 global_args = &(context_ptr->global_arguments);
133 auto parameter_overrides = rclcpp::detail::resolve_parameter_overrides(
136 &rcl_options->arguments,
140 auto prefix =
"qos_overrides." + final_topic_name +
".";
141 std::array<rclcpp::QosPolicyKind, 4> policies = {
142 rclcpp::QosPolicyKind::Depth,
143 rclcpp::QosPolicyKind::Durability,
144 rclcpp::QosPolicyKind::History,
145 rclcpp::QosPolicyKind::Reliability,
147 for (
const auto & policy : policies) {
148 auto param_name = prefix + rclcpp::qos_policy_kind_to_cstr(policy);
149 auto it = parameter_overrides.find(param_name);
150 auto value = it != parameter_overrides.end() ?
153 rclcpp::detail::apply_qos_override(policy, value, final_qos);
159 const std::string & node_name,
160 const std::string & namespace_,
162 : node_base_(new
rclcpp::node_interfaces::NodeBase(
166 *(options.get_rcl_node_options()),
167 options.use_intra_process_comms(),
168 options.enable_topic_statistics())),
169 node_graph_(new
rclcpp::node_interfaces::NodeGraph(node_base_.get())),
170 node_logging_(new
rclcpp::node_interfaces::NodeLogging(node_base_.get())),
171 node_timers_(new
rclcpp::node_interfaces::NodeTimers(node_base_.get())),
172 node_topics_(new
rclcpp::node_interfaces::NodeTopics(node_base_.get(), node_timers_.get())),
173 node_services_(new
rclcpp::node_interfaces::NodeServices(node_base_.get())),
174 node_clock_(new
rclcpp::node_interfaces::NodeClock(
181 node_parameters_(new
rclcpp::node_interfaces::NodeParameters(
187 options.parameter_overrides(),
188 options.start_parameter_services(),
189 options.start_parameter_event_publisher(),
192 get_parameter_events_qos(*node_base_, options),
193 options.parameter_event_publisher_options(),
194 options.allow_undeclared_parameters(),
195 options.automatically_declare_parameters_from_overrides()
197 node_time_source_(new
rclcpp::node_interfaces::NodeTimeSource(
206 options.use_clock_thread()
208 node_waitables_(new
rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
209 node_options_(options),
211 effective_namespace_(create_effective_namespace(this->get_namespace(), sub_namespace_))
215 rclcpp::detail::declare_qos_parameters(
218 QosPolicyKind::Depth,
219 QosPolicyKind::Durability,
220 QosPolicyKind::History,
221 QosPolicyKind::Reliability,
224 node_topics_->resolve_topic_name(
"/parameter_events"),
231 const std::string & sub_namespace)
232 : node_base_(other.node_base_),
233 node_graph_(other.node_graph_),
234 node_logging_(other.node_logging_),
235 node_timers_(other.node_timers_),
236 node_topics_(other.node_topics_),
237 node_services_(other.node_services_),
238 node_clock_(other.node_clock_),
239 node_parameters_(other.node_parameters_),
240 node_time_source_(other.node_time_source_),
241 node_waitables_(other.node_waitables_),
242 node_options_(other.node_options_),
243 sub_namespace_(extend_sub_namespace(other.get_sub_namespace(), sub_namespace)),
244 effective_namespace_(create_effective_namespace(other.get_namespace(), sub_namespace_))
247 int validation_result;
248 size_t invalid_index;
250 rmw_validate_namespace(effective_namespace_.c_str(), &validation_result, &invalid_index);
252 if (rmw_ret != RMW_RET_OK) {
253 if (rmw_ret == RMW_RET_INVALID_ARGUMENT) {
256 throw_from_rcl_error(
RCL_RET_ERROR,
"failed to validate subnode namespace");
259 if (validation_result != RMW_NAMESPACE_VALID) {
261 effective_namespace_.c_str(),
262 rmw_namespace_validation_result_string(validation_result),
270 node_waitables_.reset();
271 node_time_source_.reset();
272 node_parameters_.reset();
274 node_services_.reset();
275 node_topics_.reset();
276 node_timers_.reset();
277 node_logging_.reset();
284 return node_base_->get_name();
290 return node_base_->get_namespace();
296 return node_base_->get_fully_qualified_name();
302 return node_logging_->get_logger();
305 rclcpp::CallbackGroup::SharedPtr
307 rclcpp::CallbackGroupType group_type,
308 bool automatically_add_to_executor_with_node)
310 return node_base_->create_callback_group(group_type, automatically_add_to_executor_with_node);
315 const std::string & name,
317 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
318 bool ignore_override)
320 return this->node_parameters_->declare_parameter(
323 parameter_descriptor,
329 const std::string & name,
330 rclcpp::ParameterType type,
331 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
332 bool ignore_override)
334 return this->node_parameters_->declare_parameter(
337 parameter_descriptor,
344 this->node_parameters_->undeclare_parameter(name);
350 return this->node_parameters_->has_parameter(name);
353 rcl_interfaces::msg::SetParametersResult
359 std::vector<rcl_interfaces::msg::SetParametersResult>
362 return node_parameters_->set_parameters(parameters);
365 rcl_interfaces::msg::SetParametersResult
368 return node_parameters_->set_parameters_atomically(parameters);
374 return node_parameters_->get_parameter(name);
380 return node_parameters_->get_parameter(name, parameter);
383 std::vector<rclcpp::Parameter>
385 const std::vector<std::string> & names)
const
387 return node_parameters_->get_parameters(names);
390 rcl_interfaces::msg::ParameterDescriptor
393 auto result = node_parameters_->describe_parameters({name});
394 if (0 == result.size()) {
397 if (result.size() > 1) {
398 throw std::runtime_error(
"number of described parameters unexpectedly more than one");
400 return result.front();
403 std::vector<rcl_interfaces::msg::ParameterDescriptor>
406 return node_parameters_->describe_parameters(names);
412 return node_parameters_->get_parameter_types(names);
415 rcl_interfaces::msg::ListParametersResult
418 return node_parameters_->list_parameters(prefixes, depth);
421 rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr
424 return node_parameters_->add_on_set_parameters_callback(callback);
430 return node_parameters_->remove_on_set_parameters_callback(callback);
433 std::vector<std::string>
436 return node_graph_->get_node_names();
439 std::map<std::string, std::vector<std::string>>
442 return node_graph_->get_topic_names_and_types();
445 std::map<std::string, std::vector<std::string>>
448 return node_graph_->get_service_names_and_types();
451 std::map<std::string, std::vector<std::string>>
453 const std::string & node_name,
454 const std::string & namespace_)
const
456 return node_graph_->get_service_names_and_types_by_node(
457 node_name, namespace_);
463 return node_graph_->count_publishers(topic_name);
469 return node_graph_->count_subscribers(topic_name);
472 std::vector<rclcpp::TopicEndpointInfo>
475 return node_graph_->get_publishers_info_by_topic(topic_name, no_mangle);
478 std::vector<rclcpp::TopicEndpointInfo>
481 return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle);
486 const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func)
488 node_base_->for_each_callback_group(func);
491 rclcpp::Event::SharedPtr
494 return node_graph_->get_graph_event();
499 rclcpp::Event::SharedPtr event,
500 std::chrono::nanoseconds timeout)
502 node_graph_->wait_for_graph_change(event, timeout);
505 rclcpp::Clock::SharedPtr
508 return node_clock_->get_clock();
511 rclcpp::Clock::ConstSharedPtr
514 return node_clock_->get_clock();
520 return node_clock_->get_clock()->now();
523 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
529 rclcpp::node_interfaces::NodeClockInterface::SharedPtr
535 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
541 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
544 return node_logging_;
547 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
550 return node_time_source_;
553 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
559 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
565 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
568 return node_services_;
571 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
574 return node_parameters_;
577 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
580 return node_waitables_;
586 return this->sub_namespace_;
592 return this->effective_namespace_;
600 return std::shared_ptr<Node>(
new Node(*
this, sub_namespace));
606 return this->node_options_;
Encapsulation of options for node initialization.
RCLCPP_PUBLIC const rclcpp::QoS & parameter_event_qos() const
Return a reference to the parameter_event_qos QoS.
RCLCPP_PUBLIC std::vector< rclcpp::Parameter > & parameter_overrides()
Return a reference to the list of parameter overrides.
RCLCPP_PUBLIC const rcl_node_options_t * get_rcl_node_options() const
Return the rcl_node_options used by the node.
Node is the single point of entry for creating publishers and subscribers.
RCLCPP_PUBLIC rclcpp::Logger get_logger() const
Get the logger of the node.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
RCLCPP_PUBLIC std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
RCLCPP_PUBLIC bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
RCLCPP_PUBLIC 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_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter ¶meter)
Set a single parameter.
RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
RCLCPP_PUBLIC 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.
RCLCPP_PUBLIC 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.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
RCLCPP_PUBLIC const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
RCLCPP_PUBLIC size_t count_publishers(const std::string &topic_name) const
Return the number of publishers created for a given topic.
RCLCPP_PUBLIC 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.
RCLCPP_PUBLIC size_t count_subscribers(const std::string &topic_name) const
Return the number of subscribers created for a given topic.
RCLCPP_PUBLIC 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_PUBLIC Time now() const
Returns current time from the time source specified by clock_type.
RCLCPP_PUBLIC rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
RCLCPP_PUBLIC void for_each_callback_group(const node_interfaces::NodeBaseInterface::CallbackGroupFunction &func)
Iterate over the callback groups in the node, calling the given function on each valid one.
RCLCPP_PUBLIC rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
RCLCPP_PUBLIC void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
RCLCPP_PUBLIC 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.
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
RCLCPP_PUBLIC Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
RCLCPP_PUBLIC const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, all at once.
RCLCPP_PUBLIC 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_PUBLIC rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
RCLCPP_PUBLIC const char * get_name() const
Get the name of the node.
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)
Add a callback for when parameters are being set.
RCLCPP_PUBLIC std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, one at a time.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
RCLCPP_PUBLIC 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 a map of existing service names to list of service types for a specific node.
RCLCPP_PUBLIC void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
RCLCPP_PUBLIC 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_PUBLIC 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.
RCLCPP_PUBLIC rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node=true)
Create and return a callback group.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeTimeSourceInterface implementation.
RCLCPP_PUBLIC 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_PUBLIC const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
RCLCPP_PUBLIC const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
RCLCPP_PUBLIC std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.
RCLCPP_PUBLIC const char * get_namespace() const
Get the namespace of the node.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
Store the type and value of a parameter.
Structure to store an arbitrary parameter with templated get/set methods.
Encapsulation of Quality of Service settings.
Options that are passed in subscription/publisher constructor to specify QoSConfigurability.
Thrown when a node namespace is invalid.
Thrown when a any kind of name (node, namespace, topic, etc.) is invalid.
Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
Pure virtual interface class for the NodeBase part of the Node API.
virtual RCLCPP_PUBLIC std::string resolve_topic_or_service_name(const std::string &name, bool is_service, bool only_expand=false) const =0
Expand and remap a given topic or service name.
virtual RCLCPP_PUBLIC const char * get_fully_qualified_name() const =0
Return the fully qualified name of the node.
virtual RCLCPP_PUBLIC rclcpp::Context::SharedPtr get_context()=0
Return the context of the node.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
Hold output of parsing command line arguments.
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
#define RCL_RET_ERROR
Unspecified error return code.