Skip to content

Commit 9a481a1

Browse files
Janosch MachowinskiJanosch Machowinski
authored andcommitted
fix: Fixed possible memory violation after remove_node
Up until this change, after the call to remove node, entities of a node might still be in the use by the executor. Therefore direct deletion of the node after the call might result in a memory violation if an entity would do a callback into the node itself. From now on, by default the remove_node will be blocking until all entities are released by the executor, which should be the expected behavior for most users. Signed-off-by: Janosch Machowinski <[email protected]>
1 parent fa0cf2d commit 9a481a1

File tree

3 files changed

+95
-5
lines changed

3 files changed

+95
-5
lines changed

rclcpp/include/rclcpp/executor.hpp

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -220,20 +220,28 @@ class Executor
220220
* \param[in] notify True to trigger the interrupt guard condition and wake up the executor.
221221
* This is useful if the last node was removed from the executor while the executor was blocked
222222
* waiting for work in another thread, because otherwise the executor would never be notified.
223+
* \param[in] wait_until_removed If true and the executor is spinning, the method will block until
224+
* all entities from the node have been removed from the executor. Note, if the remove_node call
225+
* was triggered from a callback of an entity of the node itself, and this value is true, this is
226+
* likely to result in a deadlock.
223227
* \throw std::runtime_error if the node is not associated with an executor.
224228
* \throw std::runtime_error if the node is not associated with this executor.
225229
*/
226230
RCLCPP_PUBLIC
227231
virtual void
228-
remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true);
232+
remove_node(
233+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true,
234+
bool wait_until_removed = true);
229235

230236
/// Convenience function which takes Node and forwards NodeBaseInterface.
231237
/**
232238
* \see rclcpp::Executor::remove_node
233239
*/
234240
RCLCPP_PUBLIC
235241
virtual void
236-
remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true);
242+
remove_node(
243+
std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true,
244+
bool wait_until_removed = true);
237245

238246
/// Add a node to executor, execute the next available unit of work, and remove the node.
239247
/**

rclcpp/src/rclcpp/executor.cpp

Lines changed: 17 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -220,7 +220,9 @@ Executor::add_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify)
220220
}
221221

222222
void
223-
Executor::remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify)
223+
Executor::remove_node(
224+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify,
225+
bool wait_until_removed)
224226
{
225227
this->collector_.remove_node(node_ptr);
226228

@@ -231,12 +233,24 @@ Executor::remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node
231233
std::string(
232234
"Failed to handle entities update on node remove: ") + ex.what());
233235
}
236+
237+
if(wait_until_removed) {
238+
// some other thread is spinning, wait until the executor
239+
// picked up the remove
240+
while(spinning && collector_.has_pending()) {
241+
std::this_thread::sleep_for(std::chrono::milliseconds(10));
242+
}
243+
// if we are not spinning, we can directly update the collection
244+
if(!spinning) {
245+
this->collector_.update_collections();
246+
}
247+
}
234248
}
235249

236250
void
237-
Executor::remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify)
251+
Executor::remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify, bool wait_until_removed)
238252
{
239-
this->remove_node(node_ptr->get_node_base_interface(), notify);
253+
this->remove_node(node_ptr->get_node_base_interface(), notify, wait_until_removed);
240254
}
241255

242256
void

rclcpp/test/rclcpp/test_executor.cpp

Lines changed: 68 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -528,3 +528,71 @@ TEST_F(TestExecutor, is_spinning) {
528528

529529
ASSERT_TRUE(timer_called);
530530
}
531+
532+
TEST_F(TestExecutor, remove_node) {
533+
using namespace std::chrono_literals;
534+
535+
// Create an Executor
536+
rclcpp::executors::SingleThreadedExecutor executor;
537+
538+
auto future = std::async(std::launch::async, [&executor] {executor.spin();});
539+
540+
auto node = std::make_shared<rclcpp::Node>("remove_node_test");
541+
std::vector<rclcpp::TimerBase::SharedPtr> timers;
542+
543+
std::atomic_bool timer_running = false;
544+
auto timer = node->create_timer(std::chrono::milliseconds(1), [&timer_running] () {
545+
timer_running = true;
546+
std::this_thread::sleep_for(std::chrono::milliseconds(400));
547+
timer_running = false;
548+
});
549+
timer->reset();
550+
551+
executor.add_node(node);
552+
553+
while(!timer_running) {
554+
// let the executor pick up the nodes
555+
std::this_thread::sleep_for(std::chrono::microseconds(10));
556+
}
557+
ASSERT_GT(timer.use_count(), 1);
558+
559+
executor.remove_node(node, true, true);
560+
561+
ASSERT_EQ(timer.use_count(), 1);
562+
563+
std::future_status future_status = std::future_status::timeout;
564+
do {
565+
executor.cancel();
566+
future_status = future.wait_for(1s);
567+
} while (future_status == std::future_status::timeout);
568+
EXPECT_EQ(future_status, std::future_status::ready);
569+
future.get();
570+
}
571+
572+
TEST_F(TestExecutor, remove_node_not_spinning) {
573+
using namespace std::chrono_literals;
574+
575+
// Create an Executor
576+
rclcpp::executors::SingleThreadedExecutor executor;
577+
578+
auto node = std::make_shared<rclcpp::Node>("remove_node_test");
579+
std::vector<rclcpp::TimerBase::SharedPtr> timers;
580+
581+
bool executed = false;
582+
auto timer = node->create_timer(std::chrono::milliseconds(1), [&executed] () {
583+
executed = true;
584+
});
585+
timer->reset();
586+
587+
executor.add_node(node);
588+
589+
while(!executed) {
590+
// let the executor pick up the nodes
591+
executor.spin_some(std::chrono::milliseconds(2));
592+
}
593+
594+
executor.remove_node(node, true, true);
595+
596+
ASSERT_EQ(timer.use_count(), 1);
597+
598+
}

0 commit comments

Comments
 (0)