bt_factory.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2018-2020 Davide Faconti, Eurecat - All Rights Reserved
2 *
3 * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
4 * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
5 * and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
6 * The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
7 *
8 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
9 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
10 * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
11 */
12 
16 
17 #ifdef USING_ROS
18 #include "filesystem/path.h"
19 #include <ros/package.h>
20 #endif
21 
22 namespace BT
23 {
25 {
26  registerNodeType<FallbackNode>("Fallback");
27  registerNodeType<SequenceNode>("Sequence");
28  registerNodeType<SequenceStarNode>("SequenceStar");
29  registerNodeType<ParallelNode>("Parallel");
30  registerNodeType<ReactiveSequence>("ReactiveSequence");
31  registerNodeType<ReactiveFallback>("ReactiveFallback");
32  registerNodeType<IfThenElseNode>("IfThenElse");
33  registerNodeType<WhileDoElseNode>("WhileDoElse");
34 
35  registerNodeType<InverterNode>("Inverter");
36  registerNodeType<RetryNode>("RetryUntilSuccesful");
37  registerNodeType<KeepRunningUntilFailureNode>("KeepRunningUntilFailure");
38  registerNodeType<RepeatNode>("Repeat");
39  registerNodeType<TimeoutNode<>>("Timeout");
40  registerNodeType<DelayNode>("Delay");
41 
42  registerNodeType<ForceSuccessNode>("ForceSuccess");
43  registerNodeType<ForceFailureNode>("ForceFailure");
44 
45  registerNodeType<AlwaysSuccessNode>("AlwaysSuccess");
46  registerNodeType<AlwaysFailureNode>("AlwaysFailure");
47  registerNodeType<SetBlackboard>("SetBlackboard");
48 
49  registerNodeType<SubtreeNode>("SubTree");
50  registerNodeType<SubtreePlusNode>("SubTreePlus");
51 
52  registerNodeType<BlackboardPreconditionNode<int>>("BlackboardCheckInt");
53  registerNodeType<BlackboardPreconditionNode<double>>("BlackboardCheckDouble");
54  registerNodeType<BlackboardPreconditionNode<std::string>>("BlackboardCheckString");
55 
56  registerNodeType<SwitchNode<2>>("Switch2");
57  registerNodeType<SwitchNode<3>>("Switch3");
58  registerNodeType<SwitchNode<4>>("Switch4");
59  registerNodeType<SwitchNode<5>>("Switch5");
60  registerNodeType<SwitchNode<6>>("Switch6");
61 
62 #ifdef NCURSES_FOUND
63  registerNodeType<ManualSelectorNode>("ManualSelector");
64 #endif
65  for( const auto& it: builders_)
66  {
67  builtin_IDs_.insert( it.first );
68  }
69 }
70 
71 bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID)
72 {
73  if( builtinNodes().count(ID) )
74  {
75  throw LogicError("You can not remove the builtin registration ID [", ID, "]");
76  }
77  auto it = builders_.find(ID);
78  if (it == builders_.end())
79  {
80  return false;
81  }
82  builders_.erase(ID);
83  manifests_.erase(ID);
84  return true;
85 }
86 
88 {
89  auto it = builders_.find( manifest.registration_ID);
90  if (it != builders_.end())
91  {
92  throw BehaviorTreeException("ID [", manifest.registration_ID, "] already registered");
93  }
94 
95  builders_.insert( {manifest.registration_ID, builder} );
96  manifests_.insert( {manifest.registration_ID, manifest} );
97 }
98 
100  const SimpleConditionNode::TickFunctor& tick_functor,
101  PortsList ports)
102 {
103  NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeConfiguration& config) {
104  return std::make_unique<SimpleConditionNode>(name, tick_functor, config);
105  };
106 
107  TreeNodeManifest manifest = { NodeType::CONDITION, ID, std::move(ports) };
108  registerBuilder(manifest, builder);
109 }
110 
111 void BehaviorTreeFactory::registerSimpleAction(const std::string& ID,
112  const SimpleActionNode::TickFunctor& tick_functor,
113  PortsList ports)
114 {
115  NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeConfiguration& config) {
116  return std::make_unique<SimpleActionNode>(name, tick_functor, config);
117  };
118 
119  TreeNodeManifest manifest = { NodeType::ACTION, ID, std::move(ports) };
120  registerBuilder(manifest, builder);
121 }
122 
124  const SimpleDecoratorNode::TickFunctor& tick_functor,
125  PortsList ports)
126 {
127  NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeConfiguration& config) {
128  return std::make_unique<SimpleDecoratorNode>(name, tick_functor, config);
129  };
130 
131  TreeNodeManifest manifest = { NodeType::DECORATOR, ID, std::move(ports) };
132  registerBuilder(manifest, builder);
133 }
134 
135 void BehaviorTreeFactory::registerFromPlugin(const std::string& file_path)
136 {
137  BT::SharedLibrary loader;
138  loader.load(file_path);
139  typedef void (*Func)(BehaviorTreeFactory&);
140 
141  if (loader.hasSymbol(PLUGIN_SYMBOL))
142  {
143  Func func = (Func)loader.getSymbol(PLUGIN_SYMBOL);
144  func(*this);
145  }
146  else
147  {
148  std::cout << "ERROR loading library [" << file_path << "]: can't find symbol ["
149  << PLUGIN_SYMBOL << "]" << std::endl;
150  }
151 }
152 
153 #ifdef USING_ROS
154 
155  #ifdef _WIN32
156 const char os_pathsep(';'); // NOLINT
157 #else
158 const char os_pathsep(':'); // NOLINT
159 #endif
160 
161 // This function is a copy from the one in class_loader_imp.hpp in ROS pluginlib
162 // package, licensed under BSD.
163 // https://github.com/ros/pluginlib
164 std::vector<std::string> getCatkinLibraryPaths()
165 {
166  std::vector<std::string> lib_paths;
167  const char* env = std::getenv("CMAKE_PREFIX_PATH");
168  if (env)
169  {
170  const std::string env_catkin_prefix_paths(env);
171  std::vector<BT::StringView> catkin_prefix_paths =
172  splitString(env_catkin_prefix_paths, os_pathsep);
173  for (BT::StringView catkin_prefix_path : catkin_prefix_paths)
174  {
175  filesystem::path path(static_cast<std::string>(catkin_prefix_path));
176  filesystem::path lib("lib");
177  lib_paths.push_back((path / lib).str());
178  }
179  }
180  return lib_paths;
181 }
182 
184 {
185  std::vector<std::string> plugins;
186  ros::package::getPlugins("behaviortree_cpp_v3", "bt_lib_plugin", plugins, true);
187  std::vector<std::string> catkin_lib_paths = getCatkinLibraryPaths();
188 
189  for (const auto& plugin : plugins)
190  {
191  auto filename = filesystem::path(plugin + BT::SharedLibrary::suffix());
192  for (const auto& lib_path : catkin_lib_paths)
193  {
194  const auto full_path = filesystem::path(lib_path) / filename;
195  if (full_path.exists())
196  {
197  std::cout << "Registering ROS plugins from " << full_path.str() << std::endl;
198  registerFromPlugin(full_path.str());
199  break;
200  }
201  }
202  }
203 }
204 #else
205 
207  {
208  throw RuntimeError("Using attribute [ros_pkg] in <include>, but this library was compiled "
209  "without ROS support. Recompile the BehaviorTree.CPP using catkin");
210  }
211 #endif
212 
214  const std::string& name,
215  const std::string& ID,
216  const NodeConfiguration& config) const
217 {
218  auto it = builders_.find(ID);
219  if (it == builders_.end())
220  {
221  std::cerr << ID << " not included in this list:" << std::endl;
222  for (const auto& builder_it: builders_)
223  {
224  std::cerr << builder_it.first << std::endl;
225  }
226  throw RuntimeError("BehaviorTreeFactory: ID [", ID, "] not registered");
227  }
228 
229  std::unique_ptr<TreeNode> node = it->second(name, config);
230  node->setRegistrationID( ID );
231  return node;
232 }
233 
234 const std::unordered_map<std::string, NodeBuilder> &BehaviorTreeFactory::builders() const
235 {
236  return builders_;
237 }
238 
239 const std::unordered_map<std::string,TreeNodeManifest>& BehaviorTreeFactory::manifests() const
240 {
241  return manifests_;
242 }
243 
244 const std::set<std::string> &BehaviorTreeFactory::builtinNodes() const
245 {
246  return builtin_IDs_;
247 }
248 
250  Blackboard::Ptr blackboard)
251 {
252  XMLParser parser(*this);
253  parser.loadFromText(text);
254  auto tree = parser.instantiateTree(blackboard);
255  tree.manifests = this->manifests();
256  return tree;
257 }
258 
259 Tree BehaviorTreeFactory::createTreeFromFile(const std::string &file_path,
260  Blackboard::Ptr blackboard)
261 {
262  XMLParser parser(*this);
263  parser.loadFromFile(file_path);
264  auto tree = parser.instantiateTree(blackboard);
265  tree.manifests = this->manifests();
266  return tree;
267 }
268 
270 {
271  haltTree();
272 }
273 
275 {
276  if( blackboard_stack.size() > 0)
277  {
278  return blackboard_stack.front();
279  }
280  return {};
281 }
282 
283 
284 } // end namespace
constexpr const char * PLUGIN_SYMBOL
Definition: bt_factory.h:87
manifest
std::function< NodeStatus(NodeStatus, TreeNode &)> TickFunctor
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) ...
Definition: bt_factory.h:33
std::unordered_map< std::string, NodeBuilder > builders_
Definition: bt_factory.h:378
std::set< std::string > builtin_IDs_
Definition: bt_factory.h:380
std::shared_ptr< Blackboard > Ptr
Definition: blackboard.h:26
const std::set< std::string > & builtinNodes() const
List of builtin IDs.
Definition: bt_factory.cpp:244
This information is used mostly by the XMLParser.
Definition: tree_node.h:32
const std::unordered_map< std::string, NodeBuilder > & builders() const
All the builders. Made available mostly for debug purposes.
Definition: bt_factory.cpp:234
std::unordered_map< std::string, TreeNodeManifest > manifests_
Definition: bt_factory.h:379
Blackboard::Ptr rootBlackboard()
Definition: bt_factory.cpp:274
bool hasSymbol(const std::string &name)
Returns true iff a library has been loaded.
std::vector< StringView > splitString(const StringView &strToSplit, char delimeter)
std::unique_ptr< TreeNode > instantiateTreeNode(const std::string &name, const std::string &ID, const NodeConfiguration &config) const
instantiateTreeNode creates an instance of a previously registered TreeNode.
Definition: bt_factory.cpp:213
static std::string suffix()
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:207
void * getSymbol(const std::string &name)
nonstd::string_view StringView
Definition: basic_types.h:50
std::string registration_ID
Definition: tree_node.h:35
Tree createTreeFromText(const std::string &text, Blackboard::Ptr blackboard=Blackboard::create())
Definition: bt_factory.cpp:249
void registerFromPlugin(const std::string &file_path)
registerFromPlugin load a shared library and execute the function BT_REGISTER_NODES (see macro)...
Definition: bt_factory.cpp:135
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
Definition: bt_factory.h:130
Tree instantiateTree(const Blackboard::Ptr &root_blackboard) override
Simple class for manipulating paths on Linux/Windows/Mac OS.
Definition: path.h:42
void registerSimpleAction(const std::string &ID, const SimpleActionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleAction help you register nodes of type SimpleActionNode.
Definition: bt_factory.cpp:111
ROSLIB_DECL void getPlugins(const std::string &package, const std::string &attribute, V_string &plugins, bool force_recrawl=false)
std::function< NodeStatus(TreeNode &)> TickFunctor
Definition: action_node.h:85
void load(const std::string &path, int flags=0)
std::unordered_map< std::string, PortInfo > PortsList
Definition: basic_types.h:317
static volatile int count
Definition: minitrace.cpp:55
const std::unordered_map< std::string, TreeNodeManifest > & manifests() const
Manifests of all the registered TreeNodes.
Definition: bt_factory.cpp:239
The XMLParser is a class used to read the model of a BehaviorTree from file or text and instantiate t...
Definition: xml_parsing.h:14
std::unordered_map< std::string, TreeNodeManifest > manifests
Definition: bt_factory.h:136
void loadFromText(const std::string &xml_text) override
void registerBuilder(const TreeNodeManifest &manifest, const NodeBuilder &builder)
The most generic way to register your own builder.
Definition: bt_factory.cpp:87
void registerFromROSPlugins()
registerFromROSPlugins finds all shared libraries that export ROS plugins for behaviortree_cpp, and calls registerFromPlugin for each library.
Definition: bt_factory.cpp:206
bool unregisterBuilder(const std::string &ID)
Remove a registered ID.
Definition: bt_factory.cpp:71
void loadFromFile(const std::string &filename) override
Definition: xml_parsing.cpp:99
Tree createTreeFromFile(const std::string &file_path, Blackboard::Ptr blackboard=Blackboard::create())
Definition: bt_factory.cpp:259
void registerSimpleDecorator(const std::string &ID, const SimpleDecoratorNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleDecorator help you register nodes of type SimpleDecoratorNode.
Definition: bt_factory.cpp:123
void registerSimpleCondition(const std::string &ID, const SimpleConditionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleCondition help you register nodes of type SimpleConditionNode.
Definition: bt_factory.cpp:99
std::function< NodeStatus(TreeNode &)> TickFunctor


behaviotree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Tue May 4 2021 02:56:24