Skip to content

Commit 424dd61

Browse files
committed
backup
Signed-off-by: silanus23 <[email protected]>
1 parent 47327a5 commit 424dd61

File tree

4 files changed

+127
-3
lines changed

4 files changed

+127
-3
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp

Lines changed: 25 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,6 +77,7 @@ class BtActionNode : public BT::ActionNodeBase
7777
if (getInput("server_name", remapped_action_name)) {
7878
action_name_ = remapped_action_name;
7979
}
80+
getInput("is_global", is_global_);
8081
createActionClient(action_name_);
8182

8283
// Give the derive class a chance to do any initialization
@@ -121,7 +122,8 @@ class BtActionNode : public BT::ActionNodeBase
121122
{
122123
BT::PortsList basic = {
123124
BT::InputPort<std::string>("server_name", "Action server name"),
124-
BT::InputPort<std::chrono::milliseconds>("server_timeout")
125+
BT::InputPort<std::chrono::milliseconds>("server_timeout"),
126+
BT::InputPort<bool>("is_global", false, "Use RunID for initialization")
125127
};
126128
basic.insert(addition.begin(), addition.end());
127129

@@ -202,8 +204,28 @@ class BtActionNode : public BT::ActionNodeBase
202204
*/
203205
BT::NodeStatus tick() override
204206
{
207+
bool needs_initialization_ = false;
205208
// first step to be done only at the beginning of the Action
209+
if (is_global_) {
210+
try {
211+
uint64_t current_run_id = config().blackboard->get<uint64_t>("run_id");
212+
if (current_run_id != last_run_id_) {
213+
needs_initialization_ = true;
214+
last_run_id_ = current_run_id;
215+
}
216+
} catch (const std::exception & e) {
217+
// run_id not found on blackboard, use old behavior
218+
if (!BT::isStatusActive(status())) {
219+
needs_initialization_ = true;
220+
}
221+
}
222+
} else {
206223
if (!BT::isStatusActive(status())) {
224+
needs_initialization_ = true;
225+
}
226+
}
227+
228+
if (needs_initialization_) {
207229
// reset the flag to send the goal or not, allowing the user the option to set it in on_tick
208230
should_send_goal_ = true;
209231

@@ -499,6 +521,8 @@ class BtActionNode : public BT::ActionNodeBase
499521

500522
// Can be set in on_tick or on_wait_for_result to indicate if a goal should be sent.
501523
bool should_send_goal_;
524+
bool is_global_ {false};
525+
uint64_t last_run_id_ {0};
502526
};
503527

504528
} // namespace nav2_behavior_tree

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -304,6 +304,9 @@ class BtActionServer
304304
// internal error tracking (IOW not behaviorTree blackboard errors)
305305
uint16_t internal_error_code_;
306306
std::string internal_error_msg_;
307+
308+
// To keep track of the execution number
309+
uint64_t run_id_ = 0;
307310
};
308311

309312
} // namespace nav2_behavior_tree

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -179,7 +179,7 @@ bool BtActionServer<ActionT, NodeT>::on_configure()
179179
blackboard_->set<std::chrono::milliseconds>(
180180
"wait_for_service_timeout",
181181
wait_for_service_timeout_);
182-
182+
blackboard_->set<uint64_t>("run_id", run_id_); // NOLINT
183183
return true;
184184
}
185185

@@ -362,6 +362,9 @@ void BtActionServer<ActionT, NodeT>::executeCallback()
362362
return;
363363
}
364364

365+
run_id_++;
366+
blackboard_->set<uint64_t>("run_id", run_id_);
367+
365368
auto is_canceling = [&]() {
366369
if (action_server_ == nullptr) {
367370
RCLCPP_DEBUG(logger_, "Action server unavailable. Canceling.");

nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp

Lines changed: 95 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,13 @@ class FibonacciAction : public nav2_behavior_tree::BtActionNode<test_msgs::actio
147147

148148
BT::NodeStatus on_cancelled() override
149149
{
150-
config().blackboard->set("sequence", result_.result->sequence);
150+
// Check if result is available before accessing it
151+
if (result_.result) {
152+
config().blackboard->set("sequence", result_.result->sequence);
153+
} else {
154+
// Set empty sequence if no result available
155+
config().blackboard->set("sequence", std::vector<int>());
156+
}
151157
config().blackboard->set("on_cancelled_triggered", true);
152158
return BT::NodeStatus::SUCCESS;
153159
}
@@ -486,6 +492,94 @@ TEST_F(BTActionNodeTestFixture, test_server_cancel)
486492
// is at least 1000000 x 50 ms
487493
EXPECT_EQ(ticks, 7);
488494
}
495+
TEST_F(BTActionNodeTestFixture, test_run_id_initialization_and_persistence)
496+
{
497+
// create tree with is_global="true" to enable RunID checking
498+
std::string xml_txt =
499+
R"(
500+
<root BTCPP_format="4">
501+
<BehaviorTree ID="MainTree">
502+
<Fibonacci order="100" is_global="true" />
503+
</BehaviorTree>
504+
</root>)";
505+
506+
config_->blackboard->set<std::chrono::milliseconds>("server_timeout", 200ms);
507+
config_->blackboard->set<std::chrono::milliseconds>("bt_loop_duration", 10ms);
508+
509+
// Set initial RunID
510+
config_->blackboard->set<uint64_t>("run_id", 1);
511+
512+
tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText(xml_txt, config_->blackboard));
513+
action_server_->setHandleGoalSleepDuration(2ms);
514+
action_server_->setServerLoopRate(50ms); // Slower server rate
515+
516+
// First tick should initialize with run_id = 1
517+
auto result = tree_->tickOnce();
518+
EXPECT_EQ(result, BT::NodeStatus::RUNNING);
519+
520+
// Subsequent ticks with same RunID should continue without re-initialization
521+
result = tree_->tickOnce();
522+
EXPECT_EQ(result, BT::NodeStatus::RUNNING);
523+
524+
// Clean up by halting the tree
525+
tree_->haltTree();
526+
}
527+
528+
TEST_F(BTActionNodeTestFixture, test_run_id_changes_trigger_reinitialization)
529+
{
530+
std::string xml_txt =
531+
R"(
532+
<root BTCPP_format="4">
533+
<BehaviorTree ID="MainTree">
534+
<Fibonacci order="50" is_global="true" />
535+
</BehaviorTree>
536+
</root>)";
537+
538+
config_->blackboard->set<std::chrono::milliseconds>("server_timeout", 200ms);
539+
config_->blackboard->set<std::chrono::milliseconds>("bt_loop_duration", 10ms);
540+
541+
tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText(xml_txt, config_->blackboard));
542+
action_server_->setHandleGoalSleepDuration(2ms);
543+
action_server_->setServerLoopRate(50ms);
544+
545+
// Test with multiple run_id changes
546+
for (uint64_t run_id = 1; run_id <= 3; ++run_id) {
547+
config_->blackboard->set<uint64_t>("run_id", run_id);
548+
549+
// Halt tree to reset state
550+
tree_->haltTree();
551+
552+
// First tick with new run_id should start new execution
553+
auto result = tree_->tickOnce();
554+
EXPECT_EQ(result, BT::NodeStatus::RUNNING) << "Failed on run_id: " << run_id;
555+
}
556+
557+
// Final cleanup
558+
tree_->haltTree();
559+
}
560+
561+
TEST_F(BTActionNodeTestFixture, test_run_id_non_global_mode_unaffected)
562+
{
563+
// Test without is_global flag (should use old behavior)
564+
std::string xml_txt =
565+
R"(
566+
<root BTCPP_format="4">
567+
<BehaviorTree ID="MainTree">
568+
<Fibonacci order="2" />
569+
</BehaviorTree>
570+
</root>)";
571+
572+
config_->blackboard->set<std::chrono::milliseconds>("server_timeout", 20ms);
573+
config_->blackboard->set<std::chrono::milliseconds>("bt_loop_duration", 10ms);
574+
575+
tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText(xml_txt, config_->blackboard));
576+
action_server_->setHandleGoalSleepDuration(2ms);
577+
action_server_->setServerLoopRate(10ns);
578+
579+
// Should work normally without RunID checking
580+
auto result = tree_->tickOnce();
581+
EXPECT_EQ(result, BT::NodeStatus::RUNNING);
582+
}
489583

490584
int main(int argc, char ** argv)
491585
{

0 commit comments

Comments
 (0)