parallel_node.cpp
Go to the documentation of this file.
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/parallel_node.h"
00015 
00016 namespace BT
00017 {
00018 
00019 constexpr const char* ParallelNode::THRESHOLD_KEY;
00020 
00021 ParallelNode::ParallelNode(const std::string& name, int threshold)
00022   : ControlNode::ControlNode(name, {{THRESHOLD_KEY, std::to_string(threshold)}}),
00023     threshold_(threshold),
00024     read_parameter_from_blackboard_(false)
00025 {
00026     setRegistrationName("Parallel");
00027 }
00028 
00029 ParallelNode::ParallelNode(const std::string &name,
00030                                const NodeParameters &params)
00031     : ControlNode::ControlNode(name, params),
00032       read_parameter_from_blackboard_(false)
00033 {
00034     read_parameter_from_blackboard_ = isBlackboardPattern( params.at(THRESHOLD_KEY) );
00035     if(!read_parameter_from_blackboard_)
00036     {
00037         if( !getParam(THRESHOLD_KEY, threshold_) )
00038         {
00039             throw std::runtime_error("Missing parameter [threshold] in ParallelNode");
00040         }
00041     }
00042 }
00043 
00044 NodeStatus ParallelNode::tick()
00045 {
00046     if(read_parameter_from_blackboard_)
00047     {
00048         if( !getParam(THRESHOLD_KEY, threshold_) )
00049         {
00050             throw std::runtime_error("Missing parameter [threshold] in ParallelNode");
00051         }
00052     }
00053 
00054     success_childred_num_ = 0;
00055     failure_childred_num_ = 0;
00056     // Vector size initialization. children_count_ could change at runtime if you edit the tree
00057     const unsigned children_count = children_nodes_.size();
00058 
00059     // Routing the tree according to the sequence node's logic:
00060     for (unsigned int i = 0; i < children_count; i++)
00061     {
00062         TreeNode* child_node = children_nodes_[i];
00063 
00064         NodeStatus child_status = child_node->executeTick();
00065 
00066         switch (child_status)
00067         {
00068             case NodeStatus::SUCCESS:
00069                 child_node->setStatus(NodeStatus::IDLE);
00070                 // the child goes in idle if it has returned success.
00071                 if (++success_childred_num_ == threshold_)
00072                 {
00073                     success_childred_num_ = 0;
00074                     failure_childred_num_ = 0;
00075                     haltChildren(0);   // halts all running children. The execution is done.
00076                     return child_status;
00077                 }
00078                 break;
00079             case NodeStatus::FAILURE:
00080                 child_node->setStatus(NodeStatus::IDLE);
00081                 // the child goes in idle if it has returned failure.
00082                 if (++failure_childred_num_ > children_count - threshold_)
00083                 {
00084                     success_childred_num_ = 0;
00085                     failure_childred_num_ = 0;
00086                     haltChildren(0);   // halts all running children. The execution is hopeless.
00087                     return child_status;
00088                 }
00089                 break;
00090             case NodeStatus::RUNNING:
00091                 setStatus(child_status);
00092                 break;
00093             default:
00094                 break;
00095         }
00096     }
00097     return NodeStatus::RUNNING;
00098 }
00099 
00100 void ParallelNode::halt()
00101 {
00102     success_childred_num_ = 0;
00103     failure_childred_num_ = 0;
00104     ControlNode::halt();
00105 }
00106 
00107 unsigned int ParallelNode::thresholdM()
00108 {
00109     return threshold_;
00110 }
00111 
00112 void ParallelNode::setThresholdM(unsigned int threshold_M)
00113 {
00114     threshold_ = threshold_M;
00115 }
00116 
00117 }


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sat Feb 2 2019 03:50:10