bt_factory.cpp
Go to the documentation of this file.
00001 /*  Copyright (C) 2018-2019 Davide Faconti, Eurecat -  All Rights Reserved
00002 *
00003 *   Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
00004 *   to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
00005 *   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:
00006 *   The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
00007 *
00008 *   THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00009 *   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,
00010 *   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.
00011 */
00012 
00013 #include "behaviortree_cpp/bt_factory.h"
00014 #include "behaviortree_cpp/utils/shared_library.h"
00015 #include "behaviortree_cpp/xml_parsing.h"
00016 
00017 namespace BT
00018 {
00019 BehaviorTreeFactory::BehaviorTreeFactory()
00020 {
00021     registerNodeType<FallbackNode>("Fallback");
00022     registerNodeType<SequenceNode>("Sequence");
00023     registerNodeType<SequenceStarNode>("SequenceStar");
00024     registerNodeType<ParallelNode>("Parallel");
00025     registerNodeType<ReactiveSequence>("ReactiveSequence");
00026     registerNodeType<ReactiveFallback>("ReactiveFallback");
00027 
00028     registerNodeType<InverterNode>("Inverter");
00029     registerNodeType<RetryNode>("RetryUntilSuccesful");
00030     registerNodeType<RepeatNode>("Repeat");
00031     registerNodeType<TimeoutNode>("Timeout");
00032 
00033     registerNodeType<ForceSuccessNode>("ForceSuccess");
00034     registerNodeType<ForceFailureNode>("ForceFailure");
00035 
00036     registerNodeType<AlwaysSuccessNode>("AlwaysSuccess");
00037     registerNodeType<AlwaysFailureNode>("AlwaysFailure");
00038     registerNodeType<SetBlackboard>("SetBlackboard");
00039 
00040     registerNodeType<DecoratorSubtreeNode>("SubTree");
00041 
00042     registerNodeType<BlackboardPreconditionNode<int>>("BlackboardCheckInt");
00043     registerNodeType<BlackboardPreconditionNode<double>>("BlackboardCheckDouble");
00044     registerNodeType<BlackboardPreconditionNode<std::string>>("BlackboardCheckString");
00045 
00046     for( const auto& it: builders_)
00047     {
00048         builtin_IDs_.insert( it.first );
00049     }
00050 }
00051 
00052 bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID)
00053 {
00054     if( builtinNodes().count(ID) )
00055     {
00056         throw LogicError("You can not remove the builtin registration ID [", ID, "]");
00057     }
00058     auto it = builders_.find(ID);
00059     if (it == builders_.end())
00060     {
00061         return false;
00062     }
00063     builders_.erase(ID);
00064     manifests_.erase(ID);
00065     return true;
00066 }
00067 
00068 void BehaviorTreeFactory::registerBuilder(const TreeNodeManifest& manifest, const NodeBuilder& builder)
00069 {
00070     auto it = builders_.find( manifest.registration_ID);
00071     if (it != builders_.end())
00072     {
00073         throw BehaviorTreeException("ID [", manifest.registration_ID, "] already registered");
00074     }
00075 
00076     builders_.insert(  {manifest.registration_ID, builder} );
00077     manifests_.insert( {manifest.registration_ID, manifest} );
00078 }
00079 
00080 void BehaviorTreeFactory::registerSimpleCondition(const std::string& ID,
00081                                                   const SimpleConditionNode::TickFunctor& tick_functor,
00082                                                   PortsList ports)
00083 {
00084     NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeConfiguration& config) {
00085         return std::make_unique<SimpleConditionNode>(name, tick_functor, config);
00086     };
00087 
00088     TreeNodeManifest manifest = { NodeType::CONDITION, ID, std::move(ports) };
00089     registerBuilder(manifest, builder);
00090 }
00091 
00092 void BehaviorTreeFactory::registerSimpleAction(const std::string& ID,
00093                                                const SimpleActionNode::TickFunctor& tick_functor,
00094                                                PortsList ports)
00095 {
00096     NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeConfiguration& config) {
00097         return std::make_unique<SimpleActionNode>(name, tick_functor, config);
00098     };
00099 
00100     TreeNodeManifest manifest = { NodeType::ACTION, ID, std::move(ports) };
00101     registerBuilder(manifest, builder);
00102 }
00103 
00104 void BehaviorTreeFactory::registerSimpleDecorator(const std::string& ID,
00105                                                   const SimpleDecoratorNode::TickFunctor& tick_functor,
00106                                                   PortsList ports)
00107 {
00108     NodeBuilder builder = [tick_functor, ID](const std::string& name, const NodeConfiguration& config) {
00109         return std::make_unique<SimpleDecoratorNode>(name, tick_functor, config);
00110     };
00111 
00112     TreeNodeManifest manifest = { NodeType::DECORATOR, ID, std::move(ports) };
00113     registerBuilder(manifest, builder);
00114 }
00115 
00116 void BehaviorTreeFactory::registerFromPlugin(const std::string& file_path)
00117 {
00118     BT::SharedLibrary loader;
00119     loader.load(file_path);
00120     typedef void (*Func)(BehaviorTreeFactory&);
00121 
00122     if (loader.hasSymbol(PLUGIN_SYMBOL))
00123     {
00124         Func func = (Func)loader.getSymbol(PLUGIN_SYMBOL);
00125         func(*this);
00126     }
00127     else
00128     {
00129         std::cout << "ERROR loading library [" << file_path << "]: can't find symbol ["
00130                   << PLUGIN_SYMBOL << "]" << std::endl;
00131     }
00132 }
00133 
00134 std::unique_ptr<TreeNode> BehaviorTreeFactory::instantiateTreeNode(
00135         const std::string& name,
00136         const std::string& ID,
00137         const NodeConfiguration& config) const
00138 {
00139     auto it = builders_.find(ID);
00140     if (it == builders_.end())
00141     {
00142         std::cerr << ID << " not included in this list:" << std::endl;
00143         for (const auto& builder_it: builders_)
00144         {
00145             std::cerr << builder_it.first << std::endl;
00146         }
00147         throw RuntimeError("BehaviorTreeFactory: ID [", ID, "] not registered");
00148     }
00149 
00150     std::unique_ptr<TreeNode> node = it->second(name, config);
00151     node->setRegistrationID( ID );
00152     return node;
00153 }
00154 
00155 const std::unordered_map<std::string, NodeBuilder> &BehaviorTreeFactory::builders() const
00156 {
00157     return builders_;
00158 }
00159 
00160 const std::unordered_map<std::string,TreeNodeManifest>& BehaviorTreeFactory::manifests() const
00161 {
00162     return manifests_;
00163 }
00164 
00165 const std::set<std::string> &BehaviorTreeFactory::builtinNodes() const
00166 {
00167     return builtin_IDs_;
00168 }
00169 
00170 Tree BehaviorTreeFactory::createTreeFromText(const std::string &text,
00171                                              Blackboard::Ptr blackboard)
00172 {
00173     XMLParser parser(*this);
00174     parser.loadFromText(text);
00175     auto tree = parser.instantiateTree(blackboard);
00176     tree.manifests = this->manifests();
00177     return tree;
00178 }
00179 
00180 Tree BehaviorTreeFactory::createTreeFromFile(const std::string &file_path,
00181                                              Blackboard::Ptr blackboard)
00182 {
00183     XMLParser parser(*this);
00184     parser.loadFromFile(file_path);
00185     auto tree = parser.instantiateTree(blackboard);
00186     tree.manifests = this->manifests();
00187     return tree;
00188 }
00189 
00190 Tree::~Tree()
00191 {
00192     if (root_node) {
00193         haltAllActions(root_node);
00194     }
00195 }
00196 
00197 Blackboard::Ptr Tree::rootBlackboard()
00198 {
00199     if( blackboard_stack.size() > 0)
00200     {
00201         return blackboard_stack.front();
00202     }
00203     return {};
00204 }
00205 
00206 
00207 }   // end namespace


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