ROS 2 rclcpp + rcl - humble  humble
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/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"
41 
42 #include "rmw/validate_namespace.h"
43 
44 #include "./detail/resolve_parameter_overrides.hpp"
45 
46 using rclcpp::Node;
48 using rclcpp::exceptions::throw_from_rcl_error;
49 
50 namespace
51 {
52 
53 RCLCPP_LOCAL
54 std::string
55 extend_sub_namespace(const std::string & existing_sub_namespace, const std::string & extension)
56 {
57  // Assumption is that the existing_sub_namespace does not need checking
58  // because it would be checked already when it was set with this function.
59 
60  if (extension.empty()) {
62  "sub_namespace",
63  extension.c_str(),
64  "sub-nodes should not extend nodes by an empty sub-namespace",
65  0);
66  } else if (extension.front() == '/') {
67  // check if the new sub-namespace extension is absolute
69  "sub_namespace",
70  extension.c_str(),
71  "a sub-namespace should not have a leading /",
72  0);
73  }
74 
75  std::string new_sub_namespace;
76  if (existing_sub_namespace.empty()) {
77  new_sub_namespace = extension;
78  } else {
79  new_sub_namespace = existing_sub_namespace + "/" + extension;
80  }
81 
82  // remove any trailing `/` so that new extensions do not result in `//`
83  if (new_sub_namespace.back() == '/') {
84  new_sub_namespace = new_sub_namespace.substr(0, new_sub_namespace.size() - 1);
85  }
86 
87  return new_sub_namespace;
88 }
89 
90 RCLCPP_LOCAL
91 std::string
92 create_effective_namespace(const std::string & node_namespace, const std::string & sub_namespace)
93 {
94  // Assumption is that both the node_namespace and sub_namespace are conforming
95  // and do not need trimming of `/` and other things, as they were validated
96  // in other functions already.
97 
98  // A node may not have a sub_namespace if it is no sub_node. In this case,
99  // just return the original namespace
100  if (sub_namespace.empty()) {
101  return node_namespace;
102  } else if (node_namespace.back() == '/') {
103  // this is the special case where node_namespace is just `/`
104  return node_namespace + sub_namespace;
105  } else {
106  return node_namespace + "/" + sub_namespace;
107  }
108 }
109 
110 } // namespace
111 
112 Node::Node(
113  const std::string & node_name,
114  const NodeOptions & options)
115 : Node(node_name, "", options)
116 {
117 }
118 
119 static
121 get_parameter_events_qos(
123  const rclcpp::NodeOptions & options)
124 {
125  auto final_qos = options.parameter_event_qos();
126  const rcl_arguments_t * global_args = nullptr;
127  auto * rcl_options = options.get_rcl_node_options();
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);
131  }
132 
133  auto parameter_overrides = rclcpp::detail::resolve_parameter_overrides(
134  node_base.get_fully_qualified_name(),
135  options.parameter_overrides(),
136  &rcl_options->arguments,
137  global_args);
138 
139  auto final_topic_name = node_base.resolve_topic_or_service_name("/parameter_events", false);
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,
146  };
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() ?
151  it->second :
152  rclcpp::detail::get_default_qos_param_value(policy, options.parameter_event_qos());
153  rclcpp::detail::apply_qos_override(policy, value, final_qos);
154  }
155  return final_qos;
156 }
157 
159  const std::string & node_name,
160  const std::string & namespace_,
161  const NodeOptions & options)
162 : node_base_(new rclcpp::node_interfaces::NodeBase(
163  node_name,
164  namespace_,
165  options.context(),
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(
175  node_base_,
176  node_topics_,
177  node_graph_,
178  node_services_,
179  node_logging_
180  )),
181  node_parameters_(new rclcpp::node_interfaces::NodeParameters(
182  node_base_,
183  node_logging_,
184  node_topics_,
185  node_services_,
186  node_clock_,
187  options.parameter_overrides(),
188  options.start_parameter_services(),
189  options.start_parameter_event_publisher(),
190  // This is needed in order to apply parameter overrides to the qos profile provided in
191  // options.
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()
196  )),
197  node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
198  node_base_,
199  node_topics_,
200  node_graph_,
201  node_services_,
202  node_logging_,
203  node_clock_,
204  node_parameters_,
205  options.clock_qos(),
206  options.use_clock_thread()
207  )),
208  node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
209  node_options_(options),
210  sub_namespace_(""),
211  effective_namespace_(create_effective_namespace(this->get_namespace(), sub_namespace_))
212 {
213  // we have got what we wanted directly from the overrides,
214  // but declare the parameters anyway so they are visible.
215  rclcpp::detail::declare_qos_parameters(
217  {
218  QosPolicyKind::Depth,
219  QosPolicyKind::Durability,
220  QosPolicyKind::History,
221  QosPolicyKind::Reliability,
222  },
223  node_parameters_,
224  node_topics_->resolve_topic_name("/parameter_events"),
225  options.parameter_event_qos(),
227 }
228 
230  const Node & other,
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_))
245 {
246  // Validate new effective namespace.
247  int validation_result;
248  size_t invalid_index;
249  rmw_ret_t rmw_ret =
250  rmw_validate_namespace(effective_namespace_.c_str(), &validation_result, &invalid_index);
251 
252  if (rmw_ret != RMW_RET_OK) {
253  if (rmw_ret == RMW_RET_INVALID_ARGUMENT) {
254  throw_from_rcl_error(RCL_RET_INVALID_ARGUMENT, "failed to validate subnode namespace");
255  }
256  throw_from_rcl_error(RCL_RET_ERROR, "failed to validate subnode namespace");
257  }
258 
259  if (validation_result != RMW_NAMESPACE_VALID) {
261  effective_namespace_.c_str(),
262  rmw_namespace_validation_result_string(validation_result),
263  invalid_index);
264  }
265 }
266 
267 Node::~Node()
268 {
269  // release sub-interfaces in an order that allows them to consult with node_base during tear-down
270  node_waitables_.reset();
271  node_time_source_.reset();
272  node_parameters_.reset();
273  node_clock_.reset();
274  node_services_.reset();
275  node_topics_.reset();
276  node_timers_.reset();
277  node_logging_.reset();
278  node_graph_.reset();
279 }
280 
281 const char *
283 {
284  return node_base_->get_name();
285 }
286 
287 const char *
289 {
290  return node_base_->get_namespace();
291 }
292 
293 const char *
295 {
296  return node_base_->get_fully_qualified_name();
297 }
298 
301 {
302  return node_logging_->get_logger();
303 }
304 
305 rclcpp::CallbackGroup::SharedPtr
307  rclcpp::CallbackGroupType group_type,
308  bool automatically_add_to_executor_with_node)
309 {
310  return node_base_->create_callback_group(group_type, automatically_add_to_executor_with_node);
311 }
312 
315  const std::string & name,
316  const rclcpp::ParameterValue & default_value,
317  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
318  bool ignore_override)
319 {
320  return this->node_parameters_->declare_parameter(
321  name,
322  default_value,
323  parameter_descriptor,
324  ignore_override);
325 }
326 
329  const std::string & name,
330  rclcpp::ParameterType type,
331  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
332  bool ignore_override)
333 {
334  return this->node_parameters_->declare_parameter(
335  name,
336  type,
337  parameter_descriptor,
338  ignore_override);
339 }
340 
341 void
342 Node::undeclare_parameter(const std::string & name)
343 {
344  this->node_parameters_->undeclare_parameter(name);
345 }
346 
347 bool
348 Node::has_parameter(const std::string & name) const
349 {
350  return this->node_parameters_->has_parameter(name);
351 }
352 
353 rcl_interfaces::msg::SetParametersResult
355 {
356  return this->set_parameters_atomically({parameter});
357 }
358 
359 std::vector<rcl_interfaces::msg::SetParametersResult>
360 Node::set_parameters(const std::vector<rclcpp::Parameter> & parameters)
361 {
362  return node_parameters_->set_parameters(parameters);
363 }
364 
365 rcl_interfaces::msg::SetParametersResult
366 Node::set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters)
367 {
368  return node_parameters_->set_parameters_atomically(parameters);
369 }
370 
372 Node::get_parameter(const std::string & name) const
373 {
374  return node_parameters_->get_parameter(name);
375 }
376 
377 bool
378 Node::get_parameter(const std::string & name, rclcpp::Parameter & parameter) const
379 {
380  return node_parameters_->get_parameter(name, parameter);
381 }
382 
383 std::vector<rclcpp::Parameter>
385  const std::vector<std::string> & names) const
386 {
387  return node_parameters_->get_parameters(names);
388 }
389 
390 rcl_interfaces::msg::ParameterDescriptor
391 Node::describe_parameter(const std::string & name) const
392 {
393  auto result = node_parameters_->describe_parameters({name});
394  if (0 == result.size()) {
396  }
397  if (result.size() > 1) {
398  throw std::runtime_error("number of described parameters unexpectedly more than one");
399  }
400  return result.front();
401 }
402 
403 std::vector<rcl_interfaces::msg::ParameterDescriptor>
404 Node::describe_parameters(const std::vector<std::string> & names) const
405 {
406  return node_parameters_->describe_parameters(names);
407 }
408 
409 std::vector<uint8_t>
410 Node::get_parameter_types(const std::vector<std::string> & names) const
411 {
412  return node_parameters_->get_parameter_types(names);
413 }
414 
415 rcl_interfaces::msg::ListParametersResult
416 Node::list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const
417 {
418  return node_parameters_->list_parameters(prefixes, depth);
419 }
420 
421 rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr
422 Node::add_on_set_parameters_callback(OnParametersSetCallbackType callback)
423 {
424  return node_parameters_->add_on_set_parameters_callback(callback);
425 }
426 
427 void
429 {
430  return node_parameters_->remove_on_set_parameters_callback(callback);
431 }
432 
433 std::vector<std::string>
435 {
436  return node_graph_->get_node_names();
437 }
438 
439 std::map<std::string, std::vector<std::string>>
441 {
442  return node_graph_->get_topic_names_and_types();
443 }
444 
445 std::map<std::string, std::vector<std::string>>
447 {
448  return node_graph_->get_service_names_and_types();
449 }
450 
451 std::map<std::string, std::vector<std::string>>
453  const std::string & node_name,
454  const std::string & namespace_) const
455 {
456  return node_graph_->get_service_names_and_types_by_node(
457  node_name, namespace_);
458 }
459 
460 size_t
461 Node::count_publishers(const std::string & topic_name) const
462 {
463  return node_graph_->count_publishers(topic_name);
464 }
465 
466 size_t
467 Node::count_subscribers(const std::string & topic_name) const
468 {
469  return node_graph_->count_subscribers(topic_name);
470 }
471 
472 std::vector<rclcpp::TopicEndpointInfo>
473 Node::get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle) const
474 {
475  return node_graph_->get_publishers_info_by_topic(topic_name, no_mangle);
476 }
477 
478 std::vector<rclcpp::TopicEndpointInfo>
479 Node::get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle) const
480 {
481  return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle);
482 }
483 
484 void
486  const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func)
487 {
488  node_base_->for_each_callback_group(func);
489 }
490 
491 rclcpp::Event::SharedPtr
493 {
494  return node_graph_->get_graph_event();
495 }
496 
497 void
499  rclcpp::Event::SharedPtr event,
500  std::chrono::nanoseconds timeout)
501 {
502  node_graph_->wait_for_graph_change(event, timeout);
503 }
504 
505 rclcpp::Clock::SharedPtr
507 {
508  return node_clock_->get_clock();
509 }
510 
511 rclcpp::Clock::ConstSharedPtr
513 {
514  return node_clock_->get_clock();
515 }
516 
518 Node::now() const
519 {
520  return node_clock_->get_clock()->now();
521 }
522 
523 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
525 {
526  return node_base_;
527 }
528 
529 rclcpp::node_interfaces::NodeClockInterface::SharedPtr
531 {
532  return node_clock_;
533 }
534 
535 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
537 {
538  return node_graph_;
539 }
540 
541 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
543 {
544  return node_logging_;
545 }
546 
547 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
549 {
550  return node_time_source_;
551 }
552 
553 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
555 {
556  return node_timers_;
557 }
558 
559 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
561 {
562  return node_topics_;
563 }
564 
565 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
567 {
568  return node_services_;
569 }
570 
571 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
573 {
574  return node_parameters_;
575 }
576 
577 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
579 {
580  return node_waitables_;
581 }
582 
583 const std::string &
585 {
586  return this->sub_namespace_;
587 }
588 
589 const std::string &
591 {
592  return this->effective_namespace_;
593 }
594 
595 Node::SharedPtr
596 Node::create_sub_node(const std::string & sub_namespace)
597 {
598  // Cannot use make_shared<Node>() here as it requires the constructor to be
599  // public, and this constructor is intentionally protected instead.
600  return std::shared_ptr<Node>(new Node(*this, sub_namespace));
601 }
602 
603 const NodeOptions &
605 {
606  return this->node_options_;
607 }
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.
Definition: node.hpp:78
RCLCPP_PUBLIC rclcpp::Logger get_logger() const
Get the logger of the node.
Definition: node.cpp:300
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
Definition: node.cpp:578
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
Definition: node.cpp:560
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:384
RCLCPP_PUBLIC bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
Definition: node.cpp:348
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:596
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)
Set a single parameter.
Definition: node.cpp:354
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:506
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
Definition: node.cpp:554
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
Definition: node.cpp:572
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:473
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:314
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
Definition: node.cpp:542
RCLCPP_PUBLIC const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
Definition: node.cpp:590
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:461
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:446
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:467
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:404
RCLCPP_PUBLIC Time now() const
Returns current time from the time source specified by clock_type.
Definition: node.cpp:518
RCLCPP_PUBLIC rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
Definition: node.cpp:492
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:485
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:391
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:428
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:440
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
Definition: node.cpp:372
RCLCPP_PUBLIC Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
Definition: node.cpp:112
RCLCPP_PUBLIC const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
Definition: node.cpp:604
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
Definition: node.cpp:524
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:366
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:498
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
Definition: node.cpp:530
RCLCPP_PUBLIC const char * get_name() const
Get the name of the node.
Definition: node.cpp:282
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)
Add a callback for when parameters are being set.
Definition: node.cpp:422
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:360
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
Definition: node.cpp:566
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:452
RCLCPP_PUBLIC void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
Definition: node.cpp:342
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:410
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:479
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:306
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeTimeSourceInterface implementation.
Definition: node.cpp:548
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:416
RCLCPP_PUBLIC const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
Definition: node.cpp:294
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:584
RCLCPP_PUBLIC std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.
Definition: node.cpp:434
RCLCPP_PUBLIC const char * get_namespace() const
Get the namespace of the node.
Definition: node.cpp:288
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
Definition: node.cpp:536
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:111
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:285
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.
Definition: arguments.h:36
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:34
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:28