Skip to content

Commit a1eea43

Browse files
Barry-Xu-2018mergify[bot]
authored andcommitted
Release ownership of entities after spinning cancelled (#2556)
* Release ownership of entities after spinning cancelled Signed-off-by: Barry Xu <[email protected]> * Move release action to every exit point in different spin functions Signed-off-by: Barry Xu <[email protected]> * Move wait_result_.reset() before setting spinning to false Signed-off-by: Barry Xu <[email protected]> * Update test code Signed-off-by: Barry Xu <[email protected]> * Move test code to test_executors.cpp Signed-off-by: Barry Xu <[email protected]> --------- Signed-off-by: Barry Xu <[email protected]> (cherry picked from commit 069a001) # Conflicts: # rclcpp/test/rclcpp/executors/test_executors.cpp
1 parent e083bf9 commit a1eea43

File tree

5 files changed

+32
-6
lines changed

5 files changed

+32
-6
lines changed

rclcpp/src/rclcpp/executor.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -275,7 +275,7 @@ Executor::spin_until_future_complete_impl(
275275
if (spinning.exchange(true)) {
276276
throw std::runtime_error("spin_until_future_complete() called while already spinning");
277277
}
278-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
278+
RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
279279
while (rclcpp::ok(this->context_) && spinning.load()) {
280280
// Do one item of work.
281281
spin_once_impl(timeout_left);
@@ -364,7 +364,7 @@ Executor::spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive)
364364
if (spinning.exchange(true)) {
365365
throw std::runtime_error("spin_some() called while already spinning");
366366
}
367-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
367+
RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
368368

369369
// clear the wait result and wait for work without blocking to collect the work
370370
// for the first time
@@ -431,7 +431,7 @@ Executor::spin_once(std::chrono::nanoseconds timeout)
431431
if (spinning.exchange(true)) {
432432
throw std::runtime_error("spin_once() called while already spinning");
433433
}
434-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
434+
RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
435435
spin_once_impl(timeout);
436436
}
437437

rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ MultiThreadedExecutor::spin()
5555
if (spinning.exchange(true)) {
5656
throw std::runtime_error("spin() called while already spinning");
5757
}
58-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false););
58+
RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
5959
std::vector<std::thread> threads;
6060
size_t thread_id = 0;
6161
{

rclcpp/src/rclcpp/executors/single_threaded_executor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ SingleThreadedExecutor::spin()
3030
if (spinning.exchange(true)) {
3131
throw std::runtime_error("spin() called while already spinning");
3232
}
33-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
33+
RCPPUTILS_SCOPE_EXIT(wait_result_.reset();this->spinning.store(false););
3434

3535
// Clear any previous result and rebuild the waitset
3636
this->wait_result_.reset();

rclcpp/test/rclcpp/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -598,7 +598,7 @@ ament_add_gtest(test_executor test_executor.cpp
598598
APPEND_LIBRARY_DIRS "${append_library_dirs}"
599599
TIMEOUT 120)
600600
if(TARGET test_executor)
601-
target_link_libraries(test_executor ${PROJECT_NAME} mimick)
601+
target_link_libraries(test_executor ${PROJECT_NAME} mimick ${test_msgs_TARGETS})
602602
endif()
603603

604604
ament_add_gtest(test_graph_listener test_graph_listener.cpp)

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include "rclcpp/time_source.hpp"
4040

4141
#include "test_msgs/msg/empty.hpp"
42+
#include "test_msgs/srv/empty.hpp"
4243

4344
#include "./executor_types.hpp"
4445

@@ -878,6 +879,7 @@ TEST(TestExecutors, testSpinWithNonDefaultContext)
878879
rclcpp::shutdown(non_default_context);
879880
}
880881

882+
<<<<<<< HEAD
881883
template<typename T>
882884
class TestBusyWaiting : public ::testing::Test
883885
{
@@ -1028,4 +1030,28 @@ TYPED_TEST(TestBusyWaiting, test_spin)
10281030
this->check_for_busy_waits(start_time);
10291031
// this should get the initial trigger, and the follow up from in the callback
10301032
ASSERT_EQ(this->waitable->get_count(), 2u);
1033+
=======
1034+
TYPED_TEST(TestExecutors, release_ownership_entity_after_spinning_cancel)
1035+
{
1036+
using ExecutorType = TypeParam;
1037+
ExecutorType executor;
1038+
1039+
auto future = std::async(std::launch::async, [&executor] {executor.spin();});
1040+
1041+
auto node = std::make_shared<rclcpp::Node>("test_node");
1042+
auto callback = [](
1043+
const test_msgs::srv::Empty::Request::SharedPtr, test_msgs::srv::Empty::Response::SharedPtr) {
1044+
};
1045+
auto server = node->create_service<test_msgs::srv::Empty>("test_service", callback);
1046+
while (!executor.is_spinning()) {
1047+
std::this_thread::sleep_for(50ms);
1048+
}
1049+
executor.add_node(node);
1050+
std::this_thread::sleep_for(50ms);
1051+
executor.cancel();
1052+
std::future_status future_status = future.wait_for(1s);
1053+
EXPECT_EQ(future_status, std::future_status::ready);
1054+
1055+
EXPECT_EQ(server.use_count(), 1);
1056+
>>>>>>> 069a0018 (Release ownership of entities after spinning cancelled (#2556))
10311057
}

0 commit comments

Comments
 (0)