sequence_node_with_memory.cpp
Go to the documentation of this file.
00001 
00002 /* Copyright (C) 2015-2017 Michele Colledanchise - 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 
00015 #include <sequence_node_with_memory.h>
00016 #include <string>
00017 
00018 
00019 BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name) : ControlNode::ControlNode(name)
00020 {
00021     reset_policy_ = BT::ON_SUCCESS_OR_FAILURE;
00022     current_child_idx_ = 0;  // initialize the current running child
00023 }
00024 
00025 
00026 BT::SequenceNodeWithMemory::SequenceNodeWithMemory(std::string name, int reset_policy) : ControlNode::ControlNode(name)
00027 {
00028     reset_policy_ = reset_policy;
00029     current_child_idx_ = 0;  // initialize the current running child
00030 }
00031 
00032 
00033 BT::SequenceNodeWithMemory::~SequenceNodeWithMemory() {}
00034 
00035 
00036 BT::ReturnStatus BT::SequenceNodeWithMemory::Tick()
00037 {
00038     DEBUG_STDOUT(get_name() << " ticked, memory counter: "<< current_child_idx_);
00039 
00040     // Vector size initialization. N_of_children_ could change at runtime if you edit the tree
00041     N_of_children_ = children_nodes_.size();
00042 
00043     // Routing the ticks according to the sequence node's (with memory) logic:
00044     while (current_child_idx_ < N_of_children_)
00045     {
00046         /*      Ticking an action is different from ticking a condition. An action executed some portion of code in another thread.
00047                 We want this thread detached so we can cancel its execution (when the action no longer receive ticks).
00048                 Hence we cannot just call the method Tick() from the action as doing so will block the execution of the tree.
00049                 For this reason if a child of this node is an action, then we send the tick using the tick engine. Otherwise we call the method Tick() and wait for the response.
00050         */
00051 
00052         if (children_nodes_[current_child_idx_]->get_type() == BT::ACTION_NODE)
00053         {
00054             // 1) If the child i is an action, read its state.
00055             // Action nodes runs in another thread, hence you cannot retrieve the status just by executing it.
00056 
00057             child_i_status_ = children_nodes_[current_child_idx_]->get_status();
00058             DEBUG_STDOUT(get_name() << " It is an action " << children_nodes_[current_child_idx_]->get_name()
00059                          << " with status: " << child_i_status_);
00060 
00061             if (child_i_status_ == BT::IDLE || child_i_status_ == BT::HALTED)
00062             {
00063                 // 1.1) If the action status is not running, the sequence node sends a tick to it.
00064                 DEBUG_STDOUT(get_name() << "NEEDS TO TICK " << children_nodes_[current_child_idx_]->get_name());
00065                 children_nodes_[current_child_idx_]->tick_engine.Tick();
00066 
00067                 // waits for the tick to arrive to the child
00068                 do
00069                 {
00070                     child_i_status_ = children_nodes_[current_child_idx_]->get_status();
00071                     std::this_thread::sleep_for(std::chrono::milliseconds(10));
00072                 }
00073                 while (child_i_status_ != BT::RUNNING && child_i_status_ != BT::SUCCESS
00074                        && child_i_status_ != BT::FAILURE);
00075             }
00076         }
00077         else
00078         {
00079             // 2) if it's not an action:
00080             // Send the tick and wait for the response;
00081             child_i_status_ = children_nodes_[current_child_idx_]->Tick();
00082         }
00083 
00084         if (child_i_status_ == BT::SUCCESS ||child_i_status_ == BT::FAILURE )
00085         {
00086              // the child goes in idle if it has returned success or failure.
00087             children_nodes_[current_child_idx_]->set_status(BT::IDLE);
00088         }
00089 
00090         if (child_i_status_ != BT::SUCCESS)
00091         {
00092             // If the  child status is not success, return the status
00093             DEBUG_STDOUT("the status of: " << get_name() << " becomes " << child_i_status_);
00094             if (child_i_status_ == BT::FAILURE && (reset_policy_ == BT::ON_FAILURE
00095                                                    || reset_policy_ == BT::ON_SUCCESS_OR_FAILURE))
00096             {
00097                 current_child_idx_ = 0;
00098             }
00099             set_status(child_i_status_);
00100             return child_i_status_;
00101         }
00102         else if (current_child_idx_ != N_of_children_ - 1)
00103         {
00104             // If the  child status is success, continue to the next child
00105             // (if any, hence if(current_child_ != N_of_children_ - 1) ) in the for loop (if any).
00106             current_child_idx_++;
00107         }
00108         else
00109         {
00110             // if it the last child.
00111             if (child_i_status_ == BT::SUCCESS)
00112             {
00113                 // if it the last child and it has returned SUCCESS, reset the memory
00114                 current_child_idx_ = 0;
00115             }
00116             set_status(child_i_status_);
00117             return child_i_status_;
00118         }
00119     }
00120     return BT::EXIT;
00121 }
00122 
00123 
00124 int BT::SequenceNodeWithMemory::DrawType()
00125 {
00126     return BT::SEQUENCESTAR;
00127 }
00128 
00129 
00130 void BT::SequenceNodeWithMemory::Halt()
00131 {
00132     current_child_idx_ = 0;
00133     BT::ControlNode::Halt();
00134 }


behavior_tree_core
Author(s): Michele Colledanchise
autogenerated on Thu Jun 6 2019 18:19:08