bt_factory.h
Go to the documentation of this file.
00001 /* Copyright (C) 2018 Michele Colledanchise -  All Rights Reserved
00002  * Copyright (C) 2018-2019 Davide Faconti, Eurecat -  All Rights Reserved
00003 *
00004 *   Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
00005 *   to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
00006 *   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:
00007 *   The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
00008 *
00009 *   THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00010 *   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,
00011 *   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.
00012 */
00013 
00014 #ifndef BT_FACTORY_H
00015 #define BT_FACTORY_H
00016 
00017 #include <functional>
00018 #include <memory>
00019 #include <unordered_map>
00020 #include <unordered_set>
00021 #include <cstring>
00022 #include <algorithm>
00023 #include <set>
00024 
00025 
00026 #include "behaviortree_cpp/behavior_tree.h"
00027 
00028 namespace BT
00029 {
00030 
00032 typedef std::function<std::unique_ptr<TreeNode>(const std::string&, const NodeConfiguration&)>
00033 NodeBuilder;
00034 
00035 constexpr const char* PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin";
00036 
00037 #ifndef BT_PLUGIN_EXPORT
00038 
00039 /* Use this macro to automatically register one or more custom Nodes
00040 into a factory. For instance:
00041 
00042 BT_REGISTER_NODES(factory)
00043 {
00044     factory.registerNodeType<MoveBaseAction>("MoveBase");
00045 }
00046 
00047 IMPORTANT: this must funtion MUST be declared in a cpp file, NOT a header file.
00048 See examples for more information about configuring CMake correctly
00049 */
00050 #define BT_REGISTER_NODES(factory)                                                                 \
00051         static void BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory)
00052 
00053 #else
00054 
00055 #ifdef __linux__
00056 
00057 #define BT_REGISTER_NODES(factory)                                                                 \
00058     extern "C" void __attribute__((visibility("default")))                                         \
00059         BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory)
00060 
00061 #elif _WIN32
00062 
00063 #define BT_REGISTER_NODES(factory)                                                                 \
00064                 __declspec(dllexport) void BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory)
00065 #endif
00066 
00067 #endif
00068 
00069 
00078 struct Tree
00079 {
00080     TreeNode* root_node;
00081     std::vector<TreeNode::Ptr> nodes;
00082     std::vector<Blackboard::Ptr> blackboard_stack;
00083     std::unordered_map<std::string, TreeNodeManifest> manifests;
00084 
00085     Tree() : root_node(nullptr) { }
00086     ~Tree();
00087 
00088     Blackboard::Ptr rootBlackboard();
00089 };
00090 
00098 class BehaviorTreeFactory
00099 {
00100 public:
00101     BehaviorTreeFactory();
00102 
00104     bool unregisterBuilder(const std::string& ID);
00105 
00107     void registerBuilder(const TreeNodeManifest& manifest, const NodeBuilder& builder);
00108 
00109     template <typename T>
00110     void registerBuilder(const std::string& ID, const NodeBuilder& builder )
00111     {
00112         auto manifest = BehaviorTreeFactory::buildManifest<T>(ID);
00113         registerBuilder(manifest, builder);
00114     }
00115 
00124     void registerSimpleAction(const std::string& ID,
00125                               const SimpleActionNode::TickFunctor& tick_functor,
00126                               PortsList ports = {});
00135     void registerSimpleCondition(const std::string& ID,
00136                                  const SimpleConditionNode::TickFunctor& tick_functor,
00137                                  PortsList ports = {});
00146     void registerSimpleDecorator(const std::string& ID,
00147                                  const SimpleDecoratorNode::TickFunctor& tick_functor,
00148                                  PortsList ports = {});
00149 
00155     void registerFromPlugin(const std::string &file_path);
00156 
00165     std::unique_ptr<TreeNode> instantiateTreeNode(const std::string& name, const std::string &ID,
00166                                                   const NodeConfiguration& config) const;
00167 
00173     template <typename T>
00174     void registerNodeType(const std::string& ID)
00175     {
00176         static_assert(std::is_base_of<ActionNodeBase, T>::value ||
00177                       std::is_base_of<ControlNode, T>::value ||
00178                       std::is_base_of<DecoratorNode, T>::value ||
00179                       std::is_base_of<ConditionNode, T>::value,
00180                       "[registerBuilder]: accepts only classed derived from either ActionNodeBase, "
00181                       "DecoratorNode, ControlNode or ConditionNode");
00182 
00183         static_assert(!std::is_abstract<T>::value,
00184                       "[registerBuilder]: Some methods are pure virtual. "
00185                       "Did you override the methods tick() and halt()?");
00186 
00187         constexpr bool default_constructable = std::is_constructible<T, const std::string&>::value;
00188         constexpr bool param_constructable =
00189                 std::is_constructible<T, const std::string&, const NodeConfiguration&>::value;
00190         constexpr bool has_static_ports_list =
00191                 has_static_method_providedPorts<T>::value;
00192 
00193         static_assert(default_constructable || param_constructable,
00194                       "[registerBuilder]: the registered class must have at least one of these two "
00195                       "constructors: "
00196                       "  (const std::string&, const NodeParameters&) or (const std::string&).");
00197 
00198         static_assert(!(param_constructable && !has_static_ports_list),
00199                       "[registerBuilder]: you MUST implement the static method: "
00200                       "  PortsList providedPorts();\n");
00201 
00202         static_assert(!(has_static_ports_list && !param_constructable),
00203                       "[registerBuilder]: since you have a static method requiredNodeParameters(), "
00204                       "you MUST add a constructor sign signature (const std::string&, const "
00205                       "NodeParameters&)\n");
00206 
00207         registerNodeTypeImpl<T>(ID);
00208     }
00209 
00211     const std::unordered_map<std::string, NodeBuilder>& builders() const;
00212 
00214     const std::unordered_map<std::string, TreeNodeManifest>& manifests() const;
00215 
00217     const std::set<std::string>& builtinNodes() const;
00218 
00219     Tree createTreeFromText(const std::string& text,
00220                             Blackboard::Ptr blackboard = Blackboard::create());
00221 
00222     Tree createTreeFromFile(const std::string& file_path,
00223                             Blackboard::Ptr blackboard = Blackboard::create());
00224 
00225     template <typename T> static
00226     TreeNodeManifest buildManifest(const std::string& ID)
00227     {
00228         return { getType<T>(), ID, getProvidedPorts<T>() };
00229     }
00230 
00231 private:
00232     std::unordered_map<std::string, NodeBuilder> builders_;
00233     std::unordered_map<std::string, TreeNodeManifest> manifests_;
00234     std::set<std::string> builtin_IDs_;
00235 
00236     // template specialization = SFINAE + black magic
00237 
00238     // clang-format off
00239     template <typename T>
00240     using has_default_constructor = typename std::is_constructible<T, const std::string&>;
00241 
00242     template <typename T>
00243     using has_params_constructor  = typename std::is_constructible<T, const std::string&, const NodeConfiguration&>;
00244 
00245     template <typename T>
00246     void registerNodeTypeImpl(const std::string& ID)
00247     {
00248         NodeBuilder builder = getBuilder<T>();
00249         registerBuilder( buildManifest<T>(ID), builder);
00250     }
00251 
00252     template <typename T> static
00253     NodeBuilder getBuilder(typename std::enable_if<has_default_constructor<T>::value &&
00254                                                    has_params_constructor<T>::value >::type* = nullptr)
00255     {
00256         return [](const std::string& name, const NodeConfiguration& config)
00257         {
00258             //TODO FIXME
00259 
00260             // Special case. Use default constructor if parameters are empty
00261             if( config.input_ports.empty() &&
00262                 config.output_ports.empty() &&
00263                 has_default_constructor<T>::value)
00264             {
00265                 return std::make_unique<T>(name);
00266             }
00267             return std::make_unique<T>(name, config);
00268         };
00269     }
00270 
00271     template <typename T> static
00272     NodeBuilder getBuilder(typename std::enable_if<!has_default_constructor<T>::value &&
00273                                                    has_params_constructor<T>::value >::type* = nullptr)
00274     {
00275         return [](const std::string& name, const NodeConfiguration& params)
00276         {
00277             return std::unique_ptr<TreeNode>(new T(name, params));
00278         };
00279     }
00280 
00281     template <typename T> static
00282     NodeBuilder getBuilder(typename std::enable_if<has_default_constructor<T>::value &&
00283                                                    !has_params_constructor<T>::value >::type* = nullptr)
00284     {
00285         return [](const std::string& name, const NodeConfiguration&)
00286         {
00287             return std::unique_ptr<TreeNode>(new T(name));
00288         };
00289     }
00290     // clang-format on
00291 };
00292 
00293 }   // end namespace
00294 
00295 #endif   // BT_FACTORY_H


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