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