26 #include "rclcpp/create_generic_client.hpp"
27 #include "rclcpp/detail/qos_parameters.hpp"
28 #include "rclcpp/exceptions.hpp"
29 #include "rclcpp/graph_listener.hpp"
30 #include "rclcpp/node.hpp"
31 #include "rclcpp/node_interfaces/node_base.hpp"
32 #include "rclcpp/node_interfaces/node_clock.hpp"
33 #include "rclcpp/node_interfaces/node_graph.hpp"
34 #include "rclcpp/node_interfaces/node_logging.hpp"
35 #include "rclcpp/node_interfaces/node_parameters.hpp"
36 #include "rclcpp/node_interfaces/node_services.hpp"
37 #include "rclcpp/node_interfaces/node_time_source.hpp"
38 #include "rclcpp/node_interfaces/node_timers.hpp"
39 #include "rclcpp/node_interfaces/node_topics.hpp"
40 #include "rclcpp/node_interfaces/node_type_descriptions.hpp"
41 #include "rclcpp/node_interfaces/node_waitables.hpp"
42 #include "rclcpp/qos_overriding_options.hpp"
44 #include "rmw/validate_namespace.h"
46 #include "./detail/resolve_parameter_overrides.hpp"
50 using rclcpp::exceptions::throw_from_rcl_error;
57 extend_sub_namespace(
const std::string & existing_sub_namespace,
const std::string & extension)
62 if (extension.empty()) {
66 "sub-nodes should not extend nodes by an empty sub-namespace",
68 }
else if (extension.front() ==
'/') {
73 "a sub-namespace should not have a leading /",
77 std::string new_sub_namespace;
78 if (existing_sub_namespace.empty()) {
79 new_sub_namespace = extension;
81 new_sub_namespace = existing_sub_namespace +
"/" + extension;
85 if (new_sub_namespace.back() ==
'/') {
86 new_sub_namespace = new_sub_namespace.substr(0, new_sub_namespace.size() - 1);
89 return new_sub_namespace;
94 create_effective_namespace(
const std::string & node_namespace,
const std::string & sub_namespace)
102 if (sub_namespace.empty()) {
103 return node_namespace;
104 }
else if (node_namespace.back() ==
'/') {
106 return node_namespace + sub_namespace;
108 return node_namespace +
"/" + sub_namespace;
131 const std::string & node_name,
133 :
Node(node_name,
"", options)
139 get_parameter_events_qos(
146 if (rcl_options->use_global_arguments) {
147 auto context_ptr = node_base.
get_context()->get_rcl_context();
148 global_args = &(context_ptr->global_arguments);
151 auto parameter_overrides = rclcpp::detail::resolve_parameter_overrides(
154 &rcl_options->arguments,
158 auto prefix =
"qos_overrides." + final_topic_name +
".";
159 std::array<rclcpp::QosPolicyKind, 4> policies = {
160 rclcpp::QosPolicyKind::Depth,
161 rclcpp::QosPolicyKind::Durability,
162 rclcpp::QosPolicyKind::History,
163 rclcpp::QosPolicyKind::Reliability,
165 for (
const auto & policy : policies) {
166 auto param_name = prefix + rclcpp::qos_policy_kind_to_cstr(policy);
167 auto it = parameter_overrides.find(param_name);
168 auto value = it != parameter_overrides.end() ?
171 rclcpp::detail::apply_qos_override(policy, value, final_qos);
177 const std::string & node_name,
178 const std::string & namespace_,
180 : node_base_(new
rclcpp::node_interfaces::NodeBase(
184 *(options.get_rcl_node_options()),
185 options.use_intra_process_comms(),
186 options.enable_topic_statistics())),
187 node_graph_(new
rclcpp::node_interfaces::NodeGraph(node_base_.get())),
188 node_logging_(new
rclcpp::node_interfaces::NodeLogging(node_base_)),
189 node_timers_(new
rclcpp::node_interfaces::NodeTimers(node_base_.get())),
190 node_topics_(new
rclcpp::node_interfaces::NodeTopics(node_base_.get(), node_timers_.get())),
191 node_services_(new
rclcpp::node_interfaces::NodeServices(node_base_.get())),
192 node_clock_(new
rclcpp::node_interfaces::NodeClock(
200 node_parameters_(new
rclcpp::node_interfaces::NodeParameters(
206 options.parameter_overrides(),
207 options.start_parameter_services(),
208 options.start_parameter_event_publisher(),
211 get_parameter_events_qos(*node_base_, options),
212 options.parameter_event_publisher_options(),
213 options.allow_undeclared_parameters(),
214 options.automatically_declare_parameters_from_overrides()
216 node_time_source_(new
rclcpp::node_interfaces::NodeTimeSource(
225 options.use_clock_thread()
227 node_type_descriptions_(new
rclcpp::node_interfaces::NodeTypeDescriptions(
233 node_waitables_(new
rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
234 node_options_(options),
236 effective_namespace_(create_effective_namespace(this->get_namespace(), sub_namespace_))
240 rclcpp::detail::declare_qos_parameters(
243 QosPolicyKind::Depth,
244 QosPolicyKind::Durability,
245 QosPolicyKind::History,
246 QosPolicyKind::Reliability,
249 node_topics_->resolve_topic_name(
"/parameter_events"),
254 node_logging_->create_logger_services(node_services_);
260 const std::string & sub_namespace)
261 : node_base_(other.node_base_),
262 node_graph_(other.node_graph_),
263 node_logging_(other.node_logging_),
264 node_timers_(other.node_timers_),
265 node_topics_(other.node_topics_),
266 node_services_(other.node_services_),
267 node_clock_(other.node_clock_),
268 node_parameters_(other.node_parameters_),
269 node_time_source_(other.node_time_source_),
270 node_waitables_(other.node_waitables_),
271 node_options_(other.node_options_),
272 sub_namespace_(extend_sub_namespace(other.get_sub_namespace(), sub_namespace)),
273 effective_namespace_(create_effective_namespace(other.get_namespace(), sub_namespace_)),
274 hidden_impl_(other.hidden_impl_)
277 int validation_result;
278 size_t invalid_index;
280 rmw_validate_namespace(effective_namespace_.c_str(), &validation_result, &invalid_index);
282 if (rmw_ret != RMW_RET_OK) {
283 if (rmw_ret == RMW_RET_INVALID_ARGUMENT) {
286 throw_from_rcl_error(
RCL_RET_ERROR,
"failed to validate subnode namespace");
289 if (validation_result != RMW_NAMESPACE_VALID) {
291 effective_namespace_.c_str(),
292 rmw_namespace_validation_result_string(validation_result),
300 node_waitables_.reset();
301 node_time_source_.reset();
302 node_parameters_.reset();
304 node_services_.reset();
305 node_topics_.reset();
306 node_timers_.reset();
307 node_logging_.reset();
314 return node_base_->get_name();
320 return node_base_->get_namespace();
326 return node_base_->get_fully_qualified_name();
332 return node_logging_->get_logger();
335 rclcpp::CallbackGroup::SharedPtr
337 rclcpp::CallbackGroupType group_type,
338 bool automatically_add_to_executor_with_node)
340 return node_base_->create_callback_group(group_type, automatically_add_to_executor_with_node);
345 const std::string & name,
347 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
348 bool ignore_override)
350 return this->node_parameters_->declare_parameter(
353 parameter_descriptor,
359 const std::string & name,
360 rclcpp::ParameterType type,
361 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
362 bool ignore_override)
364 return this->node_parameters_->declare_parameter(
367 parameter_descriptor,
374 this->node_parameters_->undeclare_parameter(name);
380 return this->node_parameters_->has_parameter(name);
383 rcl_interfaces::msg::SetParametersResult
386 return node_parameters_->set_parameters_atomically({parameter});
389 std::vector<rcl_interfaces::msg::SetParametersResult>
392 return node_parameters_->set_parameters(parameters);
395 rcl_interfaces::msg::SetParametersResult
398 return node_parameters_->set_parameters_atomically(parameters);
404 return node_parameters_->get_parameter(name);
410 return node_parameters_->get_parameter(name, parameter);
413 std::vector<rclcpp::Parameter>
415 const std::vector<std::string> & names)
const
417 return node_parameters_->get_parameters(names);
420 rcl_interfaces::msg::ParameterDescriptor
423 auto result = node_parameters_->describe_parameters({name});
424 if (0 == result.size()) {
427 if (result.size() > 1) {
428 throw std::runtime_error(
"number of described parameters unexpectedly more than one");
430 return result.front();
433 std::vector<rcl_interfaces::msg::ParameterDescriptor>
436 return node_parameters_->describe_parameters(names);
442 return node_parameters_->get_parameter_types(names);
445 rcl_interfaces::msg::ListParametersResult
448 return node_parameters_->list_parameters(prefixes, depth);
451 rclcpp::Node::PreSetParametersCallbackHandle::SharedPtr
454 return node_parameters_->add_pre_set_parameters_callback(callback);
457 rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr
460 return node_parameters_->add_on_set_parameters_callback(callback);
463 rclcpp::Node::PostSetParametersCallbackHandle::SharedPtr
466 return node_parameters_->add_post_set_parameters_callback(callback);
472 node_parameters_->remove_pre_set_parameters_callback(handler);
478 node_parameters_->remove_on_set_parameters_callback(handler);
484 node_parameters_->remove_post_set_parameters_callback(handler);
487 std::vector<std::string>
493 std::map<std::string, std::vector<std::string>>
499 std::map<std::string, std::vector<std::string>>
505 std::map<std::string, std::vector<std::string>>
507 const std::string & node_name,
508 const std::string & namespace_)
const
511 node_name, namespace_);
538 std::vector<rclcpp::TopicEndpointInfo>
544 std::vector<rclcpp::TopicEndpointInfo>
552 const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func)
554 node_base_->for_each_callback_group(func);
557 rclcpp::Event::SharedPtr
565 rclcpp::Event::SharedPtr event,
566 std::chrono::nanoseconds timeout)
571 rclcpp::Clock::SharedPtr
574 return node_clock_->get_clock();
577 rclcpp::Clock::ConstSharedPtr
580 return node_clock_->get_clock();
586 return node_clock_->get_clock()->now();
589 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
595 rclcpp::node_interfaces::NodeClockInterface::SharedPtr
601 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
607 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
610 return node_logging_;
613 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
616 return node_time_source_;
619 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
625 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
631 rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr
634 return node_type_descriptions_;
637 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
640 return node_services_;
643 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
646 return node_parameters_;
649 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
652 return node_waitables_;
658 return this->sub_namespace_;
664 return this->effective_namespace_;
672 return std::shared_ptr<Node>(
new Node(*
this, sub_namespace));
678 return this->node_options_;
681 rclcpp::GenericClient::SharedPtr
683 const std::string & service_name,
684 const std::string & service_type,
686 rclcpp::CallbackGroup::SharedPtr group)
Internal implementation to provide hidden and API/ABI stable changes to the Node.
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 bool enable_logger_service() const
Return the enable_logger_service flag.
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 RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnSetParametersCallbackType callback)
Add a callback to validate parameters before they are set.
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 node clock.
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 size_t count_services(const std::string &service_name) const
Return the number of services created for a given service.
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 rclcpp::GenericClient::SharedPtr create_generic_client(const std::string &service_name, const std::string &service_type, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a GenericClient.
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 void remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle *const handler)
Remove a callback registered with add_pre_set_parameters_callback.
RCLCPP_PUBLIC const char * get_name() const
Get the name of the node.
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::NodeTypeDescriptionsInterface::SharedPtr get_node_type_descriptions_interface()
Return the Node's internal NodeTypeDescriptionsInterface implementation.
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 RCUTILS_WARN_UNUSED PreSetParametersCallbackHandle::SharedPtr add_pre_set_parameters_callback(PreSetParametersCallbackType callback)
Add a callback that gets triggered before parameters are validated.
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 size_t count_clients(const std::string &service_name) const
Return the number of clients created for a given service.
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 RCUTILS_WARN_UNUSED PostSetParametersCallbackHandle::SharedPtr add_post_set_parameters_callback(PostSetParametersCallbackType callback)
Add a callback that gets triggered after parameters are set successfully.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
RCLCPP_PUBLIC void remove_post_set_parameters_callback(const PostSetParametersCallbackHandle *const handler)
Remove a callback registered with add_post_set_parameters_callback.
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.
RCLCPP_PUBLIC rclcpp::GenericClient::SharedPtr create_generic_client(std::shared_ptr< node_interfaces::NodeBaseInterface > node_base, std::shared_ptr< node_interfaces::NodeGraphInterface > node_graph, std::shared_ptr< node_interfaces::NodeServicesInterface > node_services, const std::string &service_name, const std::string &service_type, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create a generic service client with a name of given type.
Hold output of parsing command line arguments.
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
#define RCL_RET_ERROR
Unspecified error return code.