diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp
index 95b0d7fcc8..181f0c9a6a 100644
--- a/rclcpp/src/rclcpp/executor.cpp
+++ b/rclcpp/src/rclcpp/executor.cpp
@@ -275,7 +275,7 @@ Executor::spin_until_future_complete_impl(
   if (spinning.exchange(true)) {
     throw std::runtime_error("spin_until_future_complete() called while already spinning");
   }
-  RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
+  RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
   while (rclcpp::ok(this->context_) && spinning.load()) {
     // Do one item of work.
     spin_once_impl(timeout_left);
@@ -364,7 +364,7 @@ Executor::spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive)
   if (spinning.exchange(true)) {
     throw std::runtime_error("spin_some() called while already spinning");
   }
-  RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
+  RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
 
   // clear the wait result and wait for work without blocking to collect the work
   // for the first time
@@ -431,7 +431,7 @@ Executor::spin_once(std::chrono::nanoseconds timeout)
   if (spinning.exchange(true)) {
     throw std::runtime_error("spin_once() called while already spinning");
   }
-  RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
+  RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
   spin_once_impl(timeout);
 }
 
diff --git a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp
index 2d5c76e817..130b4d953f 100644
--- a/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp
+++ b/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp
@@ -55,7 +55,7 @@ MultiThreadedExecutor::spin()
   if (spinning.exchange(true)) {
     throw std::runtime_error("spin() called while already spinning");
   }
-  RCPPUTILS_SCOPE_EXIT(this->spinning.store(false););
+  RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
   std::vector<std::thread> threads;
   size_t thread_id = 0;
   {
diff --git a/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp b/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp
index 975733b497..689bbae398 100644
--- a/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp
+++ b/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp
@@ -30,7 +30,7 @@ SingleThreadedExecutor::spin()
   if (spinning.exchange(true)) {
     throw std::runtime_error("spin() called while already spinning");
   }
-  RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
+  RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
 
   // Clear any previous result and rebuild the waitset
   this->wait_result_.reset();
diff --git a/rclcpp/test/rclcpp/CMakeLists.txt b/rclcpp/test/rclcpp/CMakeLists.txt
index b950bd149b..b171b215d9 100644
--- a/rclcpp/test/rclcpp/CMakeLists.txt
+++ b/rclcpp/test/rclcpp/CMakeLists.txt
@@ -641,7 +641,7 @@ ament_add_gtest(test_executor test_executor.cpp
   TIMEOUT 120)
 ament_add_test_label(test_executor mimick)
 if(TARGET test_executor)
-  target_link_libraries(test_executor ${PROJECT_NAME} mimick)
+  target_link_libraries(test_executor ${PROJECT_NAME} mimick ${test_msgs_TARGETS})
 endif()
 
 ament_add_gtest(test_graph_listener test_graph_listener.cpp)
diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp
index 5aae03c5bc..a7129d4488 100644
--- a/rclcpp/test/rclcpp/executors/test_executors.cpp
+++ b/rclcpp/test/rclcpp/executors/test_executors.cpp
@@ -39,6 +39,7 @@
 #include "rclcpp/time_source.hpp"
 
 #include "test_msgs/msg/empty.hpp"
+#include "test_msgs/srv/empty.hpp"
 
 #include "./executor_types.hpp"
 #include "./test_waitable.hpp"
@@ -831,3 +832,27 @@ TEST(TestExecutors, testSpinWithNonDefaultContext)
 
   rclcpp::shutdown(non_default_context);
 }
+
+TYPED_TEST(TestExecutors, release_ownership_entity_after_spinning_cancel)
+{
+  using ExecutorType = TypeParam;
+  ExecutorType executor;
+
+  auto future = std::async(std::launch::async, [&executor] {executor.spin();});
+
+  auto node = std::make_shared<rclcpp::Node>("test_node");
+  auto callback = [](
+    const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {
+    };
+  auto server = node->create_service<test_msgs::srv::Empty>("test_service", callback);
+  while (!executor.is_spinning()) {
+    std::this_thread::sleep_for(50ms);
+  }
+  executor.add_node(node);
+  std::this_thread::sleep_for(50ms);
+  executor.cancel();
+  std::future_status future_status = future.wait_for(1s);
+  EXPECT_EQ(future_status, std::future_status::ready);
+
+  EXPECT_EQ(server.use_count(), 1);
+}