Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
BT Namespace Reference

Namespaces

namespace  details
namespace  strings_internal

Classes

class  ActionNodeBase
 The ActionNodeBase is the base class to use to create any kind of action. A particular derived class is free to override executeTick() as needed. More...
class  AlwaysFailureNode
class  AlwaysSuccessNode
class  Any
class  AsyncActionNode
 The AsyncActionNode uses a different thread where the action will be executed. More...
class  AsyncActionTest
class  BehaviorTreeException
class  BehaviorTreeFactory
 The BehaviorTreeFactory is used to create instances of a TreeNode at run-time. More...
class  Blackboard
 The Blackboard is the mechanism used by BehaviorTrees to exchange typed data. More...
class  BlackboardPreconditionNode
class  ConditionNode
class  ConditionTestNode
class  ControlNode
class  CoroActionNode
 The CoroActionNode class is an ideal candidate for asynchronous actions which need to communicate with an external service using an asynch request/reply interface (being notable examples ActionLib in ROS, MoveIt clients or move_base clients). More...
class  DecoratorNode
class  DecoratorSubtreeNode
class  FallbackNode
 The FallbackNode is used to try different strategies, until one succeeds. If any child returns RUNNING, previous children will NOT be ticked again. More...
class  FileLogger
class  ForceFailureNode
 The ForceFailureNode returns always FAILURE or RUNNING. More...
class  ForceSuccessNode
 The ForceSuccessNode returns always SUCCESS or RUNNING. More...
struct  has_static_method_providedPorts
struct  has_static_method_providedPorts< T, typename std::enable_if< std::is_same< decltype(T::providedPorts()), PortsList >::value >::type >
class  InverterNode
 The InverterNode returns SUCCESS if child fails of FAILURE is child succeeds. RUNNING status is propagated. More...
class  LeafNode
class  LogicError
class  MinitraceLogger
struct  NodeConfiguration
class  ParallelNode
class  Parser
 The BehaviorTreeParser is a class used to read the model of a BehaviorTree from file or text and instantiate the corresponding tree using the BehaviorTreeFactory. More...
class  PortInfo
class  PublisherZMQ
class  ReactiveFallback
 The ReactiveFallback is similar to a ParallelNode. All the children are ticked from first to last: More...
class  ReactiveSequence
 The ReactiveSequence is similar to a ParallelNode. All the children are ticked from first to last: More...
class  RepeatNode
 The RepeatNode is used to execute a child several times, as long as it succeed. More...
class  RetryNode
 The RetryNode is used to execute a child several times if it fails. More...
class  RuntimeError
class  scoped_demangled_name
class  SequenceNode
 The SequenceNode is used to tick children in an ordered sequence. If any child returns RUNNING, previous children will NOT be ticked again. More...
class  SequenceStarNode
 The SequenceStarNode is used to tick children in an ordered sequence. If any child returns RUNNING, previous children are not ticked again. More...
class  SetBlackboard
 The SetBlackboard is action used to store a string into an entry of the Blackboard specified in "output_key". More...
class  SharedLibrary
class  Signal
class  SimpleActionNode
 The SimpleActionNode provides an easy to use SyncActionNode. The user should simply provide a callback with this signature. More...
class  SimpleConditionNode
 The SimpleConditionNode provides an easy to use ConditionNode. The user should simply provide a callback with this signature. More...
class  SimpleDecoratorNode
 The SimpleDecoratorNode provides an easy to use DecoratorNode. The user should simply provide a callback with this signature. More...
class  StatusChangeLogger
class  StdCoutLogger
 AddStdCoutLoggerToTree. Give the root node of a tree, a simple callback is subscribed to any status change of each node. More...
class  SyncActionNode
 The SyncActionNode is an ActionNode that explicitly prevents the status RUNNING and doesn't require an implementation of halt(). More...
class  SyncActionTest
class  TimeoutNode
 The TimeoutNode will halt() a running child if the latter has been RUNNING for more than a give time. The timeout is in millisecons and it is passed using the port "msec". More...
class  TimerQueue
struct  Tree
 Struct used to store a tree. If this object goes out of scope, the tree is destroyed. More...
class  TreeNode
 Abstract base class for Behavior Tree Nodes. More...
struct  TreeNodeManifest
 This information is used mostly by the XMLParser. More...
class  XMLParser
 The XMLParser is a class used to read the model of a BehaviorTree from file or text and instantiate the corresponding tree using the BehaviorTreeFactory. More...

Typedefs

typedef
std::chrono::high_resolution_clock::duration 
Duration
typedef std::function
< std::unique_ptr< TreeNode >
const std::string &, const
NodeConfiguration &)> 
NodeBuilder
 The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern)
typedef std::unordered_map
< std::string, PortInfo
PortsList
typedef std::unordered_map
< std::string, std::string > 
PortsRemapping
typedef std::array< uint8_t, 12 > SerializedTransition
typedef std::vector< std::pair
< uint16_t, uint8_t > > 
SerializedTreeStatus
typedef std::function< Any(StringView)> StringConverter
typedef std::unordered_map
< const std::type_info
*, StringConverter
StringConvertersMap
typedef nonstd::string_view StringView
typedef
std::chrono::high_resolution_clock::time_point 
TimePoint

Enumerations

enum  NodeStatus { IDLE = 0, RUNNING, SUCCESS, FAILURE }
enum  NodeType {
  UNDEFINED = 0, ACTION, CONDITION, CONTROL,
  DECORATOR, SUBTREE
}
 Enumerates the possible types of nodes. More...
enum  PortDirection { INPUT, OUTPUT, INOUT }
enum  TimestampType { ABSOLUTE, RELATIVE }

Functions

void applyRecursiveVisitor (const TreeNode *root_node, const std::function< void(const TreeNode *)> &visitor)
void applyRecursiveVisitor (TreeNode *root_node, const std::function< void(TreeNode *)> &visitor)
template<typename T >
void assignDefaultRemapping (NodeConfiguration &config)
template<typename T = void>
std::pair< std::string, PortInfoBidirectionalPort (StringView name, StringView description={})
template<typename T = void>
std::pair< std::string, PortInfoBidirectionalPort (StringView name, const T &default_value, StringView description)
void buildSerializedStatusSnapshot (const TreeNode *root_node, SerializedTreeStatus &serialized_buffer)
 buildSerializedStatusSnapshot can be used to create a buffer that can be stored (or sent to a client application) to know the status of all the nodes of a tree. It is not "human readable".
void buildSerializedStatusSnapshot (TreeNode *root_node, SerializedTreeStatus &serialized_buffer)
Tree buildTreeFromFile (const BehaviorTreeFactory &factory, const std::string &filename, const Blackboard::Ptr &blackboard)
Tree buildTreeFromText (const BehaviorTreeFactory &factory, const std::string &text, const Blackboard::Ptr &blackboard)
 child_halted_ (false)
template<>
Position2D convertFromString (StringView str)
template<typename T >
convertFromString (StringView)
template<>
bool convertFromString< bool > (StringView str)
template<>
const char * convertFromString< const char * > (StringView str)
template<>
double convertFromString< double > (StringView str)
template<>
int convertFromString< int > (StringView str)
template<>
NodeStatus convertFromString< NodeStatus > (StringView str)
template<>
NodeType convertFromString< NodeType > (StringView str)
template<>
PortDirection convertFromString< PortDirection > (StringView str)
template<>
std::string convertFromString< std::string > (StringView str)
template<>
std::vector< double > convertFromString< std::vector< double > > (StringView str)
template<>
std::vector< int > convertFromString< std::vector< int > > (StringView str)
template<>
unsigned convertFromString< unsigned > (StringView str)
Serialization::NodeType convertToFlatbuffers (BT::NodeType type)
Serialization::NodeStatus convertToFlatbuffers (BT::NodeStatus type)
Serialization::PortDirection convertToFlatbuffers (BT::PortDirection direction)
void CreateFlatbuffersBehaviorTree (flatbuffers::FlatBufferBuilder &builder, const BT::Tree &tree)
template<typename T = void>
std::pair< std::string, PortInfoCreatePort (PortDirection direction, StringView name, StringView description={})
 current_child_idx_ (0)
std::string demangle (char const *name)
std::string demangle (const std::type_info *info)
std::string demangle (const std::type_info &info)
char const * demangle_alloc (char const *name) noexcept
void demangle_free (char const *name) noexcept
template<typename T >
StringConverter GetAnyFromStringFunctor ()
template<>
StringConverter GetAnyFromStringFunctor< void > ()
template<typename T >
PortsList getProvidedPorts (enable_if< has_static_method_providedPorts< T > >=nullptr)
template<typename T >
PortsList getProvidedPorts (enable_if_not< has_static_method_providedPorts< T > >=nullptr)
template<typename T >
NodeType getType ()
static uint16_t getUID ()
void haltAllActions (TreeNode *root_node)
template<typename T = void>
std::pair< std::string, PortInfoInputPort (StringView name, StringView description={})
template<typename T = void>
std::pair< std::string, PortInfoInputPort (StringView name, const T &default_value, StringView description)
 max_attempts_ (NTries)
 msec_ (milliseconds)
 num_cycles_ (NTries)
std::ostream & operator<< (std::ostream &os, const BT::NodeStatus &status)
std::ostream & operator<< (std::ostream &os, const BT::NodeType &type)
std::ostream & operator<< (std::ostream &os, const BT::PortDirection &type)
template<typename T = void>
std::pair< std::string, PortInfoOutputPort (StringView name, StringView description={})
template<typename T = void>
std::pair< std::string, PortInfoOutputPort (StringView name, const T &default_value, StringView description)
void printTreeRecursively (const TreeNode *root_node)
 read_parameter_from_ports_ (false)
SerializedTransition SerializeTransition (uint16_t UID, Duration timestamp, NodeStatus prev_status, NodeStatus status)
std::vector< StringViewsplitString (const StringView &strToSplit, char delimeter)
void StrAppend (std::string *destination, const nonstd::string_view &a)
void StrAppend (std::string *destination, const nonstd::string_view &a, const nonstd::string_view &b)
void StrAppend (std::string *destination, const nonstd::string_view &a, const nonstd::string_view &b, const nonstd::string_view &c)
template<typename... AV>
void StrAppend (std::string *destination, const nonstd::string_view &a, const nonstd::string_view &b, const nonstd::string_view &c, const nonstd::string_view &d, const AV &...args)
std::string StrCat ()
std::string StrCat (const nonstd::string_view &a)
std::string StrCat (const nonstd::string_view &a, const nonstd::string_view &b)
std::string StrCat (const nonstd::string_view &a, const nonstd::string_view &b, const nonstd::string_view &c)
template<typename... AV>
std::string StrCat (const nonstd::string_view &a, const nonstd::string_view &b, const nonstd::string_view &c, const nonstd::string_view &d, const AV &...args)
 threshold_ (threshold)
 timeout_started_ (false)
 timer_id_ (0)
template<typename T >
std::string toStr (T value)
std::string toStr (std::string value)
std::string toStr (BT::NodeStatus status, bool colored)
 toStr converts NodeStatus to string. Optionally colored.
template<>
std::string toStr< BT::NodeStatus > (BT::NodeStatus status)
template<>
std::string toStr< BT::NodeType > (BT::NodeType type)
 toStr converts NodeType to string.
template<>
std::string toStr< BT::PortDirection > (BT::PortDirection direction)
template<>
std::string toStr< NodeStatus > (NodeStatus status)
template<>
std::string toStr< NodeType > (NodeType type)
template<>
std::string toStr< PortDirection > (PortDirection direction)
 try_index_ (0)
void VerifyXML (const std::string &xml_text, const std::set< std::string > &registered_nodes)
std::string writeTreeNodesModelXML (const BehaviorTreeFactory &factory)

Variables

constexpr const char * PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin"

Typedef Documentation

typedef std::chrono::high_resolution_clock::duration BT::Duration

Definition at line 339 of file basic_types.h.

typedef std::function<std::unique_ptr<TreeNode>const std::string&, const NodeConfiguration&)> BT::NodeBuilder

The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern)

Definition at line 33 of file bt_factory.h.

typedef std::unordered_map<std::string, PortInfo> BT::PortsList

Definition at line 316 of file basic_types.h.

typedef std::unordered_map<std::string, std::string> BT::PortsRemapping

Definition at line 39 of file tree_node.h.

typedef std::array< uint8_t, 12 > BT::SerializedTransition

Definition at line 10 of file bt_flatbuffer_helper.h.

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

Definition at line 61 of file behavior_tree.h.

typedef std::function<Any(StringView)> BT::StringConverter

Definition at line 106 of file basic_types.h.

typedef std::unordered_map<const std::type_info*, StringConverter> BT::StringConvertersMap

Definition at line 108 of file basic_types.h.

typedef nonstd::string_view BT::StringView

Definition at line 50 of file basic_types.h.

typedef std::chrono::high_resolution_clock::time_point BT::TimePoint

Definition at line 338 of file basic_types.h.


Enumeration Type Documentation

Enumerates the states every node can be in after execution during a particular time step. IMPORTANT: Your custom nodes should NEVER return IDLE.

Enumerator:
IDLE 
RUNNING 
SUCCESS 
FAILURE 

Definition at line 35 of file basic_types.h.

Enumerates the possible types of nodes.

Enumerator:
UNDEFINED 
ACTION 
CONDITION 
CONTROL 
DECORATOR 
SUBTREE 

Definition at line 22 of file basic_types.h.

Enumerator:
INPUT 
OUTPUT 
INOUT 

Definition at line 43 of file basic_types.h.

Enumerator:
ABSOLUTE 
RELATIVE 

Definition at line 9 of file abstract_logger.h.


Function Documentation

void BT::applyRecursiveVisitor ( const TreeNode *  root_node,
const std::function< void(const TreeNode *)> &  visitor 
)

Definition at line 18 of file behavior_tree.cpp.

void BT::applyRecursiveVisitor ( TreeNode *  root_node,
const std::function< void(TreeNode *)> &  visitor 
)

Definition at line 41 of file behavior_tree.cpp.

template<typename T >
void BT::assignDefaultRemapping ( NodeConfiguration &  config) [inline]

Definition at line 270 of file tree_node.h.

template<typename T = void>
std::pair<std::string,PortInfo> BT::BidirectionalPort ( StringView  name) [inline]

Definition at line 286 of file basic_types.h.

template<typename T = void>
std::pair<std::string,PortInfo> BT::BidirectionalPort ( StringView  name,
const T &  default_value,
StringView  description 
) [inline]

Definition at line 308 of file basic_types.h.

void BT::buildSerializedStatusSnapshot ( const TreeNode *  root_node,
SerializedTreeStatus &  serialized_buffer 
)

buildSerializedStatusSnapshot can be used to create a buffer that can be stored (or sent to a client application) to know the status of all the nodes of a tree. It is not "human readable".

Parameters:
root_node
serialized_bufferis the output.
void BT::buildSerializedStatusSnapshot ( TreeNode *  root_node,
SerializedTreeStatus &  serialized_buffer 
)

Definition at line 98 of file behavior_tree.cpp.

Tree BT::buildTreeFromFile ( const BehaviorTreeFactory &  factory,
const std::string &  filename,
const Blackboard::Ptr &  blackboard 
)

Definition at line 720 of file xml_parsing.cpp.

Tree BT::buildTreeFromText ( const BehaviorTreeFactory &  factory,
const std::string &  text,
const Blackboard::Ptr &  blackboard 
)

Definition at line 712 of file xml_parsing.cpp.

BT::child_halted_ ( false  )
template<>
Pose2D BT::convertFromString ( StringView  str) [inline]

Definition at line 17 of file t03_generic_ports.cpp.

template<typename T >
T BT::convertFromString ( StringView  ) [inline]

convertFromString is used to convert a string into a custom type.

This function is invoked under the hood by TreeNode::getInput(), but only when the input port contains a string.

If you have a custom type, you need to implement the corresponding template specialization.

Definition at line 61 of file basic_types.h.

template<>
bool BT::convertFromString< bool > ( StringView  str)

Definition at line 156 of file basic_types.cpp.

template<>
const char * BT::convertFromString< const char * > ( StringView  str)

Definition at line 104 of file basic_types.cpp.

template<>
double BT::convertFromString< double > ( StringView  str)

Definition at line 122 of file basic_types.cpp.

template<>
int BT::convertFromString< int > ( StringView  str)

Definition at line 110 of file basic_types.cpp.

template<>
NodeStatus BT::convertFromString< NodeStatus > ( StringView  str)

Definition at line 187 of file basic_types.cpp.

template<>
NodeType BT::convertFromString< NodeType > ( StringView  str)

Definition at line 197 of file basic_types.cpp.

template<>
PortDirection BT::convertFromString< PortDirection > ( StringView  str)

Definition at line 208 of file basic_types.cpp.

template<>
std::string BT::convertFromString< std::string > ( StringView  str)

Definition at line 97 of file basic_types.cpp.

template<>
std::vector< double > BT::convertFromString< std::vector< double > > ( StringView  str)

Definition at line 142 of file basic_types.cpp.

template<>
std::vector< int > BT::convertFromString< std::vector< int > > ( StringView  str)

Definition at line 128 of file basic_types.cpp.

template<>
unsigned BT::convertFromString< unsigned > ( StringView  str)

Definition at line 116 of file basic_types.cpp.

Definition at line 12 of file bt_flatbuffer_helper.h.

Definition at line 32 of file bt_flatbuffer_helper.h.

Definition at line 48 of file bt_flatbuffer_helper.h.

void BT::CreateFlatbuffersBehaviorTree ( flatbuffers::FlatBufferBuilder builder,
const BT::Tree tree 
) [inline]

Definition at line 62 of file bt_flatbuffer_helper.h.

template<typename T = void>
std::pair<std::string,PortInfo> BT::CreatePort ( PortDirection  direction,
StringView  name 
)

Definition at line 251 of file basic_types.h.

Definition at line 21 of file fallback_node.cpp.

std::string BT::demangle ( char const *  name) [inline]

Definition at line 78 of file demangle_util.h.

std::string BT::demangle ( const std::type_info *  info) [inline]

Definition at line 85 of file demangle_util.h.

std::string BT::demangle ( const std::type_info &  info) [inline]

Definition at line 107 of file demangle_util.h.

char const * BT::demangle_alloc ( char const *  name) [inline]

Definition at line 69 of file demangle_util.h.

void BT::demangle_free ( char const *  name) [inline]

Definition at line 74 of file demangle_util.h.

template<typename T >
StringConverter BT::GetAnyFromStringFunctor ( ) [inline]

Definition at line 113 of file basic_types.h.

template<>
StringConverter BT::GetAnyFromStringFunctor< void > ( ) [inline]

Definition at line 119 of file basic_types.h.

template<typename T >
PortsList BT::getProvidedPorts ( enable_if< has_static_method_providedPorts< T > >  = nullptr) [inline]

Definition at line 327 of file basic_types.h.

template<typename T >
PortsList BT::getProvidedPorts ( enable_if_not< has_static_method_providedPorts< T > >  = nullptr) [inline]

Definition at line 333 of file basic_types.h.

template<typename T >
NodeType BT::getType ( ) [inline]

Simple way to extract the type of a TreeNode at COMPILE TIME. Useful to avoid the cost of without dynamic_cast or the virtual method TreeNode::type().

Definition at line 77 of file behavior_tree.h.

static uint16_t BT::getUID ( ) [static]

Definition at line 19 of file tree_node.cpp.

void BT::haltAllActions ( TreeNode *  root_node)

Invoke AsyncActionNode::stopAndJoinThread() to the entire tree, when needed.

Definition at line 110 of file behavior_tree.cpp.

template<typename T = void>
std::pair<std::string,PortInfo> BT::InputPort ( StringView  name) [inline]

Definition at line 274 of file basic_types.h.

template<typename T = void>
std::pair<std::string,PortInfo> BT::InputPort ( StringView  name,
const T &  default_value,
StringView  description 
) [inline]

Definition at line 292 of file basic_types.h.

BT::max_attempts_ ( NTries  )
BT::msec_ ( milliseconds  )
BT::num_cycles_ ( NTries  )
std::ostream & BT::operator<< ( std::ostream &  os,
const BT::NodeStatus status 
)

Definition at line 222 of file basic_types.cpp.

std::ostream & BT::operator<< ( std::ostream &  os,
const BT::NodeType type 
)

Definition at line 216 of file basic_types.cpp.

std::ostream & BT::operator<< ( std::ostream &  os,
const BT::PortDirection type 
)

Definition at line 228 of file basic_types.cpp.

template<typename T = void>
std::pair<std::string,PortInfo> BT::OutputPort ( StringView  name) [inline]

Definition at line 280 of file basic_types.h.

template<typename T = void>
std::pair<std::string,PortInfo> BT::OutputPort ( StringView  name,
const T &  default_value,
StringView  description 
) [inline]

Definition at line 300 of file basic_types.h.

void BT::printTreeRecursively ( const TreeNode *  root_node)

Debug function to print on screen the hierarchy of the tree.

Definition at line 63 of file behavior_tree.cpp.

Definition at line 24 of file parallel_node.cpp.

SerializedTransition BT::SerializeTransition ( uint16_t  UID,
Duration  timestamp,
NodeStatus  prev_status,
NodeStatus  status 
) [inline]

Serialize manually the informations about state transition No flatbuffer serialization here

Definition at line 148 of file bt_flatbuffer_helper.h.

std::vector< StringView > BT::splitString ( const StringView &  strToSplit,
char  delimeter 
)

Definition at line 234 of file basic_types.cpp.

void BT::StrAppend ( std::string *  destination,
const nonstd::string_view &  a 
) [inline]

Definition at line 80 of file strcat.hpp.

void BT::StrAppend ( std::string *  destination,
const nonstd::string_view &  a,
const nonstd::string_view &  b 
) [inline]

Definition at line 86 of file strcat.hpp.

void BT::StrAppend ( std::string *  destination,
const nonstd::string_view &  a,
const nonstd::string_view &  b,
const nonstd::string_view &  c 
) [inline]

Definition at line 93 of file strcat.hpp.

template<typename... AV>
void BT::StrAppend ( std::string *  destination,
const nonstd::string_view &  a,
const nonstd::string_view &  b,
const nonstd::string_view &  c,
const nonstd::string_view &  d,
const AV &...  args 
) [inline]

Definition at line 103 of file strcat.hpp.

std::string BT::StrCat ( ) [inline]

Definition at line 47 of file strcat.hpp.

std::string BT::StrCat ( const nonstd::string_view &  a) [inline]

Definition at line 49 of file strcat.hpp.

std::string BT::StrCat ( const nonstd::string_view &  a,
const nonstd::string_view &  b 
) [inline]

Definition at line 53 of file strcat.hpp.

std::string BT::StrCat ( const nonstd::string_view &  a,
const nonstd::string_view &  b,
const nonstd::string_view &  c 
) [inline]

Definition at line 59 of file strcat.hpp.

template<typename... AV>
std::string BT::StrCat ( const nonstd::string_view &  a,
const nonstd::string_view &  b,
const nonstd::string_view &  c,
const nonstd::string_view &  d,
const AV &...  args 
) [inline]

Definition at line 68 of file strcat.hpp.

BT::threshold_ ( threshold  )
BT::timeout_started_ ( false  )

Definition at line 24 of file timeout_node.cpp.

BT::timer_id_ ( )
template<typename T >
std::string BT::toStr ( value)

Definition at line 127 of file basic_types.h.

std::string BT::toStr ( std::string  value)

Definition at line 25 of file basic_types.cpp.

std::string BT::toStr ( BT::NodeStatus  status,
bool  colored 
)

toStr converts NodeStatus to string. Optionally colored.

Definition at line 30 of file basic_types.cpp.

template<>
std::string BT::toStr< BT::NodeStatus > ( BT::NodeStatus  status)
template<>
std::string BT::toStr< BT::NodeType > ( BT::NodeType  type)

toStr converts NodeType to string.

template<>
std::string BT::toStr< BT::PortDirection > ( BT::PortDirection  direction)
template<>
std::string BT::toStr< NodeStatus > ( NodeStatus  status)

Definition at line 9 of file basic_types.cpp.

template<>
std::string BT::toStr< NodeType > ( NodeType  type)

Definition at line 76 of file basic_types.cpp.

template<>
std::string BT::toStr< PortDirection > ( PortDirection  direction)

Definition at line 64 of file basic_types.cpp.

BT::try_index_ ( )
void BT::VerifyXML ( const std::string &  xml_text,
const std::set< std::string > &  registered_nodes 
)

Definition at line 195 of file xml_parsing.cpp.

std::string BT::writeTreeNodesModelXML ( const BehaviorTreeFactory &  factory)

Definition at line 644 of file xml_parsing.cpp.


Variable Documentation

constexpr const char* BT::PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin"

Definition at line 35 of file bt_factory.h.



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