ROS 2 rclcpp + rcl - rolling  rolling-4d14414d
ROS 2 C++ Client Library with ROS Client Library
context.cpp
1 // Copyright 2015-2020 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 "rclcpp/context.hpp"
16 
17 #include <memory>
18 #include <mutex>
19 #include <sstream>
20 #include <string>
21 #include <vector>
22 #include <unordered_set>
23 #include <utility>
24 
25 #include "rcl/init.h"
26 #include "rcl/logging.h"
27 
28 #include "rclcpp/detail/utilities.hpp"
29 #include "rclcpp/exceptions.hpp"
30 #include "rclcpp/logging.hpp"
31 #include "rclcpp/graph_listener.hpp"
32 #include "rcutils/error_handling.h"
33 #include "rcutils/macros.h"
34 
35 #include "./logging_mutex.hpp"
36 
37 using rclcpp::Context;
38 
39 namespace rclcpp
40 {
43 {
44 public:
45  RCLCPP_SMART_PTR_DEFINITIONS(WeakContextsWrapper)
46 
47  void
48  add_context(const Context::SharedPtr & context)
49  {
50  std::lock_guard<std::mutex> guard(mutex_);
51  weak_contexts_.push_back(context);
52  }
53 
54  void
55  remove_context(const Context * context)
56  {
57  std::lock_guard<std::mutex> guard(mutex_);
58  weak_contexts_.erase(
59  std::remove_if(
60  weak_contexts_.begin(),
61  weak_contexts_.end(),
62  [context](const Context::WeakPtr weak_context) {
63  auto locked_context = weak_context.lock();
64  if (!locked_context) {
65  // take advantage and removed expired contexts
66  return true;
67  }
68  return locked_context.get() == context;
69  }
70  ),
71  weak_contexts_.end());
72  }
73 
74  std::vector<Context::SharedPtr>
75  get_contexts()
76  {
77  std::lock_guard<std::mutex> lock(mutex_);
78  std::vector<Context::SharedPtr> shared_contexts;
79  for (auto it = weak_contexts_.begin(); it != weak_contexts_.end(); /* noop */) {
80  auto context_ptr = it->lock();
81  if (!context_ptr) {
82  // remove invalid weak context pointers
83  it = weak_contexts_.erase(it);
84  } else {
85  ++it;
86  shared_contexts.push_back(context_ptr);
87  }
88  }
89  return shared_contexts;
90  }
91 
92 private:
93  std::vector<std::weak_ptr<rclcpp::Context>> weak_contexts_;
94  std::mutex mutex_;
95 };
96 } // namespace rclcpp
97 
99 
101 static
102 WeakContextsWrapper::SharedPtr
103 get_weak_contexts()
104 {
105  static WeakContextsWrapper::SharedPtr weak_contexts = WeakContextsWrapper::make_shared();
106  if (!weak_contexts) {
107  throw std::runtime_error("weak contexts vector is not valid");
108  }
109  return weak_contexts;
110 }
111 
113 static
114 size_t &
115 get_logging_reference_count()
116 {
117  static size_t ref_count = 0;
118  return ref_count;
119 }
120 
121 extern "C"
122 {
123 static
124 void
125 rclcpp_logging_output_handler(
126  const rcutils_log_location_t * location,
127  int severity, const char * name, rcutils_time_point_value_t timestamp,
128  const char * format, va_list * args)
129 {
130  try {
131  std::shared_ptr<std::recursive_mutex> logging_mutex;
132  logging_mutex = get_global_logging_mutex();
133  std::lock_guard<std::recursive_mutex> guard(*logging_mutex);
135  location, severity, name, timestamp, format, args);
136  } catch (std::exception & ex) {
137  RCUTILS_SAFE_FWRITE_TO_STDERR(ex.what());
138  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
139  } catch (...) {
140  RCUTILS_SAFE_FWRITE_TO_STDERR("failed to take global rclcpp logging mutex\n");
141  }
142 }
143 } // extern "C"
144 
145 Context::Context()
146 : rcl_context_(nullptr),
147  shutdown_reason_(""),
148  logging_mutex_(nullptr),
149  graph_listener_(nullptr)
150 {}
151 
152 Context::~Context()
153 {
154  // acquire the init lock to prevent race conditions with init and shutdown
155  // this will not prevent errors, but will maybe make them easier to reproduce
156  std::lock_guard<std::recursive_mutex> lock(init_mutex_);
157  try {
158  // Cannot rely on virtual dispatch in a destructor, so explicitly use the
159  // shutdown() provided by this base class.
160  Context::shutdown("context destructor was called while still not shutdown");
161  // at this point it is shutdown and cannot reinit
162  // clean_up will finalize the rcl context
163  this->clean_up();
164  } catch (const std::exception & exc) {
165  RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "unhandled exception in ~Context(): %s", exc.what());
166  } catch (...) {
167  RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "unhandled exception in ~Context()");
168  }
169 }
170 
171 RCLCPP_LOCAL
172 void
173 __delete_context(rcl_context_t * context)
174 {
175  if (context) {
176  if (rcl_context_is_valid(context)) {
177  RCLCPP_ERROR(
178  rclcpp::get_logger("rclcpp"), "rcl context unexpectedly not shutdown during cleanup");
179  } else {
180  // if context pointer is not null and is shutdown, then it's ready for fini
181  rcl_ret_t ret = rcl_context_fini(context);
182  if (RCL_RET_OK != ret) {
183  RCLCPP_ERROR(
184  rclcpp::get_logger("rclcpp"),
185  "failed to finalize context: %s", rcl_get_error_string().str);
186  rcl_reset_error();
187  }
188  }
189  delete context;
190  }
191 }
192 
193 void
195  int argc,
196  char const * const * argv,
197  const rclcpp::InitOptions & init_options)
198 {
199  std::lock_guard<std::recursive_mutex> init_lock(init_mutex_);
200  if (this->is_valid()) {
202  }
203  this->clean_up();
204  rcl_context_t * context = new rcl_context_t;
205  if (!context) {
206  throw std::runtime_error("failed to allocate memory for rcl context");
207  }
209  rcl_ret_t ret = rcl_init(argc, argv, init_options.get_rcl_init_options(), context);
210  if (RCL_RET_OK != ret) {
211  delete context;
212  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialize rcl");
213  }
214  rcl_context_.reset(context, __delete_context);
215 
216  try {
217  if (init_options.auto_initialize_logging()) {
218  logging_mutex_ = get_global_logging_mutex();
219  std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
220  size_t & count = get_logging_reference_count();
221  if (0u == count) {
223  &rcl_context_->global_arguments,
225  rclcpp_logging_output_handler);
226  if (RCL_RET_OK != ret) {
227  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging");
228  }
229  } else {
230  RCLCPP_WARN(
231  rclcpp::get_logger("rclcpp"),
232  "logging was initialized more than once");
233  }
234  ++count;
235  }
236 
237  std::vector<std::string> unparsed_ros_arguments = detail::get_unparsed_ros_arguments(
238  argc, argv, &(rcl_context_->global_arguments), rcl_get_default_allocator());
239  if (!unparsed_ros_arguments.empty()) {
240  throw exceptions::UnknownROSArgsError(std::move(unparsed_ros_arguments));
241  }
242 
243  init_options_ = init_options;
244 
245  weak_contexts_ = get_weak_contexts();
246  weak_contexts_->add_context(this->shared_from_this());
247 
248 
249  std::lock_guard<std::recursive_mutex> lock (on_shutdown_callbacks_mutex_);
250 
251  graph_listener_ = std::make_shared<graph_listener::GraphListener>(shared_from_this());
252 
253  if (!graph_listener_->is_started()) {
254  // Register an on_shutdown hook to shutdown the graph listener.
255  // This is important to ensure that the wait set is finalized before
256  // destruction of static objects occurs.
257  std::weak_ptr<rclcpp::graph_listener::GraphListener> weak_graph_listener = graph_listener_;
258  on_shutdown ([weak_graph_listener]() {
259  auto shared_graph_listener = weak_graph_listener.lock();
260  if(shared_graph_listener) {
261  shared_graph_listener->shutdown(std::nothrow);
262  }
263  });
264  }
265  } catch (const std::exception & e) {
266  ret = rcl_shutdown(rcl_context_.get());
267  rcl_context_.reset();
268  if (RCL_RET_OK != ret) {
269  std::ostringstream oss;
270  oss << "While handling: " << e.what() << std::endl <<
271  " another exception was thrown";
272  rclcpp::exceptions::throw_from_rcl_error(ret, oss.str());
273  }
274  throw;
275  }
276 }
277 
278 bool
280 {
281  // Take a local copy of the shared pointer to avoid it getting nulled under our feet.
282  auto local_rcl_context = rcl_context_;
283  if (!local_rcl_context) {
284  return false;
285  }
286  return rcl_context_is_valid(local_rcl_context.get());
287 }
288 
289 const rclcpp::InitOptions &
291 {
292  return init_options_;
293 }
294 
297 {
298  return init_options_;
299 }
300 
301 size_t
303 {
304  size_t domain_id;
305  rcl_ret_t ret = rcl_context_get_domain_id(rcl_context_.get(), &domain_id);
306  if (RCL_RET_OK != ret) {
307  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to get domain id from context");
308  }
309  return domain_id;
310 }
311 
312 std::string
314 {
315  std::lock_guard<std::recursive_mutex> lock(init_mutex_);
316  return shutdown_reason_;
317 }
318 
319 bool
320 Context::shutdown(const std::string & reason)
321 {
322  // prevent races
323  std::lock_guard<std::recursive_mutex> init_lock(init_mutex_);
324  // ensure validity
325  if (!this->is_valid()) {
326  // if it is not valid, then it cannot be shutdown
327  return false;
328  }
329 
330  // call each pre-shutdown callback
331  {
332  std::lock_guard<std::recursive_mutex> lock{pre_shutdown_callbacks_mutex_};
333  // callbacks may delete other callbacks during the execution,
334  // therefore we need to save a copy and check before execution
335  // if the next callback is still present
336  auto cpy = pre_shutdown_callbacks_;
337  for (const auto & callback : cpy) {
338  auto it = std::find(pre_shutdown_callbacks_.begin(), pre_shutdown_callbacks_.end(), callback);
339  if(it != pre_shutdown_callbacks_.end()) {
340  (*callback)();
341  }
342  }
343  }
344 
345  // rcl shutdown
346  rcl_ret_t ret = rcl_shutdown(rcl_context_.get());
347  if (RCL_RET_OK != ret) {
348  rclcpp::exceptions::throw_from_rcl_error(ret);
349  }
350  // set shutdown reason
351  shutdown_reason_ = reason;
352  // call each shutdown callback
353  {
354  std::lock_guard<std::recursive_mutex> lock(on_shutdown_callbacks_mutex_);
355  // callbacks may delete other callbacks during the execution,
356  // therefore we need to save a copy and check before execution
357  // if the next callback is still present
358  auto cpy = on_shutdown_callbacks_;
359  for (const auto & callback : cpy) {
360  auto it = std::find(on_shutdown_callbacks_.begin(), on_shutdown_callbacks_.end(), callback);
361  if(it != on_shutdown_callbacks_.end()) {
362  (*callback)();
363  }
364  }
365  }
366 
367  // interrupt all blocking sleep_for() and all blocking executors or wait sets
368  this->interrupt_all_sleep_for();
369  // remove self from the global contexts
370  weak_contexts_->remove_context(this);
371  // shutdown logger
372  if (logging_mutex_) {
373  // logging was initialized by this context
374  std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
375  size_t & count = get_logging_reference_count();
376  if (0u == --count) {
377  rcl_ret_t rcl_ret = rcl_logging_fini();
378  if (RCL_RET_OK != rcl_ret) {
379  RCUTILS_SAFE_FWRITE_TO_STDERR(
380  RCUTILS_STRINGIFY(__file__) ":"
381  RCUTILS_STRINGIFY(__LINE__)
382  " failed to fini logging");
383  rcl_reset_error();
384  }
385  }
386  }
387  return true;
388 }
389 
390 rclcpp::Context::OnShutdownCallback
391 Context::on_shutdown(OnShutdownCallback callback)
392 {
393  add_on_shutdown_callback(callback);
394  return callback;
395 }
396 
398 Context::add_on_shutdown_callback(OnShutdownCallback callback)
399 {
400  return add_shutdown_callback<ShutdownType::on_shutdown>(callback);
401 }
402 
403 bool
405 {
406  return remove_shutdown_callback<ShutdownType::on_shutdown>(callback_handle);
407 }
408 
410 Context::add_pre_shutdown_callback(PreShutdownCallback callback)
411 {
412  return add_shutdown_callback<ShutdownType::pre_shutdown>(callback);
413 }
414 
415 bool
417  const PreShutdownCallbackHandle & callback_handle)
418 {
419  return remove_shutdown_callback<ShutdownType::pre_shutdown>(callback_handle);
420 }
421 
422 template<Context::ShutdownType shutdown_type>
424 Context::add_shutdown_callback(
425  ShutdownCallback callback)
426 {
427  auto callback_shared_ptr =
428  std::make_shared<ShutdownCallbackHandle::ShutdownCallbackType>(callback);
429 
430  static_assert(
431  shutdown_type == ShutdownType::pre_shutdown || shutdown_type == ShutdownType::on_shutdown);
432 
433  if constexpr (shutdown_type == ShutdownType::pre_shutdown) {
434  std::lock_guard<std::recursive_mutex> lock(pre_shutdown_callbacks_mutex_);
435  pre_shutdown_callbacks_.emplace_back(callback_shared_ptr);
436  } else {
437  std::lock_guard<std::recursive_mutex> lock(on_shutdown_callbacks_mutex_);
438  on_shutdown_callbacks_.emplace_back(callback_shared_ptr);
439  }
440 
441  ShutdownCallbackHandle callback_handle;
442  callback_handle.callback = callback_shared_ptr;
443  return callback_handle;
444 }
445 
446 template<Context::ShutdownType shutdown_type>
447 bool
448 Context::remove_shutdown_callback(
449  const ShutdownCallbackHandle & callback_handle)
450 {
451  const auto callback_shared_ptr = callback_handle.callback.lock();
452  if (callback_shared_ptr == nullptr) {
453  return false;
454  }
455 
456  const auto remove_callback = [&callback_shared_ptr](auto & mutex, auto & callback_vector) {
457  const std::lock_guard<std::recursive_mutex> lock(mutex);
458  auto iter = callback_vector.begin();
459  for (; iter != callback_vector.end(); iter++) {
460  if ((*iter).get() == callback_shared_ptr.get()) {
461  break;
462  }
463  }
464  if (iter == callback_vector.end()) {
465  return false;
466  }
467  callback_vector.erase(iter);
468  return true;
469  };
470 
471  static_assert(
472  shutdown_type == ShutdownType::pre_shutdown || shutdown_type == ShutdownType::on_shutdown);
473 
474  if constexpr (shutdown_type == ShutdownType::pre_shutdown) {
475  return remove_callback(pre_shutdown_callbacks_mutex_, pre_shutdown_callbacks_);
476  } else {
477  return remove_callback(on_shutdown_callbacks_mutex_, on_shutdown_callbacks_);
478  }
479 }
480 
481 std::vector<rclcpp::Context::OnShutdownCallback>
483 {
484  return get_shutdown_callback<ShutdownType::on_shutdown>();
485 }
486 
487 std::vector<rclcpp::Context::PreShutdownCallback>
489 {
490  return get_shutdown_callback<ShutdownType::pre_shutdown>();
491 }
492 
493 template<Context::ShutdownType shutdown_type>
494 std::vector<rclcpp::Context::ShutdownCallback>
495 Context::get_shutdown_callback() const
496 {
497  const auto get_callback_vector = [](auto & mutex, auto & callback_set) {
498  const std::lock_guard<std::recursive_mutex> lock(mutex);
499  std::vector<rclcpp::Context::ShutdownCallback> callbacks;
500  for (auto & callback : callback_set) {
501  callbacks.push_back(*callback);
502  }
503  return callbacks;
504  };
505 
506  static_assert(
507  shutdown_type == ShutdownType::pre_shutdown || shutdown_type == ShutdownType::on_shutdown);
508 
509  if constexpr (shutdown_type == ShutdownType::pre_shutdown) {
510  return get_callback_vector(pre_shutdown_callbacks_mutex_, pre_shutdown_callbacks_);
511  } else {
512  return get_callback_vector(on_shutdown_callbacks_mutex_, on_shutdown_callbacks_);
513  }
514 }
515 
516 std::shared_ptr<rcl_context_t>
518 {
519  return rcl_context_;
520 }
521 
522 std::shared_ptr<rclcpp::graph_listener::GraphListener>
523 Context::get_graph_listener()
524 {
525  return graph_listener_;
526 }
527 
528 bool
529 Context::sleep_for(const std::chrono::nanoseconds & nanoseconds)
530 {
531  std::chrono::nanoseconds time_left = nanoseconds;
532  do {
533  {
534  std::unique_lock<std::mutex> lock(interrupt_mutex_);
535  auto start = std::chrono::steady_clock::now();
536  // this will release the lock while waiting
537  interrupt_condition_variable_.wait_for(lock, time_left);
538  time_left -= std::chrono::steady_clock::now() - start;
539  }
540  } while (time_left > std::chrono::nanoseconds::zero() && this->is_valid());
541  // Return true if the timeout elapsed successfully, otherwise false.
542  return this->is_valid();
543 }
544 
545 void
547 {
548  interrupt_condition_variable_.notify_all();
549 }
550 
551 void
552 Context::clean_up()
553 {
554  shutdown_reason_ = "";
555  rcl_context_.reset();
556  sub_contexts_.clear();
557 }
558 
559 std::vector<Context::SharedPtr>
561 {
562  WeakContextsWrapper::SharedPtr weak_contexts = get_weak_contexts();
563  return weak_contexts->get_contexts();
564 }
#define rcl_get_default_allocator
Return a properly initialized rcl_allocator_t with default values.
Definition: allocator.h:37
Thrown when init is called on an already initialized context.
Definition: context.hpp:47
Context which encapsulates shared state between nodes and other similar entities.
Definition: context.hpp:80
virtual RCLCPP_PUBLIC void init(int argc, char const *const *argv, const rclcpp::InitOptions &init_options=rclcpp::InitOptions())
Initialize the context, and the underlying elements like the rcl context.
Definition: context.cpp:194
RCLCPP_PUBLIC std::vector< OnShutdownCallback > get_on_shutdown_callbacks() const
Return the shutdown callbacks.
Definition: context.cpp:482
RCLCPP_PUBLIC std::vector< PreShutdownCallback > get_pre_shutdown_callbacks() const
Return the pre-shutdown callbacks.
Definition: context.cpp:488
RCLCPP_PUBLIC size_t get_domain_id() const
Return actual domain id.
Definition: context.cpp:302
RCLCPP_PUBLIC std::string shutdown_reason() const
Return the shutdown reason, or empty string if not shutdown.
Definition: context.cpp:313
RCLCPP_PUBLIC const rclcpp::InitOptions & get_init_options() const
Return the init options used during init.
Definition: context.cpp:290
RCLCPP_PUBLIC bool sleep_for(const std::chrono::nanoseconds &nanoseconds)
Sleep for a given period of time or until shutdown() is called.
Definition: context.cpp:529
RCLCPP_PUBLIC void interrupt_all_sleep_for()
Interrupt any blocking sleep_for calls, causing them to return immediately and return true.
Definition: context.cpp:546
virtual RCLCPP_PUBLIC OnShutdownCallback on_shutdown(OnShutdownCallback callback)
Add a on_shutdown callback to be called when shutdown is called for this context.
Definition: context.cpp:391
virtual RCLCPP_PUBLIC OnShutdownCallbackHandle add_on_shutdown_callback(OnShutdownCallback callback)
Add a on_shutdown callback to be called when shutdown is called for this context.
Definition: context.cpp:398
virtual RCLCPP_PUBLIC bool remove_pre_shutdown_callback(const PreShutdownCallbackHandle &callback_handle)
Remove an registered pre_shutdown callback.
Definition: context.cpp:416
RCLCPP_PUBLIC bool is_valid() const
Return true if the context is valid, otherwise false.
Definition: context.cpp:279
virtual RCLCPP_PUBLIC PreShutdownCallbackHandle add_pre_shutdown_callback(PreShutdownCallback callback)
Add a pre_shutdown callback to be called before shutdown is called for this context.
Definition: context.cpp:410
virtual RCLCPP_PUBLIC bool remove_on_shutdown_callback(const OnShutdownCallbackHandle &callback_handle)
Remove an registered on_shutdown callbacks.
Definition: context.cpp:404
virtual RCLCPP_PUBLIC bool shutdown(const std::string &reason)
Shutdown the context, making it uninitialized and therefore invalid for derived entities.
Definition: context.cpp:320
RCLCPP_PUBLIC std::shared_ptr< rcl_context_t > get_rcl_context()
Return the internal rcl context.
Definition: context.cpp:517
Encapsulation of options for initializing rclcpp.
RCLCPP_PUBLIC const rcl_init_options_t * get_rcl_init_options() const
Return the rcl init options.
RCLCPP_PUBLIC bool auto_initialize_logging() const
Return true if logging should be initialized when rclcpp::Context::init is called.
Class to manage vector of weak pointers to all created contexts.
Definition: context.cpp:43
Thrown when unparsed ROS specific arguments are found.
Definition: exceptions.hpp:206
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_context_fini(rcl_context_t *context)
Finalize a context.
Definition: context.c:49
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_context_get_domain_id(rcl_context_t *context, size_t *domain_id)
Returns the context domain id.
Definition: context.c:83
struct rcl_context_s rcl_context_t
Encapsulates the non-global state of an init/shutdown cycle.
RCL_PUBLIC RCL_WARN_UNUSED bool rcl_context_is_valid(const rcl_context_t *context)
Return true if the given context is currently valid, otherwise false.
Definition: context.c:94
RCL_PUBLIC RCL_WARN_UNUSED rcl_context_t rcl_get_zero_initialized_context(void)
Return a zero initialization context object.
Definition: context.c:29
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_shutdown(rcl_context_t *context)
Shutdown a given rcl context.
Definition: init.c:282
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_init(int argc, char const *const *argv, const rcl_init_options_t *options, rcl_context_t *context)
Initialization of rcl.
Definition: init.c:46
RCL_PUBLIC RCL_WARN_UNUSED const rcl_allocator_t * rcl_init_options_get_allocator(const rcl_init_options_t *init_options)
Return the allocator stored in the init_options.
Definition: init_options.c:175
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_fini(void)
Definition: logging.c:127
RCL_PUBLIC void rcl_logging_multiple_output_handler(const rcutils_log_location_t *location, int severity, const char *name, rcutils_time_point_value_t timestamp, const char *format, va_list *args)
Default output handler used by rcl.
Definition: logging.c:154
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_configure_with_output_handler(const rcl_arguments_t *global_args, const rcl_allocator_t *allocator, rcl_logging_output_handler_t output_handler)
Configure the logging system with the provided output handler.
Definition: logging.c:57
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC std::vector< Context::SharedPtr > get_contexts()
Return a copy of the list of context shared pointers.
Definition: context.cpp:560
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
Definition: logger.cpp:34
Encapsulates the non-global state of an init/shutdown cycle.
Definition: context.h:114
#define RCL_RET_OK
Success return code.
Definition: types.h:27
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24