Public Member Functions | Private Member Functions | Private Attributes
BT::DotBt Class Reference

Provides tools for translate a BT in DOT and publishing it to ROS for visualization in RQT. More...

#include <dot_bt.h>

List of all members.

Public Member Functions

 DotBt (TreeNode *root, const std::string &topic="/bt_dotcode", double ros_rate=50, bool left_right=false, bool multiple_parents=false)
 The default constructor.
std::string getDotFile ()
 Returns the current DOT code produced for the BT.
void publish ()
 Publishes the tree for visualization.
 ~DotBt ()
 An empty destructor.

Private Member Functions

std::string defineNodeDot (TreeNode *node, const std::string &alias)
 Produces DOT code for the definition of the node.
std::string getAlias (const std::string &name)
 Returns the alias of a node.
void produceDot (TreeNode *node, TreeNode *parent=NULL, const std::string &parent_alias="")
 Produces DOT code for the tree recursively.

Private Attributes

std::vector< std::string > aliases_
 Stores the aliases of each node of tree. It is used for avoiding conflicts due to nodes with the same name or multiple parents.
std::string dot_file_
 Stores the DOT code of the current tree.
ros::Publisher dotbt_publisher_
 A ROS publisher for publishing DotBt::dot_file_.
bool left_right_
 True for left to right visualization. False for top to down.
ros::Rate loop_rate_
 The rate at which the DotBt::dotbt_publisher_ will publish the tree.
int multiple_alias_solver_
bool multiple_parents_
 True if you want to visualize nodes with multiple parents without duplication.
ros::NodeHandle n_
 A node handle used by the ROS publisher DotBt::dotbt_publisher_.
TreeNoderoot_
 The root of the Behavior Tree.
std::string topic_
 Stores the name of the topic that DotBt::dotbt_publisher_ will publish.

Detailed Description

Provides tools for translate a BT in DOT and publishing it to ROS for visualization in RQT.

The class generates code of the DOT graph description language which describes the current BT running. It also provide ROS publisher for publishing this code in a ROS topic. Then, the user can use the rqt_dot plugin in order to visualize in real-time the current tree and the status of each node. Regarding multi-parenting this class by default visualize the node multiple times under its different parents, in order to have a straight-forward visualization. Notice that in the implementation level the same node will be ticked. The class also provides the option to visualize the nodes with the same name as one node and the nodes with multiple parents as without replication (in order to detect visually these undesired replications).

Find below an example of use:

 {.cpp}
 #include <dot_bt.h>
 #include <thread>

 // ...

 // Assume root is a pointer TreeNode* to the root of your tree
 std::string topic = "/my_topic" // The ROS topic to publish the tree
 double rate = 50; // The rate of publishing in Hz
 BT::DotBt dot_bt(root, topic, rate);  // Call the constructor
 std::thread t(&BT::DotBt::publish, dot_bt); // A separate thread publishes the tree

Definition at line 63 of file dot_bt.h.


Constructor & Destructor Documentation

BT::DotBt::DotBt ( TreeNode root,
const std::string &  topic = "/bt_dotcode",
double  ros_rate = 50,
bool  left_right = false,
bool  multiple_parents = false 
) [explicit]

The default constructor.

Parameters:
rootA pointer to the root of the tree.
topicThe name of the ROS topic to publish the tree. Defaults to "/bt_dotcode".
ros_rateThe rate of the publishing in Hz. Defaults to 50Hz.
left_rightSet true if a left to right visualization is desired. Defaults to true, i.e. top-down visualization
multiple_parentsSet true if it is desired to visualize nodes with multiple parents (or nodes with the same name) without duplication. It is recommended to use the default (false) value for better results.

Definition at line 29 of file dot_bt.cpp.

An empty destructor.

Definition at line 42 of file dot_bt.cpp.


Member Function Documentation

std::string BT::DotBt::defineNodeDot ( TreeNode node,
const std::string &  alias 
) [private]

Produces DOT code for the definition of the node.

The current node's alias is used as the DOT object of the node. Then checks the type of the node (Action, Sequence etc) and gives the node the correct shape and label. Finally it checks the status of the node (Running, Idle, Failed etc) in order to give the correct color to each node.

Parameters:
nodeA pointer to the node to be defined.
aliasThe alias of the given node.
Returns:
The definition of the Node in DOT

Definition at line 44 of file dot_bt.cpp.

std::string BT::DotBt::getAlias ( const std::string &  name) [private]

Returns the alias of a node.

In general tranforms a string to lower case and replace the space with underscores. E.g. the string "My String" will be returned as "my_string".

Parameters:
nameThe initial string as input
Returns:
The final string as output.

Definition at line 182 of file dot_bt.cpp.

std::string BT::DotBt::getDotFile ( )

Returns the current DOT code produced for the BT.

Returns:
The current DOT code

Definition at line 206 of file dot_bt.cpp.

void BT::DotBt::produceDot ( TreeNode node,
TreeNode parent = NULL,
const std::string &  parent_alias = "" 
) [private]

Produces DOT code for the tree recursively.

Initially defines the current node calling DotBt::produceDot and then if the current node has a parent produces the DOT code for adding this node as the child of its parent. If the node has children repeats this process recursively. It also checks if the produced alias of the node is already existing in order to visualize with a different instance nodes with multiple parents or nodes with the same name.

Parameters:
nodeThe current node.
parentThe parent of the current node. Defaults to NULL for the root of the tree.
parent_aliasThe alias of the parent to be used in the DOT code. Defaults to empty string in case this node is the root of the tree.

Definition at line 105 of file dot_bt.cpp.

Publishes the tree for visualization.

This is the main API of the class. It publishes in the given topic with the given name the produced DOT code for the current BT running. Run it in a separate thread in your BT application.

Definition at line 211 of file dot_bt.cpp.


Member Data Documentation

std::vector<std::string> BT::DotBt::aliases_ [private]

Stores the aliases of each node of tree. It is used for avoiding conflicts due to nodes with the same name or multiple parents.

Definition at line 184 of file dot_bt.h.

std::string BT::DotBt::dot_file_ [private]

Stores the DOT code of the current tree.

Definition at line 153 of file dot_bt.h.

A ROS publisher for publishing DotBt::dot_file_.

Definition at line 163 of file dot_bt.h.

bool BT::DotBt::left_right_ [private]

True for left to right visualization. False for top to down.

Definition at line 189 of file dot_bt.h.

The rate at which the DotBt::dotbt_publisher_ will publish the tree.

Definition at line 178 of file dot_bt.h.

Definition at line 197 of file dot_bt.h.

True if you want to visualize nodes with multiple parents without duplication.

Definition at line 195 of file dot_bt.h.

A node handle used by the ROS publisher DotBt::dotbt_publisher_.

Definition at line 158 of file dot_bt.h.

The root of the Behavior Tree.

Definition at line 168 of file dot_bt.h.

std::string BT::DotBt::topic_ [private]

Stores the name of the topic that DotBt::dotbt_publisher_ will publish.

Definition at line 173 of file dot_bt.h.


The documentation for this class was generated from the following files:


behavior_tree_core
Author(s): Michele Colledanchise
autogenerated on Sun Sep 10 2017 02:31:49