Skip to content

Commit 6806cdf

Browse files
Use OnShutdown callback handle instead of OnShutdown callback (#1639)
1. Add remove_on_shutdown_callback() in rclcpp::Context Signed-off-by: Barry Xu <barry.xu@sony.com> 2. Add add_on_shutdown_callback(), which returns a handle that can be removed by remove_on_shutdown_callback(). Signed-off-by: Barry Xu <barry.xu@sony.com>
1 parent 79c2dd8 commit 6806cdf

4 files changed

Lines changed: 102 additions & 22 deletions

File tree

rclcpp/include/rclcpp/context.hpp

Lines changed: 48 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include <typeindex>
2424
#include <typeinfo>
2525
#include <unordered_map>
26+
#include <unordered_set>
2627
#include <utility>
2728
#include <vector>
2829

@@ -47,6 +48,17 @@ class ContextAlreadyInitialized : public std::runtime_error
4748
/// Forward declare WeakContextsWrapper
4849
class WeakContextsWrapper;
4950

51+
class OnShutdownCallbackHandle
52+
{
53+
friend class Context;
54+
55+
public:
56+
using OnShutdownCallbackType = std::function<void ()>;
57+
58+
private:
59+
std::weak_ptr<OnShutdownCallbackType> callback;
60+
};
61+
5062
/// Context which encapsulates shared state between nodes and other similar entities.
5163
/**
5264
* A context also represents the lifecycle between init and shutdown of rclcpp.
@@ -177,7 +189,7 @@ class Context : public std::enable_shared_from_this<Context>
177189
bool
178190
shutdown(const std::string & reason);
179191

180-
using OnShutdownCallback = std::function<void ()>;
192+
using OnShutdownCallback = OnShutdownCallbackHandle::OnShutdownCallbackType;
181193

182194
/// Add a on_shutdown callback to be called when shutdown is called for this context.
183195
/**
@@ -203,23 +215,47 @@ class Context : public std::enable_shared_from_this<Context>
203215
OnShutdownCallback
204216
on_shutdown(OnShutdownCallback callback);
205217

206-
/// Return the shutdown callbacks as const.
218+
/// Add a on_shutdown callback to be called when shutdown is called for this context.
219+
/**
220+
* These callbacks will be called in the order they are added as the second
221+
* to last step in shutdown().
222+
*
223+
* When shutdown occurs due to the signal handler, these callbacks are run
224+
* asynchronously in the dedicated singal handling thread.
225+
*
226+
* Also, shutdown() may be called from the destructor of this function.
227+
* Therefore, it is not safe to throw exceptions from these callbacks.
228+
* Instead, log errors or use some other mechanism to indicate an error has
229+
* occurred.
230+
*
231+
* On shutdown callbacks may be registered before init and after shutdown,
232+
* and persist on repeated init's.
233+
*
234+
* \param[in] callback the on_shutdown callback to be registered
235+
* \return the created callback handle
236+
*/
237+
RCLCPP_PUBLIC
238+
virtual
239+
OnShutdownCallbackHandle
240+
add_on_shutdown_callback(OnShutdownCallback callback);
241+
242+
/// Remove an registered on_shutdown callbacks.
207243
/**
208-
* Using the returned reference is not thread-safe with calls that modify
209-
* the list of "on shutdown" callbacks, i.e. on_shutdown().
244+
* \param[in] callback_handle the on_shutdown callback handle to be removed.
245+
* \return true if the callback is found and removed, otherwise false.
210246
*/
211247
RCLCPP_PUBLIC
212-
const std::vector<OnShutdownCallback> &
213-
get_on_shutdown_callbacks() const;
248+
virtual
249+
bool
250+
remove_on_shutdown_callback(const OnShutdownCallbackHandle & callback_handle);
214251

215252
/// Return the shutdown callbacks.
216253
/**
217-
* Using the returned reference is not thread-safe with calls that modify
218-
* the list of "on shutdown" callbacks, i.e. on_shutdown().
254+
* Returned callbacks are a copy of the registered callbacks.
219255
*/
220256
RCLCPP_PUBLIC
221-
std::vector<OnShutdownCallback> &
222-
get_on_shutdown_callbacks();
257+
std::vector<OnShutdownCallback>
258+
get_on_shutdown_callbacks() const;
223259

224260
/// Return the internal rcl context.
225261
RCLCPP_PUBLIC
@@ -299,8 +335,8 @@ class Context : public std::enable_shared_from_this<Context>
299335
// attempt to acquire another sub context.
300336
std::recursive_mutex sub_contexts_mutex_;
301337

302-
std::vector<OnShutdownCallback> on_shutdown_callbacks_;
303-
std::mutex on_shutdown_callbacks_mutex_;
338+
std::unordered_set<std::shared_ptr<OnShutdownCallback>> on_shutdown_callbacks_;
339+
mutable std::mutex on_shutdown_callbacks_mutex_;
304340

305341
/// Condition variable for timed sleep (see sleep_for).
306342
std::condition_variable interrupt_condition_variable_;

rclcpp/include/rclcpp/executor.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
#include "rcl/guard_condition.h"
3131
#include "rcl/wait.h"
3232

33+
#include "rclcpp/context.hpp"
3334
#include "rclcpp/contexts/default_context.hpp"
3435
#include "rclcpp/guard_condition.hpp"
3536
#include "rclcpp/executor_options.hpp"
@@ -571,6 +572,9 @@ class Executor
571572
/// nodes that are associated with the executor
572573
std::list<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>
573574
weak_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
575+
576+
/// shutdown callback handle registered to Context
577+
rclcpp::OnShutdownCallbackHandle shutdown_callback_handle_;
574578
};
575579

576580
} // namespace rclcpp

rclcpp/src/rclcpp/context.cpp

Lines changed: 41 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -315,9 +315,13 @@ Context::shutdown(const std::string & reason)
315315
// set shutdown reason
316316
shutdown_reason_ = reason;
317317
// call each shutdown callback
318-
for (const auto & callback : on_shutdown_callbacks_) {
319-
callback();
318+
{
319+
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
320+
for (const auto & callback : on_shutdown_callbacks_) {
321+
(*callback)();
322+
}
320323
}
324+
321325
// interrupt all blocking sleep_for() and all blocking executors or wait sets
322326
this->interrupt_all_sleep_for();
323327
// remove self from the global contexts
@@ -344,20 +348,48 @@ Context::shutdown(const std::string & reason)
344348
rclcpp::Context::OnShutdownCallback
345349
Context::on_shutdown(OnShutdownCallback callback)
346350
{
347-
on_shutdown_callbacks_.push_back(callback);
351+
add_on_shutdown_callback(callback);
348352
return callback;
349353
}
350354

351-
const std::vector<rclcpp::Context::OnShutdownCallback> &
352-
Context::get_on_shutdown_callbacks() const
355+
rclcpp::OnShutdownCallbackHandle
356+
Context::add_on_shutdown_callback(OnShutdownCallback callback)
353357
{
354-
return on_shutdown_callbacks_;
358+
auto callback_shared_ptr = std::make_shared<OnShutdownCallback>(callback);
359+
{
360+
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
361+
on_shutdown_callbacks_.emplace(callback_shared_ptr);
362+
}
363+
364+
OnShutdownCallbackHandle callback_handle;
365+
callback_handle.callback = callback_shared_ptr;
366+
return callback_handle;
355367
}
356368

357-
std::vector<rclcpp::Context::OnShutdownCallback> &
358-
Context::get_on_shutdown_callbacks()
369+
bool
370+
Context::remove_on_shutdown_callback(const OnShutdownCallbackHandle & callback_handle)
359371
{
360-
return on_shutdown_callbacks_;
372+
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
373+
auto callback_shared_ptr = callback_handle.callback.lock();
374+
if (callback_shared_ptr == nullptr) {
375+
return false;
376+
}
377+
return on_shutdown_callbacks_.erase(callback_shared_ptr) == 1;
378+
}
379+
380+
std::vector<rclcpp::Context::OnShutdownCallback>
381+
Context::get_on_shutdown_callbacks() const
382+
{
383+
std::vector<OnShutdownCallback> callbacks;
384+
385+
{
386+
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
387+
for (auto & iter : on_shutdown_callbacks_) {
388+
callbacks.emplace_back(*iter);
389+
}
390+
}
391+
392+
return callbacks;
361393
}
362394

363395
std::shared_ptr<rcl_context_t>

rclcpp/src/rclcpp/executor.cpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ Executor::Executor(const rclcpp::ExecutorOptions & options)
5656
throw_from_rcl_error(ret, "Failed to create interrupt guard condition in Executor constructor");
5757
}
5858

59-
context_->on_shutdown(
59+
shutdown_callback_handle_ = context_->add_on_shutdown_callback(
6060
[weak_gc = std::weak_ptr<rclcpp::GuardCondition>{shutdown_guard_condition_}]() {
6161
auto strong_gc = weak_gc.lock();
6262
if (strong_gc) {
@@ -138,6 +138,14 @@ Executor::~Executor()
138138
}
139139
// Remove and release the sigint guard condition
140140
memory_strategy_->remove_guard_condition(&shutdown_guard_condition_->get_rcl_guard_condition());
141+
142+
// Remove shutdown callback handle registered to Context
143+
if (!context_->remove_on_shutdown_callback(shutdown_callback_handle_)) {
144+
RCUTILS_LOG_ERROR_NAMED(
145+
"rclcpp",
146+
"failed to remove registered on_shutdown callback");
147+
rcl_reset_error();
148+
}
141149
}
142150

143151
std::vector<rclcpp::CallbackGroup::WeakPtr>

0 commit comments

Comments
 (0)