gtest_blackboard.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 <gtest/gtest.h>
00014 #include "action_test_node.h"
00015 #include "condition_test_node.h"
00016 #include "behaviortree_cpp/behavior_tree.h"
00017 #include "behaviortree_cpp/bt_factory.h"
00018 #include "behaviortree_cpp/blackboard.h"
00019 #include "behaviortree_cpp/xml_parsing.h"
00020 
00021 using namespace BT;
00022 
00023 class BB_TestNode: public SyncActionNode
00024 {
00025   public:
00026     BB_TestNode(const std::string& name, const NodeConfiguration& config):
00027       SyncActionNode(name, config)
00028     { }
00029 
00030     NodeStatus tick()
00031     {
00032         int value = 0;
00033         auto res = getInput<int>("in_port");
00034         if(!res)
00035         {
00036             throw RuntimeError("BB_TestNode needs input", res.error());
00037         }
00038         value = res.value()*2;
00039         if( !setOutput("out_port", value) )
00040         {
00041             throw RuntimeError("BB_TestNode failed output");
00042         }
00043         return NodeStatus::SUCCESS;
00044     }
00045 
00046     static PortsList providedPorts()
00047     {
00048         return { BT::InputPort<int>("in_port"),
00049                  BT::OutputPort<int>("out_port") };
00050     }
00051 };
00052 
00053 
00054 class BB_TypedTestNode: public SyncActionNode
00055 {
00056   public:
00057     BB_TypedTestNode(const std::string& name, const NodeConfiguration& config):
00058       SyncActionNode(name, config)
00059     { }
00060 
00061     NodeStatus tick()
00062     {
00063         return NodeStatus::SUCCESS;
00064     }
00065 
00066     static PortsList providedPorts()
00067     {
00068         return { BT::InputPort("input"),
00069                  BT::InputPort<int>("input_int"),
00070                  BT::InputPort<std::string>("input_string"),
00071 
00072                  BT::OutputPort("output"),
00073                  BT::OutputPort<int>("output_int"),
00074                  BT::OutputPort<std::string>("output_string") };
00075     }
00076 };
00077 
00078 
00079 TEST(BlackboardTest, GetInputsFromBlackboard)
00080 {
00081     auto bb = Blackboard::create();
00082 
00083     NodeConfiguration config;
00084     assignDefaultRemapping<BB_TestNode>( config );
00085 
00086     config.blackboard = bb;
00087     bb->set("in_port", 11 );
00088 
00089     BB_TestNode node("good_one", config);
00090 
00091     // this should read and write "my_entry" in tick()
00092     node.executeTick();
00093 
00094     ASSERT_EQ( bb->get<int>("out_port"), 22 );
00095 }
00096 
00097 TEST(BlackboardTest, BasicRemapping)
00098 {
00099     auto bb = Blackboard::create();
00100 
00101     NodeConfiguration config;
00102 
00103     config.blackboard = bb;
00104     config.input_ports["in_port"]   = "{my_input_port}";
00105     config.output_ports["out_port"] = "{my_output_port}";
00106     bb->set("my_input_port", 11 );
00107 
00108     BB_TestNode node("good_one", config);
00109     node.executeTick();
00110 
00111     ASSERT_EQ( bb->get<int>("my_output_port"), 22 );
00112 }
00113 
00114 TEST(BlackboardTest, GetInputsFromText)
00115 {
00116     auto bb = Blackboard::create();
00117 
00118     NodeConfiguration config;
00119     config.input_ports["in_port"] = "11";
00120 
00121     BB_TestNode missing_out("missing_output", config);
00122     EXPECT_THROW( missing_out.executeTick(), RuntimeError );
00123 
00124     config.blackboard = bb;
00125     config.output_ports["out_port"] = "=";
00126 
00127     BB_TestNode node("good_one", config);
00128     node.executeTick();
00129 
00130     ASSERT_EQ( bb->get<int>("out_port"), 22 );
00131 }
00132 
00133 TEST(BlackboardTest, SetOutputFromText)
00134 {
00135     const char* xml_text = R"(
00136 
00137      <root main_tree_to_execute = "MainTree" >
00138          <BehaviorTree ID="MainTree">
00139             <Sequence>
00140                 <BB_TestNode in_port="11" out_port="{my_port}"/>
00141                 <SetBlackboard output_key="my_port" value="-43" />
00142             </Sequence>
00143          </BehaviorTree>
00144      </root>
00145     )";
00146 
00147     BehaviorTreeFactory factory;
00148     factory.registerNodeType<BB_TestNode>("BB_TestNode");
00149 
00150     auto bb = Blackboard::create();
00151 
00152     auto tree = factory.createTreeFromText(xml_text, bb);
00153     tree.root_node->executeTick();
00154 }
00155 
00156 TEST(BlackboardTest, WithFactory)
00157 {
00158     BehaviorTreeFactory factory;
00159 
00160     factory.registerNodeType<BB_TestNode>("BB_TestNode");
00161 
00162     const std::string xml_text = R"(
00163 
00164     <root main_tree_to_execute = "MainTree" >
00165         <BehaviorTree ID="MainTree">
00166             <Sequence>
00167                 <BB_TestNode name = "first" in_port="11"
00168                              out_port="{my_input_port}"/>
00169 
00170                 <BB_TestNode name = "second" in_port="{my_input_port}"
00171                              out_port="{my_input_port}" />
00172 
00173                 <BB_TestNode name = "third" in_port="{my_input_port}"
00174                              out_port="{my_output_port}" />
00175             </Sequence>
00176         </BehaviorTree>
00177     </root>)";
00178 
00179     auto bb = Blackboard::create();
00180 
00181     auto tree = factory.createTreeFromText(xml_text, bb);
00182     NodeStatus status = tree.root_node->executeTick();
00183 
00184     ASSERT_EQ( status, NodeStatus::SUCCESS );
00185     ASSERT_EQ( bb->get<int>("my_input_port"), 44 );
00186     ASSERT_EQ( bb->get<int>("my_output_port"), 88 );
00187 }
00188 
00189 
00190 TEST(BlackboardTest, TypoInPortName)
00191 {
00192     BehaviorTreeFactory factory;
00193     factory.registerNodeType<BB_TestNode>("BB_TestNode");
00194 
00195     const std::string xml_text = R"(
00196 
00197     <root main_tree_to_execute = "MainTree" >
00198         <BehaviorTree ID="MainTree">
00199              <BB_TestNode inpuuuut_port="{value}" />
00200         </BehaviorTree>
00201     </root>)";
00202 
00203     ASSERT_THROW( factory.createTreeFromText(xml_text), RuntimeError );
00204 }
00205 
00206 
00207 TEST(BlackboardTest, CheckPortType)
00208 {
00209     BehaviorTreeFactory factory;
00210     factory.registerNodeType<BB_TypedTestNode>("TypedNode");
00211 
00212     //-----------------------------
00213     std::string good_one = R"(
00214     <root main_tree_to_execute = "MainTree" >
00215         <BehaviorTree ID="MainTree">
00216             <Sequence>
00217                 <TypedNode name = "first"  output_int="{matching}"  output_string="{whatever}" output="{no_problem}" />
00218                 <TypedNode name = "second" input_int="{matching}"   input="{whatever}"         input_string="{no_problem}"  />
00219             </Sequence>
00220         </BehaviorTree>
00221     </root>)";
00222 
00223     auto tree = factory.createTreeFromText(good_one);
00224     ASSERT_NE( tree.root_node, nullptr );
00225     //-----------------------------
00226     std::string bad_one = R"(
00227     <root main_tree_to_execute = "MainTree" >
00228         <BehaviorTree ID="MainTree">
00229             <Sequence>
00230                 <TypedNode name = "first"  output_int="{value}" />
00231                 <TypedNode name = "second" input_string="{value}" />
00232             </Sequence>
00233         </BehaviorTree>
00234     </root>)";
00235 
00236     ASSERT_THROW( factory.createTreeFromText(bad_one), RuntimeError);
00237 }
00238 
00239 class RefCountClass {
00240   public:
00241     RefCountClass(std::shared_ptr<int> value): sptr_(std::move(value))
00242     {
00243         std::cout<< "Constructor: ref_count " << sptr_.use_count() << std::endl;
00244     }
00245 
00246     RefCountClass(const RefCountClass &from) : sptr_(from.sptr_)
00247     {
00248         std::cout<< "ctor copy: ref_count " << sptr_.use_count() << std::endl;
00249     }
00250 
00251     RefCountClass& operator=(const RefCountClass &from)
00252     {
00253         sptr_ = (from.sptr_);
00254         std::cout<< "equal copied: ref_count " << sptr_.use_count() << std::endl;
00255         return *this;
00256     }
00257 
00258     virtual ~RefCountClass() {
00259         std::cout<<("Destructor")<< std::endl;
00260     }
00261 
00262     int refCount() const { return sptr_.use_count(); }
00263 
00264   private:
00265     std::shared_ptr<int> sptr_;
00266 };
00267 
00268 TEST(BlackboardTest, MoveVsCopy)
00269 {
00270     auto blackboard = Blackboard::create();
00271 
00272     RefCountClass test( std::make_shared<int>() );
00273 
00274     ASSERT_EQ( test.refCount(), 1);
00275 
00276     std::cout<<("----- before set -----")<< std::endl;
00277     blackboard->set("testmove", test );
00278     std::cout<<(" ----- after set -----")<< std::endl;
00279 
00280     ASSERT_EQ( test.refCount(), 2);
00281 
00282     RefCountClass other( blackboard->get<RefCountClass>("testmove") );
00283 
00284     ASSERT_EQ( test.refCount(), 3);
00285 }
00286 
00287 
00288 TEST(BlackboardTest, CheckTypeSafety)
00289 {
00290     //TODO check type safety when ports are created.
00291     // remember that std::string is considered a type erased type.
00292 
00293     bool is = std::is_constructible<BT::StringView, char*>::value;
00294     ASSERT_TRUE( is );
00295 
00296     is = std::is_constructible<BT::StringView, std::string>::value;
00297     ASSERT_TRUE( is );
00298 }
00299 


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