|
| 1 | +/* Copyright (C) 2018-2025 Davide Faconti, Eurecat - All Rights Reserved |
| 2 | +* |
| 3 | +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), |
| 4 | +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, |
| 5 | +* and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: |
| 6 | +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. |
| 7 | +* |
| 8 | +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, |
| 9 | +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, |
| 10 | +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. |
| 11 | +*/ |
| 12 | + |
| 13 | +#include "behaviortree_cpp/controls/try_catch_node.h" |
| 14 | + |
| 15 | +namespace BT |
| 16 | +{ |
| 17 | +TryCatchNode::TryCatchNode(const std::string& name, const NodeConfig& config) |
| 18 | + : ControlNode::ControlNode(name, config) |
| 19 | + , current_child_idx_(0) |
| 20 | + , skipped_count_(0) |
| 21 | + , in_catch_(false) |
| 22 | +{ |
| 23 | + setRegistrationID("TryCatch"); |
| 24 | +} |
| 25 | + |
| 26 | +void TryCatchNode::halt() |
| 27 | +{ |
| 28 | + bool catch_on_halt = false; |
| 29 | + getInput("catch_on_halt", catch_on_halt); |
| 30 | + |
| 31 | + // If catch_on_halt is enabled and we were in the try-block (not already in catch), |
| 32 | + // execute the catch child synchronously before halting. |
| 33 | + if(catch_on_halt && !in_catch_ && isStatusActive(status()) && |
| 34 | + children_nodes_.size() >= 2) |
| 35 | + { |
| 36 | + // Halt all try-block children first |
| 37 | + for(size_t i = 0; i < children_nodes_.size() - 1; i++) |
| 38 | + { |
| 39 | + haltChild(i); |
| 40 | + } |
| 41 | + |
| 42 | + // Tick the catch child. If it returns RUNNING, halt it too |
| 43 | + // (best-effort cleanup during halt). |
| 44 | + TreeNode* catch_child = children_nodes_.back(); |
| 45 | + const NodeStatus catch_status = catch_child->executeTick(); |
| 46 | + if(catch_status == NodeStatus::RUNNING) |
| 47 | + { |
| 48 | + haltChild(children_nodes_.size() - 1); |
| 49 | + } |
| 50 | + } |
| 51 | + |
| 52 | + current_child_idx_ = 0; |
| 53 | + skipped_count_ = 0; |
| 54 | + in_catch_ = false; |
| 55 | + ControlNode::halt(); |
| 56 | +} |
| 57 | + |
| 58 | +NodeStatus TryCatchNode::tick() |
| 59 | +{ |
| 60 | + const size_t children_count = children_nodes_.size(); |
| 61 | + |
| 62 | + if(children_count < 2) |
| 63 | + { |
| 64 | + throw LogicError("[", name(), "]: TryCatch requires at least 2 children"); |
| 65 | + } |
| 66 | + |
| 67 | + if(!isStatusActive(status())) |
| 68 | + { |
| 69 | + skipped_count_ = 0; |
| 70 | + in_catch_ = false; |
| 71 | + } |
| 72 | + |
| 73 | + setStatus(NodeStatus::RUNNING); |
| 74 | + |
| 75 | + const size_t try_count = children_count - 1; |
| 76 | + |
| 77 | + // If we are in catch mode, tick the last child (cleanup) |
| 78 | + if(in_catch_) |
| 79 | + { |
| 80 | + TreeNode* catch_child = children_nodes_.back(); |
| 81 | + const NodeStatus catch_status = catch_child->executeTick(); |
| 82 | + |
| 83 | + if(catch_status == NodeStatus::RUNNING) |
| 84 | + { |
| 85 | + return NodeStatus::RUNNING; |
| 86 | + } |
| 87 | + |
| 88 | + // Catch child finished (SUCCESS or FAILURE): return FAILURE |
| 89 | + resetChildren(); |
| 90 | + current_child_idx_ = 0; |
| 91 | + in_catch_ = false; |
| 92 | + return NodeStatus::FAILURE; |
| 93 | + } |
| 94 | + |
| 95 | + // Try-block: execute children 0..N-2 as a Sequence |
| 96 | + while(current_child_idx_ < try_count) |
| 97 | + { |
| 98 | + TreeNode* current_child_node = children_nodes_[current_child_idx_]; |
| 99 | + const NodeStatus child_status = current_child_node->executeTick(); |
| 100 | + |
| 101 | + switch(child_status) |
| 102 | + { |
| 103 | + case NodeStatus::RUNNING: { |
| 104 | + return NodeStatus::RUNNING; |
| 105 | + } |
| 106 | + case NodeStatus::FAILURE: { |
| 107 | + // Enter catch mode: halt try-block children, then tick catch child |
| 108 | + resetChildren(); |
| 109 | + current_child_idx_ = 0; |
| 110 | + in_catch_ = true; |
| 111 | + return tick(); // re-enter to tick the catch child |
| 112 | + } |
| 113 | + case NodeStatus::SUCCESS: { |
| 114 | + current_child_idx_++; |
| 115 | + } |
| 116 | + break; |
| 117 | + case NodeStatus::SKIPPED: { |
| 118 | + current_child_idx_++; |
| 119 | + skipped_count_++; |
| 120 | + } |
| 121 | + break; |
| 122 | + case NodeStatus::IDLE: { |
| 123 | + throw LogicError("[", name(), "]: A child should not return IDLE"); |
| 124 | + } |
| 125 | + } |
| 126 | + } |
| 127 | + |
| 128 | + // All try-children completed successfully (or were skipped) |
| 129 | + const bool all_skipped = (skipped_count_ == try_count); |
| 130 | + resetChildren(); |
| 131 | + current_child_idx_ = 0; |
| 132 | + skipped_count_ = 0; |
| 133 | + |
| 134 | + return all_skipped ? NodeStatus::SKIPPED : NodeStatus::SUCCESS; |
| 135 | +} |
| 136 | + |
| 137 | +} // namespace BT |
0 commit comments