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-2019 Davide Faconti, Eurecat -  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, BT::Duration deadline_ms) :
00018     AsyncActionNode(name, {})
00019 {
00020     boolean_value_ = true;
00021     time_ = deadline_ms;
00022     stop_loop_ = false;
00023     tick_count_ = 0;
00024 }
00025 
00026 BT::AsyncActionTest::~AsyncActionTest()
00027 {
00028     halt();
00029 }
00030 
00031 BT::NodeStatus BT::AsyncActionTest::tick()
00032 {
00033     using std::chrono::high_resolution_clock;
00034     tick_count_++;
00035     stop_loop_ = false;
00036     auto initial_time = high_resolution_clock::now();
00037 
00038     while (!stop_loop_ && high_resolution_clock::now() < initial_time + time_)
00039     {
00040         std::this_thread::sleep_for(std::chrono::milliseconds(1));
00041     }
00042 
00043     if (!stop_loop_)
00044     {
00045         return boolean_value_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE;
00046     }
00047     else
00048     {
00049         return NodeStatus::IDLE;
00050     }
00051 }
00052 
00053 void BT::AsyncActionTest::halt()
00054 {
00055     stop_loop_ = true;
00056 }
00057 
00058 void BT::AsyncActionTest::setTime(BT::Duration time)
00059 {
00060     time_ = time;
00061 }
00062 
00063 void BT::AsyncActionTest::setBoolean(bool boolean_value)
00064 {
00065     boolean_value_ = boolean_value;
00066 }
00067 
00068 //----------------------------------------------
00069 
00070 BT::SyncActionTest::SyncActionTest(const std::string& name) :
00071     SyncActionNode(name, {})
00072 {
00073     tick_count_ = 0;
00074     boolean_value_ = true;
00075 }
00076 
00077 BT::NodeStatus BT::SyncActionTest::tick()
00078 {
00079     tick_count_++;
00080     return boolean_value_ ? NodeStatus::SUCCESS : NodeStatus::FAILURE;
00081 }
00082 
00083 void BT::SyncActionTest::setBoolean(bool boolean_value)
00084 {
00085     boolean_value_ = boolean_value;
00086 }


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sat Jun 8 2019 20:17:15