Skip to content

Commit

Permalink
Update code based on review comments
Browse files Browse the repository at this point in the history
1. Context hold the shutdown callback handle
2. Change rclcpp::on_shutdown()
3. Add new interface rclcpp::remove_on_shutdown()

Signed-off-by: Barry Xu <barry.xu@sony.com>
  • Loading branch information
Barry-Xu-2018 committed Apr 23, 2021
1 parent ad35b60 commit e044aab
Show file tree
Hide file tree
Showing 7 changed files with 62 additions and 34 deletions.
19 changes: 10 additions & 9 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <typeindex>
#include <typeinfo>
#include <unordered_map>
#include <unordered_set>
#include <utility>
#include <vector>

Expand Down Expand Up @@ -192,7 +193,7 @@ class Context : public std::enable_shared_from_this<Context>
* to last step in shutdown().
*
* When shutdown occurs due to the signal handler, these callbacks are run
* asynchronoulsy in the dedicated singal handling thread.
* asynchronously in the dedicated singal handling thread.
*
* Also, shutdown() may be called from the destructor of this function.
* Therefore, it is not safe to throw exceptions from these callbacks.
Expand All @@ -203,29 +204,29 @@ class Context : public std::enable_shared_from_this<Context>
* and persist on repeated init's.
*
* \param[in] callback the on shutdown callback to be registered
* \return the created shared pointer of callback handler
* \return the weak pointer to registered callback handler
*/
RCLCPP_PUBLIC
virtual
OnShutdownCallbackHandle::SharedPtr
OnShutdownCallbackHandle::WeakPtr
on_shutdown(OnShutdownCallbackHandle::OnShutdownCallbackType callback);

/// Remove a on_shutdown callback handle registered with on_shutdown.
/// Remove a specified shutdown callback handle.
/**
* \param[in] callback_handle the on shutdown callback handle to be removed.
* \param[in] callback_handle the weak pointer to a shutdown callback handle
*/
RCLCPP_PUBLIC
virtual
void
remove_on_shutdown_callback(OnShutdownCallbackHandle::SharedPtr callback_handle);
remove_on_shutdown_callback(const OnShutdownCallbackHandle::WeakPtr callback_handle);

/// Return the shutdown callback handles as const.
/**
* Using the returned reference is not thread-safe with calls that modify
* the list of "on shutdown" callback handles, i.e. on_shutdown().
*/
RCLCPP_PUBLIC
const std::vector<OnShutdownCallbackHandle::WeakPtr> &
const std::unordered_set<OnShutdownCallbackHandle::SharedPtr> &
get_on_shutdown_callbacks() const;

/// Return the shutdown callback handles
Expand All @@ -234,7 +235,7 @@ class Context : public std::enable_shared_from_this<Context>
* the list of "on shutdown" callback handles, i.e. on_shutdown().
*/
RCLCPP_PUBLIC
std::vector<OnShutdownCallbackHandle::WeakPtr> &
std::unordered_set<OnShutdownCallbackHandle::SharedPtr> &
get_on_shutdown_callbacks();

/// Return the internal rcl context.
Expand Down Expand Up @@ -315,7 +316,7 @@ class Context : public std::enable_shared_from_this<Context>
// attempt to acquire another sub context.
std::recursive_mutex sub_contexts_mutex_;

std::vector<OnShutdownCallbackHandle::WeakPtr> on_shutdown_callbacks_;
std::unordered_set<OnShutdownCallbackHandle::SharedPtr> on_shutdown_callbacks_;
std::mutex on_shutdown_callbacks_mutex_;

/// Condition variable for timed sleep (see sleep_for).
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -574,7 +574,7 @@ class Executor
weak_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

/// shutdown callback handle registered to Context
rclcpp::OnShutdownCallbackHandle::SharedPtr shutdown_callback_handle_;
rclcpp::OnShutdownCallbackHandle::WeakPtr shutdown_callback_handle_;
};

} // namespace rclcpp
Expand Down
3 changes: 3 additions & 0 deletions rclcpp/include/rclcpp/graph_listener.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,6 +187,9 @@ class GraphListener : public std::enable_shared_from_this<GraphListener>
mutable std::mutex node_graph_interfaces_mutex_;
std::vector<rclcpp::node_interfaces::NodeGraphInterface *> node_graph_interfaces_;

/// shutdown callback handle registered to Context
rclcpp::OnShutdownCallbackHandle::WeakPtr shutdown_callback_handle_;

rcl_guard_condition_t interrupt_guard_condition_ = rcl_get_zero_initialized_guard_condition();
rcl_wait_set_t wait_set_ = rcl_get_zero_initialized_wait_set();
};
Expand Down
14 changes: 13 additions & 1 deletion rclcpp/include/rclcpp/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,11 +177,23 @@ shutdown(
* \sa rclcpp::Context::on_shutdown()
* \param[in] callback to be called when the given context is shutdown
* \param[in] context with which to associate the context
* \return the weak pointer to registered callback handler
*/
RCLCPP_PUBLIC
void
OnShutdownCallbackHandle::WeakPtr
on_shutdown(std::function<void()> callback, rclcpp::Context::SharedPtr context = nullptr);

/// Remove a specified shutdown callback handle.
/**
* \param[in] callback_handle the weak pointer to a shutdown callback handle
* \param[in] context with which to associate the context
*/
RCLCPP_PUBLIC
void
remove_on_shutdown(
const OnShutdownCallbackHandle::WeakPtr callback_handle,
rclcpp::Context::SharedPtr context = nullptr);

/// Use the global condition variable to block for the specified amount of time.
/**
* This function can be interrupted early if the associated context becomes
Expand Down
35 changes: 15 additions & 20 deletions rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <sstream>
#include <string>
#include <vector>
#include <unordered_set>
#include <utility>

#include "rcl/init.h"
Expand Down Expand Up @@ -317,11 +318,8 @@ Context::shutdown(const std::string & reason)
// call each shutdown callback
{
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
for (const auto & callback_handle_weak_ptr : on_shutdown_callbacks_) {
auto callback_handle = callback_handle_weak_ptr.lock();
if (callback_handle) {
callback_handle->callback();
}
for (const auto & callback_handle : on_shutdown_callbacks_) {
callback_handle->callback();
}
}

Expand All @@ -348,38 +346,35 @@ Context::shutdown(const std::string & reason)
return true;
}

rclcpp::OnShutdownCallbackHandle::SharedPtr
rclcpp::OnShutdownCallbackHandle::WeakPtr
Context::on_shutdown(OnShutdownCallbackHandle::OnShutdownCallbackType callback)
{
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
auto handle = std::make_shared<OnShutdownCallbackHandle>();
handle->callback = callback;
on_shutdown_callbacks_.push_back(handle);
{
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
on_shutdown_callbacks_.emplace(handle);
}
return handle;
}

void
Context::remove_on_shutdown_callback(OnShutdownCallbackHandle::SharedPtr callback_handle)
Context::remove_on_shutdown_callback(const OnShutdownCallbackHandle::WeakPtr callback_handle)
{
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
auto it = std::find_if(
on_shutdown_callbacks_.begin(),
on_shutdown_callbacks_.end(),
[callback_handle](const auto & weak_handle) {
return callback_handle.get() == weak_handle.lock().get();
});
if (it != on_shutdown_callbacks_.end()) {
on_shutdown_callbacks_.erase(it);
auto callback_handle_shared_ptr = callback_handle.lock();
if (callback_handle_shared_ptr) {
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
on_shutdown_callbacks_.erase(callback_handle_shared_ptr);
}
}

const std::vector<rclcpp::OnShutdownCallbackHandle::WeakPtr> &
const std::unordered_set<rclcpp::OnShutdownCallbackHandle::SharedPtr> &
Context::get_on_shutdown_callbacks() const
{
return on_shutdown_callbacks_;
}

std::vector<rclcpp::OnShutdownCallbackHandle::WeakPtr> &
std::unordered_set<rclcpp::OnShutdownCallbackHandle::SharedPtr> &
Context::get_on_shutdown_callbacks()
{
return on_shutdown_callbacks_;
Expand Down
6 changes: 5 additions & 1 deletion rclcpp/src/rclcpp/graph_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,10 @@ GraphListener::GraphListener(const std::shared_ptr<Context> & parent_context)

GraphListener::~GraphListener()
{
auto parent_context = weak_parent_context_.lock();
if (parent_context) {
parent_context->remove_on_shutdown_callback(shutdown_callback_handle_);
}
this->shutdown(std::nothrow);
}

Expand Down Expand Up @@ -90,7 +94,7 @@ GraphListener::start_if_not_started()
// This is important to ensure that the wait set is finalized before
// destruction of static objects occurs.
std::weak_ptr<GraphListener> weak_this = shared_from_this();
parent_context->on_shutdown(
shutdown_callback_handle_ = parent_context->on_shutdown(
[weak_this]() {
auto shared_this = weak_this.lock();
if (shared_this) {
Expand Down
17 changes: 15 additions & 2 deletions rclcpp/src/rclcpp/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <vector>

#include "./signal_handler.hpp"
#include "rclcpp/context.hpp"
#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/detail/utilities.hpp"
#include "rclcpp/exceptions.hpp"
Expand Down Expand Up @@ -177,14 +178,26 @@ shutdown(Context::SharedPtr context, const std::string & reason)
return ret;
}

void
OnShutdownCallbackHandle::WeakPtr
on_shutdown(std::function<void()> callback, Context::SharedPtr context)
{
using rclcpp::contexts::get_global_default_context;
if (nullptr == context) {
context = get_global_default_context();
}
context->on_shutdown(callback);
return context->on_shutdown(callback);
}

void
remove_on_shutdown(
const OnShutdownCallbackHandle::WeakPtr callback_handle,
Context::SharedPtr context)
{
using rclcpp::contexts::get_global_default_context;
if (nullptr == context) {
context = get_global_default_context();
}
context->remove_on_shutdown_callback(callback_handle);
}

bool
Expand Down

0 comments on commit e044aab

Please sign in to comment.