From b8e41b052aad0c7c77ad24a4b4512a89901b665c Mon Sep 17 00:00:00 2001 From: Ramon Wijnands Date: Tue, 5 May 2026 11:24:58 +0200 Subject: [PATCH 1/2] Fix LoopNode does not reload dynamic vector input on second execution I've implemented the suggestion from https://github.com/BehaviorTree/BehaviorTree.CPP/issues/1124 This seems to have fixed the issue I had with LoopNode not reloading the input vector on second execution. --- include/behaviortree_cpp/decorators/loop_node.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/include/behaviortree_cpp/decorators/loop_node.h b/include/behaviortree_cpp/decorators/loop_node.h index de06d0165..7c89da68b 100644 --- a/include/behaviortree_cpp/decorators/loop_node.h +++ b/include/behaviortree_cpp/decorators/loop_node.h @@ -59,6 +59,8 @@ class LoopNode : public DecoratorNode if(status() == NodeStatus::IDLE) { child_running_ = false; + current_queue_.reset(); + // special case: the port contains a string that was converted to SharedQueue if(static_queue_) { From 01976d6fba58987b392638648f030a54d82b2072 Mon Sep 17 00:00:00 2001 From: Ramon Wijnands Date: Tue, 5 May 2026 11:38:47 +0200 Subject: [PATCH 2/2] Add unittest for restarting LoopNode with a vector from the blackboard --- tests/gtest_loop.cpp | 36 ++++++++++++++++++++++++++++++++++++ 1 file changed, 36 insertions(+) diff --git a/tests/gtest_loop.cpp b/tests/gtest_loop.cpp index 3a69767ed..58216fc86 100644 --- a/tests/gtest_loop.cpp +++ b/tests/gtest_loop.cpp @@ -410,6 +410,42 @@ TEST(LoopNode, RestartAfterCompletion) ASSERT_EQ(tick_count, 3); // Should iterate over queue again } +TEST(LoopNode, RestartAfterCompletion_VectorFromBlackboard) +{ + BehaviorTreeFactory factory; + + int tick_count = 0; + factory.registerSimpleAction("CountTicks", [&tick_count](TreeNode&) { + tick_count++; + return NodeStatus::SUCCESS; + }); + + const std::string xml_text = R"( + + + + + + + )"; + + auto tree = factory.createTreeFromText(xml_text); + tree.rootBlackboard()->set("my_vector", std::vector{ 1, 2, 3 }); + + // First execution + auto status = tree.tickWhileRunning(); + ASSERT_EQ(status, NodeStatus::SUCCESS); + ASSERT_EQ(tick_count, 3); + + // Reset and execute again + tree.haltTree(); + tick_count = 0; + tree.rootBlackboard()->set("my_vector", std::vector{ 1, 2, 3 }); + status = tree.tickWhileRunning(); + ASSERT_EQ(status, NodeStatus::SUCCESS); + ASSERT_EQ(tick_count, 3); // Should iterate over vector again +} + // ============ convertFromString tests for SharedQueue ============ TEST(LoopNode, ConvertFromString_Int)