Skip to content

Commit

Permalink
Save shared pointer of callback instead of callback handle in Context
Browse files Browse the repository at this point in the history
Signed-off-by: Barry Xu <barry.xu@sony.com>
  • Loading branch information
Barry-Xu-2018 committed Apr 29, 2021
1 parent 16be094 commit f495091
Show file tree
Hide file tree
Showing 4 changed files with 35 additions and 27 deletions.
17 changes: 9 additions & 8 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class OnShutdownCallbackHandle
using OnShutdownCallbackType = std::function<void ()>;

private:
OnShutdownCallbackType callback;
std::weak_ptr<OnShutdownCallbackType> callback;
};

/// Context which encapsulates shared state between nodes and other similar entities.
Expand Down Expand Up @@ -234,22 +234,23 @@ class Context : public std::enable_shared_from_this<Context>
* On shutdown callbacks may be registered before init and after shutdown,
* and persist on repeated init's.
*
* \param[in] callback the on shutdown callback to be registered
* \return the created shared pointer of callback handler
* \param[in] callback the on_shutdown callback to be registered
* \return the created callback handle
*/
RCLCPP_PUBLIC
virtual
OnShutdownCallbackHandle::WeakPtr
OnShutdownCallbackHandle
add_on_shutdown_callback(OnShutdownCallback callback);

/// Remove an registered on_shutdown callbacks.
/**
* \param[in] callback_handle the handle to be removed.
* \param[in] callback_handle the on_shutdown callback handle to be removed.
* \return true if the callback is found and removed, otherwise false.
*/
RCLCPP_PUBLIC
virtual
void
remove_on_shutdown_callback(const OnShutdownCallbackHandle::WeakPtr & callback_handle);
bool
remove_on_shutdown_callback(const OnShutdownCallbackHandle & callback_handle);

/// Return the shutdown callbacks.
/**
Expand Down Expand Up @@ -337,7 +338,7 @@ class Context : public std::enable_shared_from_this<Context>
// attempt to acquire another sub context.
std::recursive_mutex sub_contexts_mutex_;

std::unordered_set<OnShutdownCallbackHandle::SharedPtr> on_shutdown_callbacks_;
std::unordered_set<std::shared_ptr<OnShutdownCallback>> 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::WeakPtr shutdown_callback_handle_;
rclcpp::OnShutdownCallbackHandle shutdown_callback_handle_;
};

} // namespace rclcpp
Expand Down
37 changes: 19 additions & 18 deletions rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -318,8 +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 : on_shutdown_callbacks_) {
callback_handle->callback();
for (const auto & callback : on_shutdown_callbacks_) {
(*callback)();
}
}

Expand Down Expand Up @@ -349,43 +349,44 @@ Context::shutdown(const std::string & reason)
rclcpp::Context::OnShutdownCallback
Context::on_shutdown(OnShutdownCallback callback)
{
std::weak_ptr<OnShutdownCallbackHandle> callback_handle =
add_on_shutdown_callback(callback);
return callback_handle.lock()->callback;
OnShutdownCallbackHandle callback_handle = add_on_shutdown_callback(callback);
return *(callback_handle.callback.lock());
}

rclcpp::OnShutdownCallbackHandle::WeakPtr
rclcpp::OnShutdownCallbackHandle
Context::add_on_shutdown_callback(OnShutdownCallback callback)
{
auto handle = std::make_shared<OnShutdownCallbackHandle>();
handle->callback = callback;
auto callback_shared_ptr = std::make_shared<OnShutdownCallback>(callback);
{
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
on_shutdown_callbacks_.emplace(handle);
on_shutdown_callbacks_.emplace(callback_shared_ptr);
}
return handle;

OnShutdownCallbackHandle callback_handle;
callback_handle.callback = callback_shared_ptr;
return callback_handle;
}

void
Context::remove_on_shutdown_callback(const OnShutdownCallbackHandle::WeakPtr & callback_handle)
bool
Context::remove_on_shutdown_callback(const OnShutdownCallbackHandle & callback_handle)
{
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
auto callback_handle_shared_ptr = callback_handle.lock();
if (callback_handle_shared_ptr) {
on_shutdown_callbacks_.erase(callback_handle_shared_ptr);
auto callback_shared_ptr = callback_handle.callback.lock();
if (callback_shared_ptr == nullptr) {
return false;
}
return on_shutdown_callbacks_.erase(callback_shared_ptr) == 1;
}

std::vector<rclcpp::Context::OnShutdownCallback>
Context::get_on_shutdown_callbacks()
{
std::vector<OnShutdownCallback> callbacks;
std::unordered_set<OnShutdownCallbackHandle::SharedPtr>::iterator iter;

{
std::lock_guard<std::mutex> lock(on_shutdown_callbacks_mutex_);
for (iter = on_shutdown_callbacks_.begin(); iter != on_shutdown_callbacks_.end(); ++iter) {
callbacks.emplace_back((*iter)->callback);
for (auto & iter : on_shutdown_callbacks_) {
callbacks.emplace_back(*iter);
}
}

Expand Down
6 changes: 6 additions & 0 deletions rclcpp/test/rclcpp/test_utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,12 @@ TEST(TestUtilities, test_context_basic_access) {
EXPECT_EQ(std::string{""}, context1->shutdown_reason());
}

TEST(TestUtilities, test_context_basic_access_const_methods) {
auto context1 = std::make_shared<const rclcpp::contexts::DefaultContext>();

EXPECT_NE(nullptr, context1->get_init_options().get_rcl_init_options());
}

MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, ==)
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, !=)
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, >)
Expand Down

0 comments on commit f495091

Please sign in to comment.