bt_factory.h
Go to the documentation of this file.
00001 /* Copyright (C) 2018 Michele Colledanchise -  All Rights Reserved
00002  * Copyright (C) 2018 Davide Faconti -  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 <map>
00020 #include <set>
00021 #include <cstring>
00022 #include <algorithm>
00023 
00024 #include "behaviortree_cpp/behavior_tree.h"
00025 
00026 namespace BT
00027 {
00029 typedef std::function<std::unique_ptr<TreeNode>(const std::string&, const NodeParameters&)>
00030     NodeBuilder;
00031 
00033 struct TreeNodeManifest
00034 {
00035     NodeType type;
00036     std::string registration_ID;
00037     NodeParameters required_parameters;
00038 };
00039 
00040 const char PLUGIN_SYMBOL[] = "BT_RegisterNodesFromPlugin";
00041 #define BT_REGISTER_NODES(factory)                                                                 \
00042     extern "C" void __attribute__((visibility("default")))                                         \
00043         BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory)
00044 
00045 class BehaviorTreeFactory
00046 {
00047   public:
00048     BehaviorTreeFactory();
00049 
00050     bool unregisterBuilder(const std::string& ID);
00051 
00055     void registerBuilder(const TreeNodeManifest& manifest, NodeBuilder builder);
00056 
00058     void registerSimpleAction(const std::string& ID,
00059                               const SimpleActionNode::TickFunctor& tick_functor);
00060 
00062     void registerSimpleCondition(const std::string& ID,
00063                                  const SimpleConditionNode::TickFunctor& tick_functor);
00064 
00066     void registerSimpleDecorator(const std::string& ID,
00067                                  const SimpleDecoratorNode::TickFunctor& tick_functor);
00068 
00076     void registerFromPlugin(const std::string file_path);
00077 
00086     std::unique_ptr<TreeNode> instantiateTreeNode(const std::string& ID, const std::string& name,
00087                                                   const NodeParameters& params,
00088                                                   const Blackboard::Ptr& blackboard) const;
00089 
00097     template <typename T>
00098     void registerNodeType(const std::string& ID)
00099     {
00100         static_assert(std::is_base_of<ActionNodeBase, T>::value ||
00101                           std::is_base_of<ControlNode, T>::value ||
00102                           std::is_base_of<DecoratorNode, T>::value ||
00103                           std::is_base_of<ConditionNode, T>::value,
00104                       "[registerBuilder]: accepts only classed derived from either ActionNodeBase, "
00105                       "DecoratorNode, ControlNode or ConditionNode");
00106 
00107         static_assert(!std::is_abstract<T>::value,
00108                       "[registerBuilder]: Some methods are pure virtual. "
00109                       "Did you override the methods tick() and halt()?");
00110 
00111         constexpr bool default_constructable = std::is_constructible<T, const std::string&>::value;
00112         constexpr bool param_constructable =
00113             std::is_constructible<T, const std::string&, const NodeParameters&>::value;
00114         constexpr bool has_static_required_parameters =
00115             has_static_method_requiredParams<T>::value;
00116 
00117         static_assert(default_constructable || param_constructable,
00118                       "[registerBuilder]: the registered class must have at least one of these two "
00119                       "constructors: "
00120                       "  (const std::string&, const NodeParameters&) or (const std::string&).");
00121 
00122         static_assert(!(param_constructable && !has_static_required_parameters),
00123                       "[registerBuilder]: you MUST implement the static method: "
00124                       "  const NodeParameters& requiredNodeParameters();\n");
00125 
00126         static_assert(!(has_static_required_parameters && !param_constructable),
00127                       "[registerBuilder]: since you have a static method requiredNodeParameters(), "
00128                       "you MUST add a constructor sign signature (const std::string&, const "
00129                       "NodeParameters&)\n");
00130 
00131         registerNodeTypeImpl<T>(ID);
00132     }
00133 
00135     const std::map<std::string, NodeBuilder>& builders() const;
00136 
00138     const std::vector<TreeNodeManifest>& manifests() const;
00139 
00140     const  std::set<std::string>& builtinNodes() const;
00141 
00142   private:
00143     std::map<std::string, NodeBuilder> builders_;
00144     std::vector<TreeNodeManifest> manifests_;
00145     std::set<std::string> builtin_IDs_;
00146 
00147     // template specialization = SFINAE + black magic
00148 
00149     // clang-format off
00150     template <typename T>
00151     using has_default_constructor = typename std::is_constructible<T, const std::string&>;
00152 
00153     template <typename T>
00154     using has_params_constructor  = typename std::is_constructible<T, const std::string&, const NodeParameters&>;
00155 
00156     template <typename T, typename = void>
00157     struct has_static_method_requiredParams: std::false_type {};
00158 
00159     template <typename T>
00160     struct has_static_method_requiredParams<T,
00161             typename std::enable_if<std::is_same<decltype(T::requiredNodeParameters()), const NodeParameters&>::value>::type>
00162         : std::true_type {};
00163 
00164     template <typename T>
00165     void registerNodeTypeImpl(const std::string& ID)
00166     {
00167         NodeBuilder builder = getBuilderImpl<T>();
00168         TreeNodeManifest manifest = { getType<T>(), ID,
00169                                       getRequiredParamsImpl<T>() };
00170         registerBuilder(manifest, builder);
00171     }
00172 
00173     template <typename T>
00174     NodeBuilder getBuilderImpl(typename std::enable_if< !has_params_constructor<T>::value >::type* = nullptr)
00175     {
00176         return [](const std::string& name, const NodeParameters&)
00177         {
00178             return std::unique_ptr<TreeNode>(new T(name));
00179         };
00180     }
00181 
00182     template <typename T>
00183     NodeBuilder getBuilderImpl(typename std::enable_if<has_default_constructor<T>::value && has_params_constructor<T>::value >::type* = nullptr)
00184     {
00185         return [this](const std::string& name, const NodeParameters& params)
00186         {
00187             // Special case. Use default constructor if parameters are empty
00188             if( params.empty() && has_default_constructor<T>::value && getRequiredParamsImpl<T>().size()>0)
00189             {
00190                 return std::unique_ptr<TreeNode>(new T(name));
00191             }
00192             return std::unique_ptr<TreeNode>(new T(name, params));
00193         };
00194     }
00195 
00196     template <typename T>
00197     NodeBuilder getBuilderImpl(typename std::enable_if<!has_default_constructor<T>::value && has_params_constructor<T>::value >::type* = nullptr)
00198     {
00199         return [](const std::string& name, const NodeParameters& params)
00200         {
00201             return std::unique_ptr<TreeNode>(new T(name, params));
00202         };
00203     }
00204 
00205     template <typename T>
00206     NodeParameters getRequiredParamsImpl(typename std::enable_if< has_static_method_requiredParams<T>::value >::type* = nullptr)
00207     {
00208         return T::requiredNodeParameters();
00209     }
00210 
00211     template <typename T>
00212     NodeParameters getRequiredParamsImpl(typename std::enable_if< !has_static_method_requiredParams<T>::value >::type* = nullptr)
00213     {
00214         return NodeParameters();
00215     }
00216     // clang-format on
00217 
00218     void sortTreeNodeManifests();
00219 
00220 };
00221 
00222 }   // end namespace
00223 #endif   // BT_FACTORY_H


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sat Feb 2 2019 03:50:09