action_test_node.cpp
Go to the documentation of this file.
00001 /* Copyright (C) 2015-2017 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 "action_test_node.h"
00015 #include <string>
00016 
00017 BT::AsyncActionTest::AsyncActionTest(const std::string& name) : ActionNode(name)
00018 {
00019     boolean_value_ = true;
00020     time_ = 3;
00021     stop_loop_ = false;
00022     tick_count_ = 0;
00023 }
00024 
00025 BT::AsyncActionTest::~AsyncActionTest()
00026 {
00027     halt();
00028 }
00029 
00030 BT::NodeStatus BT::AsyncActionTest::tick()
00031 {
00032     tick_count_++;
00033     stop_loop_ = false;
00034     int i = 0;
00035     while (!stop_loop_ && i++ < time_)
00036     {
00037         std::this_thread::sleep_for(std::chrono::milliseconds(100));
00038     }
00039 
00040     if (!stop_loop_)
00041     {
00042         return boolean_value_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE;
00043     }
00044     else
00045     {
00046         return NodeStatus::IDLE;
00047     }
00048 }
00049 
00050 void BT::AsyncActionTest::halt()
00051 {
00052     stop_loop_ = true;
00053     setStatus(NodeStatus::IDLE);
00054 }
00055 
00056 void BT::AsyncActionTest::setTime(int time)
00057 {
00058     time_ = time;
00059 }
00060 
00061 void BT::AsyncActionTest::setBoolean(bool boolean_value)
00062 {
00063     boolean_value_ = boolean_value;
00064 }
00065 
00066 //----------------------------------------------
00067 
00068 BT::SyncActionTest::SyncActionTest(const std::string& name) : SyncActionNode(name)
00069 {
00070     tick_count_ = 0;
00071     boolean_value_ = true;
00072 }
00073 
00074 BT::NodeStatus BT::SyncActionTest::tick()
00075 {
00076     tick_count_++;
00077     return boolean_value_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE;
00078 }
00079 
00080 void BT::SyncActionTest::setBoolean(bool boolean_value)
00081 {
00082     boolean_value_ = boolean_value;
00083 }


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