00001 /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved 00002 * Copyright (C) 2018 Davide Faconti - All Rights Reserved 00003 * 00004 * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), 00005 * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, 00006 * 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: 00007 * The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. 00008 * 00009 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 00010 * 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, 00011 * 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. 00012 */ 00013 00014 #include "behaviortree_cpp/controls/fallback_star_node.h" 00015 00016 namespace BT 00017 { 00018 FallbackStarNode::FallbackStarNode(const std::string& name) 00019 : ControlNode::ControlNode(name, {}), current_child_idx_(0) 00020 { 00021 setRegistrationName("FallbackStar"); 00022 } 00023 00024 NodeStatus FallbackStarNode::tick() 00025 { 00026 // Vector size initialization. children_count_ could change at runtime if you edit the tree 00027 const unsigned children_count = children_nodes_.size(); 00028 00029 setStatus(NodeStatus::RUNNING); 00030 00031 while (current_child_idx_ < children_count) 00032 { 00033 TreeNode* current_child_node = children_nodes_[current_child_idx_]; 00034 const NodeStatus child_status = current_child_node->executeTick(); 00035 00036 switch (child_status) 00037 { 00038 case NodeStatus::RUNNING: 00039 { 00040 return child_status; 00041 } 00042 case NodeStatus::SUCCESS: 00043 { 00044 haltChildren(0); 00045 current_child_idx_ = 0; 00046 return child_status; 00047 } 00048 case NodeStatus::FAILURE: 00049 { 00050 current_child_idx_++; 00051 } 00052 break; 00053 00054 case NodeStatus::IDLE: 00055 { 00056 throw std::runtime_error("This is not supposed to happen"); 00057 } 00058 } // end switch 00059 } // end while loop 00060 00061 // The entire while loop completed. This means that all the children returned FAILURE. 00062 if (current_child_idx_ == children_count) 00063 { 00064 haltChildren(0); 00065 current_child_idx_ = 0; 00066 } 00067 return NodeStatus::FAILURE; 00068 } 00069 00070 void FallbackStarNode::halt() 00071 { 00072 current_child_idx_ = 0; 00073 ControlNode::halt(); 00074 } 00075 }