ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
node.cpp
1 // Copyright 2015 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <algorithm>
16 #include <array>
17 #include <limits>
18 #include <map>
19 #include <memory>
20 #include <string>
21 #include <utility>
22 #include <vector>
23 
24 #include "rcl/arguments.h"
25 
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"
43 
44 #include "rmw/validate_namespace.h"
45 
46 #include "./detail/resolve_parameter_overrides.hpp"
47 
48 using rclcpp::Node;
50 using rclcpp::exceptions::throw_from_rcl_error;
51 
52 namespace
53 {
54 
55 RCLCPP_LOCAL
56 std::string
57 extend_sub_namespace(const std::string & existing_sub_namespace, const std::string & extension)
58 {
59  // Assumption is that the existing_sub_namespace does not need checking
60  // because it would be checked already when it was set with this function.
61 
62  if (extension.empty()) {
64  "sub_namespace",
65  extension.c_str(),
66  "sub-nodes should not extend nodes by an empty sub-namespace",
67  0);
68  } else if (extension.front() == '/') {
69  // check if the new sub-namespace extension is absolute
71  "sub_namespace",
72  extension.c_str(),
73  "a sub-namespace should not have a leading /",
74  0);
75  }
76 
77  std::string new_sub_namespace;
78  if (existing_sub_namespace.empty()) {
79  new_sub_namespace = extension;
80  } else {
81  new_sub_namespace = existing_sub_namespace + "/" + extension;
82  }
83 
84  // remove any trailing `/` so that new extensions do not result in `//`
85  if (new_sub_namespace.back() == '/') {
86  new_sub_namespace = new_sub_namespace.substr(0, new_sub_namespace.size() - 1);
87  }
88 
89  return new_sub_namespace;
90 }
91 
92 RCLCPP_LOCAL
93 std::string
94 create_effective_namespace(const std::string & node_namespace, const std::string & sub_namespace)
95 {
96  // Assumption is that both the node_namespace and sub_namespace are conforming
97  // and do not need trimming of `/` and other things, as they were validated
98  // in other functions already.
99 
100  // A node may not have a sub_namespace if it is no sub_node. In this case,
101  // just return the original namespace
102  if (sub_namespace.empty()) {
103  return node_namespace;
104  } else if (node_namespace.back() == '/') {
105  // this is the special case where node_namespace is just `/`
106  return node_namespace + sub_namespace;
107  } else {
108  return node_namespace + "/" + sub_namespace;
109  }
110 }
111 
112 } // namespace
113 
115 
124 {
125 public:
126  NodeImpl() = default;
127  ~NodeImpl() = default;
128 };
129 
130 Node::Node(
131  const std::string & node_name,
132  const NodeOptions & options)
133 : Node(node_name, "", options)
134 {
135 }
136 
137 static
139 get_parameter_events_qos(
141  const rclcpp::NodeOptions & options)
142 {
143  auto final_qos = options.parameter_event_qos();
144  const rcl_arguments_t * global_args = nullptr;
145  auto * rcl_options = options.get_rcl_node_options();
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);
149  }
150 
151  auto parameter_overrides = rclcpp::detail::resolve_parameter_overrides(
152  node_base.get_fully_qualified_name(),
153  options.parameter_overrides(),
154  &rcl_options->arguments,
155  global_args);
156 
157  auto final_topic_name = node_base.resolve_topic_or_service_name("/parameter_events", false);
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,
164  };
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() ?
169  it->second :
170  rclcpp::detail::get_default_qos_param_value(policy, options.parameter_event_qos());
171  rclcpp::detail::apply_qos_override(policy, value, final_qos);
172  }
173  return final_qos;
174 }
175 
177  const std::string & node_name,
178  const std::string & namespace_,
179  const NodeOptions & options)
180 : node_base_(new rclcpp::node_interfaces::NodeBase(
181  node_name,
182  namespace_,
183  options.context(),
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(
193  node_base_,
194  node_topics_,
195  node_graph_,
196  node_services_,
197  node_logging_,
198  options.clock_type()
199  )),
200  node_parameters_(new rclcpp::node_interfaces::NodeParameters(
201  node_base_,
202  node_logging_,
203  node_topics_,
204  node_services_,
205  node_clock_,
206  options.parameter_overrides(),
207  options.start_parameter_services(),
208  options.start_parameter_event_publisher(),
209  // This is needed in order to apply parameter overrides to the qos profile provided in
210  // options.
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()
215  )),
216  node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
217  node_base_,
218  node_topics_,
219  node_graph_,
220  node_services_,
221  node_logging_,
222  node_clock_,
223  node_parameters_,
224  options.clock_qos(),
225  options.use_clock_thread()
226  )),
227  node_type_descriptions_(new rclcpp::node_interfaces::NodeTypeDescriptions(
228  node_base_,
229  node_logging_,
230  node_parameters_,
231  node_services_
232  )),
233  node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
234  node_options_(options),
235  sub_namespace_(""),
236  effective_namespace_(create_effective_namespace(this->get_namespace(), sub_namespace_))
237 {
238  // we have got what we wanted directly from the overrides,
239  // but declare the parameters anyway so they are visible.
240  rclcpp::detail::declare_qos_parameters(
242  {
243  QosPolicyKind::Depth,
244  QosPolicyKind::Durability,
245  QosPolicyKind::History,
246  QosPolicyKind::Reliability,
247  },
248  node_parameters_,
249  node_topics_->resolve_topic_name("/parameter_events"),
250  options.parameter_event_qos(),
252 
253  if (options.enable_logger_service()) {
254  node_logging_->create_logger_services(node_services_);
255  }
256 }
257 
259  const Node & other,
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_)
275 {
276  // Validate new effective namespace.
277  int validation_result;
278  size_t invalid_index;
279  rmw_ret_t rmw_ret =
280  rmw_validate_namespace(effective_namespace_.c_str(), &validation_result, &invalid_index);
281 
282  if (rmw_ret != RMW_RET_OK) {
283  if (rmw_ret == RMW_RET_INVALID_ARGUMENT) {
284  throw_from_rcl_error(RCL_RET_INVALID_ARGUMENT, "failed to validate subnode namespace");
285  }
286  throw_from_rcl_error(RCL_RET_ERROR, "failed to validate subnode namespace");
287  }
288 
289  if (validation_result != RMW_NAMESPACE_VALID) {
291  effective_namespace_.c_str(),
292  rmw_namespace_validation_result_string(validation_result),
293  invalid_index);
294  }
295 }
296 
297 Node::~Node()
298 {
299  // release sub-interfaces in an order that allows them to consult with node_base during tear-down
300  node_waitables_.reset();
301  node_time_source_.reset();
302  node_parameters_.reset();
303  node_clock_.reset();
304  node_services_.reset();
305  node_topics_.reset();
306  node_timers_.reset();
307  node_logging_.reset();
308  node_graph_.reset();
309 }
310 
311 const char *
313 {
314  return node_base_->get_name();
315 }
316 
317 const char *
319 {
320  return node_base_->get_namespace();
321 }
322 
323 const char *
325 {
326  return node_base_->get_fully_qualified_name();
327 }
328 
331 {
332  return node_logging_->get_logger();
333 }
334 
335 rclcpp::CallbackGroup::SharedPtr
337  rclcpp::CallbackGroupType group_type,
338  bool automatically_add_to_executor_with_node)
339 {
340  return node_base_->create_callback_group(group_type, automatically_add_to_executor_with_node);
341 }
342 
345  const std::string & name,
346  const rclcpp::ParameterValue & default_value,
347  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
348  bool ignore_override)
349 {
350  return this->node_parameters_->declare_parameter(
351  name,
352  default_value,
353  parameter_descriptor,
354  ignore_override);
355 }
356 
359  const std::string & name,
360  rclcpp::ParameterType type,
361  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
362  bool ignore_override)
363 {
364  return this->node_parameters_->declare_parameter(
365  name,
366  type,
367  parameter_descriptor,
368  ignore_override);
369 }
370 
371 void
372 Node::undeclare_parameter(const std::string & name)
373 {
374  this->node_parameters_->undeclare_parameter(name);
375 }
376 
377 bool
378 Node::has_parameter(const std::string & name) const
379 {
380  return this->node_parameters_->has_parameter(name);
381 }
382 
383 rcl_interfaces::msg::SetParametersResult
385 {
386  return node_parameters_->set_parameters_atomically({parameter});
387 }
388 
389 std::vector<rcl_interfaces::msg::SetParametersResult>
390 Node::set_parameters(const std::vector<rclcpp::Parameter> & parameters)
391 {
392  return node_parameters_->set_parameters(parameters);
393 }
394 
395 rcl_interfaces::msg::SetParametersResult
396 Node::set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters)
397 {
398  return node_parameters_->set_parameters_atomically(parameters);
399 }
400 
402 Node::get_parameter(const std::string & name) const
403 {
404  return node_parameters_->get_parameter(name);
405 }
406 
407 bool
408 Node::get_parameter(const std::string & name, rclcpp::Parameter & parameter) const
409 {
410  return node_parameters_->get_parameter(name, parameter);
411 }
412 
413 std::vector<rclcpp::Parameter>
415  const std::vector<std::string> & names) const
416 {
417  return node_parameters_->get_parameters(names);
418 }
419 
420 rcl_interfaces::msg::ParameterDescriptor
421 Node::describe_parameter(const std::string & name) const
422 {
423  auto result = node_parameters_->describe_parameters({name});
424  if (0 == result.size()) {
426  }
427  if (result.size() > 1) {
428  throw std::runtime_error("number of described parameters unexpectedly more than one");
429  }
430  return result.front();
431 }
432 
433 std::vector<rcl_interfaces::msg::ParameterDescriptor>
434 Node::describe_parameters(const std::vector<std::string> & names) const
435 {
436  return node_parameters_->describe_parameters(names);
437 }
438 
439 std::vector<uint8_t>
440 Node::get_parameter_types(const std::vector<std::string> & names) const
441 {
442  return node_parameters_->get_parameter_types(names);
443 }
444 
445 rcl_interfaces::msg::ListParametersResult
446 Node::list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const
447 {
448  return node_parameters_->list_parameters(prefixes, depth);
449 }
450 
451 rclcpp::Node::PreSetParametersCallbackHandle::SharedPtr
452 Node::add_pre_set_parameters_callback(PreSetParametersCallbackType callback)
453 {
454  return node_parameters_->add_pre_set_parameters_callback(callback);
455 }
456 
457 rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr
458 Node::add_on_set_parameters_callback(OnSetParametersCallbackType callback)
459 {
460  return node_parameters_->add_on_set_parameters_callback(callback);
461 }
462 
463 rclcpp::Node::PostSetParametersCallbackHandle::SharedPtr
464 Node::add_post_set_parameters_callback(PostSetParametersCallbackType callback)
465 {
466  return node_parameters_->add_post_set_parameters_callback(callback);
467 }
468 
469 void
471 {
472  node_parameters_->remove_pre_set_parameters_callback(handler);
473 }
474 
475 void
477 {
478  node_parameters_->remove_on_set_parameters_callback(handler);
479 }
480 
481 void
483 {
484  node_parameters_->remove_post_set_parameters_callback(handler);
485 }
486 
487 std::vector<std::string>
489 {
490  return node_graph_->get_node_names();
491 }
492 
493 std::map<std::string, std::vector<std::string>>
495 {
496  return node_graph_->get_topic_names_and_types();
497 }
498 
499 std::map<std::string, std::vector<std::string>>
501 {
502  return node_graph_->get_service_names_and_types();
503 }
504 
505 std::map<std::string, std::vector<std::string>>
507  const std::string & node_name,
508  const std::string & namespace_) const
509 {
510  return node_graph_->get_service_names_and_types_by_node(
511  node_name, namespace_);
512 }
513 
514 size_t
515 Node::count_publishers(const std::string & topic_name) const
516 {
517  return node_graph_->count_publishers(topic_name);
518 }
519 
520 size_t
521 Node::count_subscribers(const std::string & topic_name) const
522 {
523  return node_graph_->count_subscribers(topic_name);
524 }
525 
526 size_t
527 Node::count_clients(const std::string & service_name) const
528 {
529  return node_graph_->count_clients(service_name);
530 }
531 
532 size_t
533 Node::count_services(const std::string & service_name) const
534 {
535  return node_graph_->count_services(service_name);
536 }
537 
538 std::vector<rclcpp::TopicEndpointInfo>
539 Node::get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle) const
540 {
541  return node_graph_->get_publishers_info_by_topic(topic_name, no_mangle);
542 }
543 
544 std::vector<rclcpp::TopicEndpointInfo>
545 Node::get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle) const
546 {
547  return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle);
548 }
549 
550 void
552  const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func)
553 {
554  node_base_->for_each_callback_group(func);
555 }
556 
557 rclcpp::Event::SharedPtr
559 {
560  return node_graph_->get_graph_event();
561 }
562 
563 void
565  rclcpp::Event::SharedPtr event,
566  std::chrono::nanoseconds timeout)
567 {
568  node_graph_->wait_for_graph_change(event, timeout);
569 }
570 
571 rclcpp::Clock::SharedPtr
573 {
574  return node_clock_->get_clock();
575 }
576 
577 rclcpp::Clock::ConstSharedPtr
579 {
580  return node_clock_->get_clock();
581 }
582 
584 Node::now() const
585 {
586  return node_clock_->get_clock()->now();
587 }
588 
589 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
591 {
592  return node_base_;
593 }
594 
595 rclcpp::node_interfaces::NodeClockInterface::SharedPtr
597 {
598  return node_clock_;
599 }
600 
601 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
603 {
604  return node_graph_;
605 }
606 
607 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
609 {
610  return node_logging_;
611 }
612 
613 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
615 {
616  return node_time_source_;
617 }
618 
619 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
621 {
622  return node_timers_;
623 }
624 
625 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
627 {
628  return node_topics_;
629 }
630 
631 rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr
633 {
634  return node_type_descriptions_;
635 }
636 
637 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
639 {
640  return node_services_;
641 }
642 
643 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
645 {
646  return node_parameters_;
647 }
648 
649 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
651 {
652  return node_waitables_;
653 }
654 
655 const std::string &
657 {
658  return this->sub_namespace_;
659 }
660 
661 const std::string &
663 {
664  return this->effective_namespace_;
665 }
666 
667 Node::SharedPtr
668 Node::create_sub_node(const std::string & sub_namespace)
669 {
670  // Cannot use make_shared<Node>() here as it requires the constructor to be
671  // public, and this constructor is intentionally protected instead.
672  return std::shared_ptr<Node>(new Node(*this, sub_namespace));
673 }
674 
675 const NodeOptions &
677 {
678  return this->node_options_;
679 }
680 
681 rclcpp::GenericClient::SharedPtr
683  const std::string & service_name,
684  const std::string & service_type,
685  const rclcpp::QoS & qos,
686  rclcpp::CallbackGroup::SharedPtr group)
687 {
689  node_base_,
690  node_graph_,
691  node_services_,
692  service_name,
693  service_type,
694  qos,
695  group);
696 }
Internal implementation to provide hidden and API/ABI stable changes to the Node.
Definition: node.cpp:124
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.
Definition: node.hpp:80
RCLCPP_PUBLIC rclcpp::Logger get_logger() const
Get the logger of the node.
Definition: node.cpp:330
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
Definition: node.cpp:650
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
Definition: node.cpp:626
RCLCPP_PUBLIC std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
Definition: node.cpp:414
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnSetParametersCallbackType callback)
Add a callback to validate parameters before they are set.
Definition: node.cpp:458
RCLCPP_PUBLIC bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
Definition: node.cpp:378
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.
Definition: node.cpp:668
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)
Set a single parameter.
Definition: node.cpp:384
RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
Definition: node.cpp:572
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
Definition: node.cpp:620
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
Definition: node.cpp:644
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.
Definition: node.cpp:539
RCLCPP_PUBLIC const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
Definition: node.cpp:344
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
Definition: node.cpp:608
RCLCPP_PUBLIC const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
Definition: node.cpp:662
RCLCPP_PUBLIC size_t count_publishers(const std::string &topic_name) const
Return the number of publishers created for a given topic.
Definition: node.cpp:515
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.
Definition: node.cpp:500
RCLCPP_PUBLIC size_t count_subscribers(const std::string &topic_name) const
Return the number of subscribers created for a given topic.
Definition: node.cpp:521
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.
Definition: node.cpp:434
RCLCPP_PUBLIC Time now() const
Returns current time from the time source specified by clock_type.
Definition: node.cpp:584
RCLCPP_PUBLIC rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
Definition: node.cpp:558
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.
Definition: node.cpp:551
RCLCPP_PUBLIC rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
Definition: node.cpp:421
RCLCPP_PUBLIC void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
Definition: node.cpp:476
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.
Definition: node.cpp:494
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
Definition: node.cpp:402
RCLCPP_PUBLIC Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
Definition: node.cpp:130
RCLCPP_PUBLIC size_t count_services(const std::string &service_name) const
Return the number of services created for a given service.
Definition: node.cpp:533
RCLCPP_PUBLIC const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
Definition: node.cpp:676
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
Definition: node.cpp:590
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.
Definition: node.cpp:682
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, all at once.
Definition: node.cpp:396
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.
Definition: node.cpp:564
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
Definition: node.cpp:596
RCLCPP_PUBLIC void remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle *const handler)
Remove a callback registered with add_pre_set_parameters_callback.
Definition: node.cpp:470
RCLCPP_PUBLIC const char * get_name() const
Get the name of the node.
Definition: node.cpp:312
RCLCPP_PUBLIC std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, one at a time.
Definition: node.cpp:390
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr get_node_type_descriptions_interface()
Return the Node's internal NodeTypeDescriptionsInterface implementation.
Definition: node.cpp:632
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
Definition: node.cpp:638
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.
Definition: node.cpp:506
RCLCPP_PUBLIC void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
Definition: node.cpp:372
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.
Definition: node.cpp:440
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.
Definition: node.cpp:545
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.
Definition: node.cpp:336
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeTimeSourceInterface implementation.
Definition: node.cpp:614
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED PreSetParametersCallbackHandle::SharedPtr add_pre_set_parameters_callback(PreSetParametersCallbackType callback)
Add a callback that gets triggered before parameters are validated.
Definition: node.cpp:452
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.
Definition: node.cpp:446
RCLCPP_PUBLIC size_t count_clients(const std::string &service_name) const
Return the number of clients created for a given service.
Definition: node.cpp:527
RCLCPP_PUBLIC const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
Definition: node.cpp:324
RCLCPP_PUBLIC const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
Definition: node.cpp:656
RCLCPP_PUBLIC std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.
Definition: node.cpp:488
RCLCPP_PUBLIC const char * get_namespace() const
Get the namespace of the node.
Definition: node.cpp:318
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.
Definition: node.cpp:464
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
Definition: node.cpp:602
RCLCPP_PUBLIC void remove_post_set_parameters_callback(const PostSetParametersCallbackHandle *const handler)
Remove a callback registered with add_post_set_parameters_callback.
Definition: node.cpp:482
Store the type and value of a parameter.
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:53
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
Options that are passed in subscription/publisher constructor to specify QoSConfigurability.
Thrown when a node namespace is invalid.
Definition: exceptions.hpp:78
Thrown when a any kind of name (node, namespace, topic, etc.) is invalid.
Definition: exceptions.hpp:43
Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
Definition: exceptions.hpp:301
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.
Definition: arguments.h:36
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:35
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:29