13 #include <gtest/gtest.h> 19 using std::chrono::milliseconds;
27 , action(
"action", milliseconds(500) )
74 timeout_root(
"deadline", 9)
75 , retry(
"retry", 1000)
95 ASSERT_EQ(NodeStatus::RUNNING, state);
97 std::this_thread::sleep_for(std::chrono::milliseconds(400));
99 ASSERT_EQ(NodeStatus::FAILURE, state);
111 ASSERT_EQ(NodeStatus::RUNNING, state);
113 std::this_thread::sleep_for(std::chrono::milliseconds(400));
116 ASSERT_EQ(NodeStatus::SUCCESS, state);
124 ASSERT_EQ(NodeStatus::FAILURE,
root.
status());
131 ASSERT_EQ(NodeStatus::SUCCESS,
root.
status());
140 ASSERT_EQ(NodeStatus::FAILURE,
root.
status());
148 ASSERT_EQ(NodeStatus::SUCCESS,
root.
status());
157 auto t1 = std::chrono::high_resolution_clock::now();
159 while( std::chrono::high_resolution_clock::now() < t1 + std::chrono::seconds(2) )
162 std::this_thread::sleep_for( std::chrono::microseconds(50) );
BT::TimeoutNode timeout_root
The TimeoutNode will halt() a running child if the latter has been RUNNING for more than a give time...
TEST_F(DeadlineTest, DeadlineTriggeredTest)
The RepeatNode is used to execute a child several times, as long as it succeed.
BT::SyncActionTest action
The RetryNode is used to execute a child several times if it fails.
void haltAllActions(TreeNode *root_node)
BT::SyncActionTest action
void setChild(TreeNode *child)
BT::SyncActionTest action
NodeStatus executeTick() override
The method that should be used to invoke tick() and setStatus();.
BT::AsyncActionTest action
void setTime(BT::Duration time)
NodeStatus status() const
void setBoolean(bool boolean_value)