gtest_decorator.cpp
Go to the documentation of this file.
00001 /* Copyright (C) 2018-2019 Davide Faconti, Eurecat - All Rights Reserved
00002 *
00003 *   Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
00004 *   to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
00005 *   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:
00006 *   The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
00007 *
00008 *   THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00009 *   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,
00010 *   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.
00011 */
00012 
00013 #include <gtest/gtest.h>
00014 #include "action_test_node.h"
00015 #include "condition_test_node.h"
00016 #include "behaviortree_cpp/behavior_tree.h"
00017 
00018 using BT::NodeStatus;
00019 using std::chrono::milliseconds;
00020 
00021 struct DeadlineTest : testing::Test
00022 {
00023     BT::TimeoutNode root;
00024     BT::AsyncActionTest action;
00025 
00026     DeadlineTest() : root("deadline", 300)
00027       , action("action", milliseconds(500) )
00028     {
00029         root.setChild(&action);
00030     }
00031     ~DeadlineTest()
00032     {
00033         haltAllActions(&root);
00034     }
00035 };
00036 
00037 struct RepeatTest : testing::Test
00038 {
00039     BT::RepeatNode root;
00040     BT::SyncActionTest action;
00041 
00042     RepeatTest() : root("repeat", 3), action("action")
00043     {
00044         root.setChild(&action);
00045     }
00046     ~RepeatTest()
00047     {
00048         haltAllActions(&root);
00049     }
00050 };
00051 
00052 struct RetryTest : testing::Test
00053 {
00054     BT::RetryNode root;
00055     BT::SyncActionTest action;
00056 
00057     RetryTest() : root("retry", 3), action("action")
00058     {
00059         root.setChild(&action);
00060     }
00061     ~RetryTest()
00062     {
00063         haltAllActions(&root);
00064     }
00065 };
00066 
00067 struct TimeoutAndRetry : testing::Test
00068 {
00069     BT::TimeoutNode timeout_root;
00070     BT::RetryNode retry;
00071     BT::SyncActionTest action;
00072 
00073     TimeoutAndRetry() :
00074       timeout_root("deadline", 9)
00075       , retry("retry", 1000)
00076       , action("action")
00077     {
00078         timeout_root.setChild(&retry);
00079         retry.setChild(&action);
00080     }
00081     ~TimeoutAndRetry()
00082     {
00083         haltAllActions(&timeout_root);
00084     }
00085 };
00086 
00087 /****************TESTS START HERE***************************/
00088 
00089 TEST_F(DeadlineTest, DeadlineTriggeredTest)
00090 {
00091     BT::NodeStatus state = root.executeTick();
00092     // deadline in 300 ms, action requires 500 ms
00093 
00094     ASSERT_EQ(NodeStatus::RUNNING, action.status());
00095     ASSERT_EQ(NodeStatus::RUNNING, state);
00096 
00097     std::this_thread::sleep_for(std::chrono::milliseconds(400));
00098     state = root.executeTick();
00099     ASSERT_EQ(NodeStatus::FAILURE, state);
00100     ASSERT_EQ(NodeStatus::IDLE, action.status());
00101 }
00102 
00103 TEST_F(DeadlineTest, DeadlineNotTriggeredTest)
00104 {
00105     action.setTime( milliseconds(200) );
00106     // deadline in 300 ms
00107 
00108     BT::NodeStatus state = root.executeTick();
00109 
00110     ASSERT_EQ(NodeStatus::RUNNING, action.status());
00111     ASSERT_EQ(NodeStatus::RUNNING, state);
00112 
00113     std::this_thread::sleep_for(std::chrono::milliseconds(400));
00114     state = root.executeTick();
00115     ASSERT_EQ(NodeStatus::IDLE, action.status());
00116     ASSERT_EQ(NodeStatus::SUCCESS, state);
00117 }
00118 
00119 TEST_F(RetryTest, RetryTestA)
00120 {
00121     action.setBoolean(false);
00122 
00123     root.executeTick();
00124     ASSERT_EQ(NodeStatus::FAILURE, root.status());
00125     ASSERT_EQ(3, action.tickCount() );
00126 
00127     action.setBoolean(true);
00128     action.resetTicks();
00129 
00130     root.executeTick();
00131     ASSERT_EQ(NodeStatus::SUCCESS, root.status());
00132     ASSERT_EQ(1, action.tickCount() );
00133 }
00134 
00135 TEST_F(RepeatTest, RepeatTestA)
00136 {
00137     action.setBoolean(false);
00138 
00139     root.executeTick();
00140     ASSERT_EQ(NodeStatus::FAILURE, root.status());
00141     ASSERT_EQ(1, action.tickCount() );
00142 
00143     //-------------------
00144     action.resetTicks();
00145     action.setBoolean(true);
00146 
00147     root.executeTick();
00148     ASSERT_EQ(NodeStatus::SUCCESS, root.status());
00149     ASSERT_EQ(3, action.tickCount() );
00150 }
00151 
00152 // https://github.com/BehaviorTree/BehaviorTree.CPP/issues/57
00153 TEST_F(TimeoutAndRetry, Issue57)
00154 {
00155     action.setBoolean( false );
00156 
00157     auto t1 = std::chrono::high_resolution_clock::now();
00158 
00159     while( std::chrono::high_resolution_clock::now() < t1 + std::chrono::seconds(2) )
00160     {
00161         ASSERT_NE( timeout_root.executeTick(), BT::NodeStatus::IDLE );
00162         std::this_thread::sleep_for( std::chrono::microseconds(50) );
00163     }
00164 }


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