Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions include/behaviortree_cpp_v3/behavior_tree.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include "behaviortree_cpp_v3/decorators/timeout_node.h"
#include "behaviortree_cpp_v3/decorators/delay_node.h"

#include <iostream>

namespace BT
{
Expand All @@ -56,9 +57,9 @@ void applyRecursiveVisitor(const TreeNode* root_node,
void applyRecursiveVisitor(TreeNode* root_node, const std::function<void(TreeNode*)>& visitor);

/**
* Debug function to print on screen the hierarchy of the tree.
* Debug function to print the hierarchy of the tree. Prints to std::cout by default.
*/
void printTreeRecursively(const TreeNode* root_node);
void printTreeRecursively(const TreeNode* root_node, std::ostream& stream = std::cout);

typedef std::vector<std::pair<uint16_t, uint8_t>> SerializedTreeStatus;

Expand Down
14 changes: 7 additions & 7 deletions src/behavior_tree.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,21 +60,21 @@ void applyRecursiveVisitor(TreeNode* node, const std::function<void(TreeNode*)>&
}
}

void printTreeRecursively(const TreeNode* root_node)
void printTreeRecursively(const TreeNode* root_node, std::ostream& stream)
{
std::function<void(unsigned, const BT::TreeNode*)> recursivePrint;

recursivePrint = [&recursivePrint](unsigned indent, const BT::TreeNode* node) {
recursivePrint = [&recursivePrint, &stream](unsigned indent, const BT::TreeNode* node) {
for (unsigned i = 0; i < indent; i++)
{
std::cout << " ";
stream << " ";
}
if (!node)
{
std::cout << "!nullptr!" << std::endl;
stream << "!nullptr!" << std::endl;
return;
}
std::cout << node->name() << std::endl;
stream << node->name() << std::endl;
indent++;

if (auto control = dynamic_cast<const BT::ControlNode*>(node))
Expand All @@ -90,9 +90,9 @@ void printTreeRecursively(const TreeNode* root_node)
}
};

std::cout << "----------------" << std::endl;
stream << "----------------" << std::endl;
recursivePrint(0, root_node);
std::cout << "----------------" << std::endl;
stream << "----------------" << std::endl;
}

void buildSerializedStatusSnapshot(TreeNode* root_node, SerializedTreeStatus& serialized_buffer)
Expand Down
42 changes: 42 additions & 0 deletions tests/gtest_tree.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,9 @@
#include "condition_test_node.h"
#include "behaviortree_cpp_v3/behavior_tree.h"

#include <sstream>
#include <string>

using BT::NodeStatus;
using std::chrono::milliseconds;

Expand Down Expand Up @@ -76,6 +79,45 @@ TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True)
ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
}

TEST_F(BehaviorTreeTest, PrintWithStream)
{
// no stream parameter should go to default stream (std::cout)
BT::printTreeRecursively(&root);

// verify value for with custom stream parameter
std::stringstream stream;
BT::printTreeRecursively(&root, stream);
const auto string = stream.str();
std::string line;

// first line is all dashes
ASSERT_FALSE(std::getline(stream, line, '\n').fail());
ASSERT_STREQ("----------------", line.c_str());

// each line is the name of the node, indented by depth * 3 spaces
ASSERT_FALSE(std::getline(stream, line, '\n').fail());
ASSERT_STREQ(root.name().c_str(), line.c_str());

ASSERT_FALSE(std::getline(stream, line, '\n').fail());
ASSERT_STREQ((" " + fal_conditions.name()).c_str(), line.c_str());

ASSERT_FALSE(std::getline(stream, line, '\n').fail());
ASSERT_STREQ((" " + condition_1.name()).c_str(), line.c_str());

ASSERT_FALSE(std::getline(stream, line, '\n').fail());
ASSERT_STREQ((" " + condition_2.name()).c_str(), line.c_str());

ASSERT_FALSE(std::getline(stream, line, '\n').fail());
ASSERT_STREQ((" " + action_1.name()).c_str(), line.c_str());

// last line is all dashes
ASSERT_FALSE(std::getline(stream, line, '\n').fail());
ASSERT_STREQ("----------------", line.c_str());

// no more lines
ASSERT_TRUE(std::getline(stream, line, '\n').fail());
}

int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
Expand Down