ROS 2 rclcpp + rcl - humble  humble
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 
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 {}
150 
151 Context::~Context()
152 {
153  // acquire the init lock to prevent race conditions with init and shutdown
154  // this will not prevent errors, but will maybe make them easier to reproduce
155  std::lock_guard<std::recursive_mutex> lock(init_mutex_);
156  try {
157  this->shutdown("context destructor was called while still not shutdown");
158  // at this point it is shutdown and cannot reinit
159  // clean_up will finalize the rcl context
160  this->clean_up();
161  } catch (const std::exception & exc) {
162  RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "unhandled exception in ~Context(): %s", exc.what());
163  } catch (...) {
164  RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "unhandled exception in ~Context()");
165  }
166 }
167 
168 RCLCPP_LOCAL
169 void
170 __delete_context(rcl_context_t * context)
171 {
172  if (context) {
173  if (rcl_context_is_valid(context)) {
174  RCLCPP_ERROR(
175  rclcpp::get_logger("rclcpp"), "rcl context unexpectedly not shutdown during cleanup");
176  } else {
177  // if context pointer is not null and is shutdown, then it's ready for fini
178  rcl_ret_t ret = rcl_context_fini(context);
179  if (RCL_RET_OK != ret) {
180  RCLCPP_ERROR(
181  rclcpp::get_logger("rclcpp"),
182  "failed to finalize context: %s", rcl_get_error_string().str);
183  rcl_reset_error();
184  }
185  }
186  delete context;
187  }
188 }
189 
190 void
192  int argc,
193  char const * const * argv,
194  const rclcpp::InitOptions & init_options)
195 {
196  std::lock_guard<std::recursive_mutex> init_lock(init_mutex_);
197  if (this->is_valid()) {
199  }
200  this->clean_up();
201  rcl_context_t * context = new rcl_context_t;
202  if (!context) {
203  throw std::runtime_error("failed to allocate memory for rcl context");
204  }
206  rcl_ret_t ret = rcl_init(argc, argv, init_options.get_rcl_init_options(), context);
207  if (RCL_RET_OK != ret) {
208  delete context;
209  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialize rcl");
210  }
211  rcl_context_.reset(context, __delete_context);
212 
213  if (init_options.auto_initialize_logging()) {
214  logging_mutex_ = get_global_logging_mutex();
215  std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
216  size_t & count = get_logging_reference_count();
217  if (0u == count) {
219  &rcl_context_->global_arguments,
221  rclcpp_logging_output_handler);
222  if (RCL_RET_OK != ret) {
223  rcl_context_.reset();
224  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging");
225  }
226  } else {
227  RCLCPP_WARN(
228  rclcpp::get_logger("rclcpp"),
229  "logging was initialized more than once");
230  }
231  ++count;
232  }
233 
234  try {
235  std::vector<std::string> unparsed_ros_arguments = detail::get_unparsed_ros_arguments(
236  argc, argv, &(rcl_context_->global_arguments), rcl_get_default_allocator());
237  if (!unparsed_ros_arguments.empty()) {
238  throw exceptions::UnknownROSArgsError(std::move(unparsed_ros_arguments));
239  }
240 
241  init_options_ = init_options;
242 
243  weak_contexts_ = get_weak_contexts();
244  weak_contexts_->add_context(this->shared_from_this());
245  } catch (const std::exception & e) {
246  ret = rcl_shutdown(rcl_context_.get());
247  rcl_context_.reset();
248  if (RCL_RET_OK != ret) {
249  std::ostringstream oss;
250  oss << "While handling: " << e.what() << std::endl <<
251  " another exception was thrown";
252  rclcpp::exceptions::throw_from_rcl_error(ret, oss.str());
253  }
254  throw;
255  }
256 }
257 
258 bool
260 {
261  // Take a local copy of the shared pointer to avoid it getting nulled under our feet.
262  auto local_rcl_context = rcl_context_;
263  if (!local_rcl_context) {
264  return false;
265  }
266  return rcl_context_is_valid(local_rcl_context.get());
267 }
268 
269 const rclcpp::InitOptions &
271 {
272  return init_options_;
273 }
274 
277 {
278  return init_options_;
279 }
280 
281 size_t
283 {
284  size_t domain_id;
285  rcl_ret_t ret = rcl_context_get_domain_id(rcl_context_.get(), &domain_id);
286  if (RCL_RET_OK != ret) {
287  rclcpp::exceptions::throw_from_rcl_error(ret, "failed to get domain id from context");
288  }
289  return domain_id;
290 }
291 
292 std::string
294 {
295  std::lock_guard<std::recursive_mutex> lock(init_mutex_);
296  return shutdown_reason_;
297 }
298 
299 bool
300 Context::shutdown(const std::string & reason)
301 {
302  // prevent races
303  std::lock_guard<std::recursive_mutex> init_lock(init_mutex_);
304  // ensure validity
305  if (!this->is_valid()) {
306  // if it is not valid, then it cannot be shutdown
307  return false;
308  }
309 
310  // call each pre-shutdown callback
311  {
312  std::lock_guard<std::mutex> lock{pre_shutdown_callbacks_mutex_};
313  for (const auto & callback : pre_shutdown_callbacks_) {
314  (*callback)();
315  }
316  }
317 
318  // rcl shutdown
319  rcl_ret_t ret = rcl_shutdown(rcl_context_.get());
320  if (RCL_RET_OK != ret) {
321  rclcpp::exceptions::throw_from_rcl_error(ret);
322  }
323  // set shutdown reason
324  shutdown_reason_ = reason;
325  // call each shutdown callback
326  {
327  std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
328  for (const auto & callback : on_shutdown_callbacks_) {
329  (*callback)();
330  }
331  }
332 
333  // interrupt all blocking sleep_for() and all blocking executors or wait sets
334  this->interrupt_all_sleep_for();
335  // remove self from the global contexts
336  weak_contexts_->remove_context(this);
337  // shutdown logger
338  if (logging_mutex_) {
339  // logging was initialized by this context
340  std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
341  size_t & count = get_logging_reference_count();
342  if (0u == --count) {
343  rcl_ret_t rcl_ret = rcl_logging_fini();
344  if (RCL_RET_OK != rcl_ret) {
345  RCUTILS_SAFE_FWRITE_TO_STDERR(
346  RCUTILS_STRINGIFY(__file__) ":"
347  RCUTILS_STRINGIFY(__LINE__)
348  " failed to fini logging");
349  rcl_reset_error();
350  }
351  }
352  }
353  return true;
354 }
355 
356 rclcpp::Context::OnShutdownCallback
357 Context::on_shutdown(OnShutdownCallback callback)
358 {
359  add_on_shutdown_callback(callback);
360  return callback;
361 }
362 
364 Context::add_on_shutdown_callback(OnShutdownCallback callback)
365 {
366  return add_shutdown_callback(ShutdownType::on_shutdown, callback);
367 }
368 
369 bool
371 {
372  return remove_shutdown_callback(ShutdownType::on_shutdown, callback_handle);
373 }
374 
376 Context::add_pre_shutdown_callback(PreShutdownCallback callback)
377 {
378  return add_shutdown_callback(ShutdownType::pre_shutdown, callback);
379 }
380 
381 bool
383  const PreShutdownCallbackHandle & callback_handle)
384 {
385  return remove_shutdown_callback(ShutdownType::pre_shutdown, callback_handle);
386 }
387 
389 Context::add_shutdown_callback(
390  ShutdownType shutdown_type,
391  ShutdownCallback callback)
392 {
393  auto callback_shared_ptr =
394  std::make_shared<ShutdownCallbackHandle::ShutdownCallbackType>(callback);
395 
396  switch (shutdown_type) {
397  case ShutdownType::pre_shutdown:
398  {
399  std::lock_guard<std::mutex> lock(pre_shutdown_callbacks_mutex_);
400  pre_shutdown_callbacks_.emplace(callback_shared_ptr);
401  }
402  break;
403  case ShutdownType::on_shutdown:
404  {
405  std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
406  on_shutdown_callbacks_.emplace(callback_shared_ptr);
407  }
408  break;
409  }
410 
411  ShutdownCallbackHandle callback_handle;
412  callback_handle.callback = callback_shared_ptr;
413  return callback_handle;
414 }
415 
416 bool
417 Context::remove_shutdown_callback(
418  ShutdownType shutdown_type,
419  const ShutdownCallbackHandle & callback_handle)
420 {
421  std::mutex * mutex_ptr = nullptr;
422  std::unordered_set<
423  std::shared_ptr<ShutdownCallbackHandle::ShutdownCallbackType>> * callback_list_ptr;
424 
425  switch (shutdown_type) {
426  case ShutdownType::pre_shutdown:
427  mutex_ptr = &pre_shutdown_callbacks_mutex_;
428  callback_list_ptr = &pre_shutdown_callbacks_;
429  break;
430  case ShutdownType::on_shutdown:
431  mutex_ptr = &on_shutdown_callbacks_mutex_;
432  callback_list_ptr = &on_shutdown_callbacks_;
433  break;
434  }
435 
436  std::lock_guard<std::mutex> lock(*mutex_ptr);
437  auto callback_shared_ptr = callback_handle.callback.lock();
438  if (callback_shared_ptr == nullptr) {
439  return false;
440  }
441  return callback_list_ptr->erase(callback_shared_ptr) == 1;
442 }
443 
444 std::vector<rclcpp::Context::OnShutdownCallback>
446 {
447  return get_shutdown_callback(ShutdownType::on_shutdown);
448 }
449 
450 std::vector<rclcpp::Context::PreShutdownCallback>
452 {
453  return get_shutdown_callback(ShutdownType::pre_shutdown);
454 }
455 
456 std::vector<rclcpp::Context::ShutdownCallback>
457 Context::get_shutdown_callback(ShutdownType shutdown_type) const
458 {
459  std::mutex * mutex_ptr = nullptr;
460  const std::unordered_set<
461  std::shared_ptr<ShutdownCallbackHandle::ShutdownCallbackType>> * callback_list_ptr;
462 
463  switch (shutdown_type) {
464  case ShutdownType::pre_shutdown:
465  mutex_ptr = &pre_shutdown_callbacks_mutex_;
466  callback_list_ptr = &pre_shutdown_callbacks_;
467  break;
468  case ShutdownType::on_shutdown:
469  mutex_ptr = &on_shutdown_callbacks_mutex_;
470  callback_list_ptr = &on_shutdown_callbacks_;
471  break;
472  }
473 
474  std::vector<rclcpp::Context::ShutdownCallback> callbacks;
475  {
476  std::lock_guard<std::mutex> lock(*mutex_ptr);
477  for (auto & iter : *callback_list_ptr) {
478  callbacks.emplace_back(*iter);
479  }
480  }
481 
482  return callbacks;
483 }
484 
485 std::shared_ptr<rcl_context_t>
487 {
488  return rcl_context_;
489 }
490 
491 bool
492 Context::sleep_for(const std::chrono::nanoseconds & nanoseconds)
493 {
494  std::chrono::nanoseconds time_left = nanoseconds;
495  do {
496  {
497  std::unique_lock<std::mutex> lock(interrupt_mutex_);
498  auto start = std::chrono::steady_clock::now();
499  // this will release the lock while waiting
500  interrupt_condition_variable_.wait_for(lock, time_left);
501  time_left -= std::chrono::steady_clock::now() - start;
502  }
503  } while (time_left > std::chrono::nanoseconds::zero() && this->is_valid());
504  // Return true if the timeout elapsed successfully, otherwise false.
505  return this->is_valid();
506 }
507 
508 void
510 {
511  interrupt_condition_variable_.notify_all();
512 }
513 
514 void
515 Context::clean_up()
516 {
517  shutdown_reason_ = "";
518  rcl_context_.reset();
519  sub_contexts_.clear();
520 }
521 
522 std::vector<Context::SharedPtr>
524 {
525  WeakContextsWrapper::SharedPtr weak_contexts = get_weak_contexts();
526  return weak_contexts->get_contexts();
527 }
#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:43
Context which encapsulates shared state between nodes and other similar entities.
Definition: context.hpp:73
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:191
RCLCPP_PUBLIC std::vector< OnShutdownCallback > get_on_shutdown_callbacks() const
Return the shutdown callbacks.
Definition: context.cpp:445
RCLCPP_PUBLIC std::vector< PreShutdownCallback > get_pre_shutdown_callbacks() const
Return the pre-shutdown callbacks.
Definition: context.cpp:451
RCLCPP_PUBLIC size_t get_domain_id() const
Return actual domain id.
Definition: context.cpp:282
RCLCPP_PUBLIC std::string shutdown_reason() const
Return the shutdown reason, or empty string if not shutdown.
Definition: context.cpp:293
RCLCPP_PUBLIC const rclcpp::InitOptions & get_init_options() const
Return the init options used during init.
Definition: context.cpp:270
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:492
virtual RCLCPP_PUBLIC void interrupt_all_sleep_for()
Interrupt any blocking sleep_for calls, causing them to return immediately and return true.
Definition: context.cpp:509
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:357
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:364
virtual RCLCPP_PUBLIC bool remove_pre_shutdown_callback(const PreShutdownCallbackHandle &callback_handle)
Remove an registered pre_shutdown callback.
Definition: context.cpp:382
RCLCPP_PUBLIC bool is_valid() const
Return true if the context is valid, otherwise false.
Definition: context.cpp:259
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:376
virtual RCLCPP_PUBLIC bool remove_on_shutdown_callback(const OnShutdownCallbackHandle &callback_handle)
Remove an registered on_shutdown callbacks.
Definition: context.cpp:370
virtual RCLCPP_PUBLIC bool shutdown(const std::string &reason)
Shutdown the context, making it uninitialized and therefore invalid for derived entities.
Definition: context.cpp:300
RCLCPP_PUBLIC std::shared_ptr< rcl_context_t > get_rcl_context()
Return the internal rcl context.
Definition: context.cpp:486
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: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:232
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:169
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_fini(void)
Definition: logging.c:125
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:152
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:523
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
Definition: logger.cpp:27
Encapsulates the non-global state of an init/shutdown cycle.
Definition: context.h:114
#define RCL_RET_OK
Success return code.
Definition: types.h:26
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:23