13 #include <gtest/gtest.h> 23 using std::chrono::milliseconds;
35 root(
"root_sequence"),
36 action_1(
"action_1", milliseconds(100)),
37 condition_1(
"condition_1"),
38 condition_2(
"condition_2"),
39 fal_conditions(
"fallback_conditions")
43 fal_conditions.
addChild(&condition_1);
44 fal_conditions.
addChild(&condition_2);
61 ASSERT_EQ(NodeStatus::RUNNING, state);
75 ASSERT_EQ(NodeStatus::RUNNING, state);
88 std::stringstream stream;
90 const auto string = stream.str();
94 ASSERT_FALSE(std::getline(stream, line,
'\n').fail());
95 ASSERT_STREQ(
"----------------", line.c_str());
98 ASSERT_FALSE(std::getline(stream, line,
'\n').fail());
99 ASSERT_STREQ(
root.
name().c_str(), line.c_str());
101 ASSERT_FALSE(std::getline(stream, line,
'\n').fail());
104 ASSERT_FALSE(std::getline(stream, line,
'\n').fail());
107 ASSERT_FALSE(std::getline(stream, line,
'\n').fail());
110 ASSERT_FALSE(std::getline(stream, line,
'\n').fail());
111 ASSERT_STREQ((
" " +
action_1.
name()).c_str(), line.c_str());
114 ASSERT_FALSE(std::getline(stream, line,
'\n').fail());
115 ASSERT_STREQ(
"----------------", line.c_str());
118 ASSERT_TRUE(std::getline(stream, line,
'\n').fail());
124 int main(
int argc,
char** argv)
126 testing::InitGoogleTest(&argc, argv);
130 testing::AddGlobalTestEnvironment(environment);
132 return RUN_ALL_TESTS();
BT::ConditionTestNode condition_2
BT::ConditionTestNode condition_1
NodeStatus status() const
BT::FallbackNode fal_conditions
Environment * environment
void setExpectedResult(NodeStatus res)
const std::string & name() const
Name of the instance, not the type.
int main(int argc, char **argv)
void printTreeRecursively(const TreeNode *root_node, std::ostream &stream=std::cout)
void addChild(TreeNode *child)
The method used to add nodes to the children vector.
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
The FallbackNode is used to try different strategies, until one succeeds. If any child returns RUNNIN...
The SequenceNode is used to tick children in an ordered sequence. If any child returns RUNNING...
TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True)
BT::AsyncActionTest action_1