13 #include <gtest/gtest.h> 33 auto res = getInput<int>(
"in_port");
36 throw RuntimeError(
"BB_TestNode needs input", res.error());
38 value = res.value()*2;
39 if( !setOutput(
"out_port", value) )
48 return { BT::InputPort<int>(
"in_port"),
49 BT::OutputPort<int>(
"out_port") };
69 BT::InputPort<int>(
"input_int"),
70 BT::InputPort<std::string>(
"input_string"),
73 BT::OutputPort<int>(
"output_int"),
74 BT::OutputPort<std::string>(
"output_string") };
79 TEST(BlackboardTest, GetInputsFromBlackboard)
84 assignDefaultRemapping<BB_TestNode>( config );
87 bb->set(
"in_port", 11 );
94 ASSERT_EQ( bb->get<
int>(
"out_port"), 22 );
97 TEST(BlackboardTest, BasicRemapping)
106 bb->set(
"my_input_port", 11 );
111 ASSERT_EQ( bb->get<
int>(
"my_output_port"), 22 );
114 TEST(BlackboardTest, GetInputsFromText)
130 ASSERT_EQ( bb->get<
int>(
"out_port"), 22 );
133 TEST(BlackboardTest, SetOutputFromText)
137 <root main_tree_to_execute = "MainTree" > 138 <BehaviorTree ID="MainTree"> 140 <BB_TestNode in_port="11" out_port="{my_port}"/> 141 <SetBlackboard output_key="my_port" value="-43" /> 156 TEST(BlackboardTest, WithFactory)
164 <root main_tree_to_execute = "MainTree" > 165 <BehaviorTree ID="MainTree"> 167 <BB_TestNode name = "first" in_port="11" 168 out_port="{my_input_port}"/> 170 <BB_TestNode name = "second" in_port="{my_input_port}" 171 out_port="{my_input_port}" /> 173 <BB_TestNode name = "third" in_port="{my_input_port}" 174 out_port="{my_output_port}" /> 185 ASSERT_EQ( bb->get<
int>(
"my_input_port"), 44 );
186 ASSERT_EQ( bb->get<
int>(
"my_output_port"), 88 );
190 TEST(BlackboardTest, TypoInPortName)
197 <root main_tree_to_execute = "MainTree" > 198 <BehaviorTree ID="MainTree"> 199 <BB_TestNode inpuuuut_port="{value}" /> 207 TEST(BlackboardTest, CheckPortType) 213 std::string good_one = R
"( 214 <root main_tree_to_execute = "MainTree" > 215 <BehaviorTree ID="MainTree"> 217 <TypedNode name = "first" output_int="{matching}" output_string="{whatever}" output="{no_problem}" /> 218 <TypedNode name = "second" input_int="{matching}" input="{whatever}" input_string="{no_problem}" /> 224 ASSERT_NE( tree.root_node,
nullptr );
226 std::string bad_one = R
"( 227 <root main_tree_to_execute = "MainTree" > 228 <BehaviorTree ID="MainTree"> 230 <TypedNode name = "first" output_int="{value}" /> 231 <TypedNode name = "second" input_string="{value}" /> 243 std::cout<<
"Constructor: ref_count " << sptr_.use_count() << std::endl;
248 std::cout<<
"ctor copy: ref_count " << sptr_.use_count() << std::endl;
253 sptr_ = (from.
sptr_);
254 std::cout<<
"equal copied: ref_count " << sptr_.use_count() << std::endl;
259 std::cout<<(
"Destructor")<< std::endl;
268 TEST(BlackboardTest, MoveVsCopy)
276 std::cout<<(
"----- before set -----")<< std::endl;
277 blackboard->set(
"testmove", test );
278 std::cout<<(
" ----- after set -----")<< std::endl;
288 TEST(BlackboardTest, CheckTypeSafety)
293 bool is = std::is_constructible<BT::StringView, char*>::value;
296 is = std::is_constructible<BT::StringView, std::string>::value;
NodeStatus tick()
Method to be implemented by the user.
static Blackboard::Ptr create(Blackboard::Ptr parent={})
void registerNodeType(const std::string &ID)
TEST(BlackboardTest, GetInputsFromBlackboard)
std::shared_ptr< int > sptr_
Blackboard::Ptr blackboard
std::pair< std::string, PortInfo > OutputPort(StringView name, StringView description={})
static PortsList providedPorts()
The SyncActionNode is an ActionNode that explicitly prevents the status RUNNING and doesn't require a...
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
RefCountClass(const RefCountClass &from)
Tree createTreeFromText(const std::string &text, Blackboard::Ptr blackboard=Blackboard::create())
BB_TypedTestNode(const std::string &name, const NodeConfiguration &config)
NodeStatus tick()
Method to be implemented by the user.
PortsRemapping output_ports
std::unordered_map< std::string, PortInfo > PortsList
virtual NodeStatus executeTick() override
throws if the derived class return RUNNING.
static const char * xml_text
static PortsList providedPorts()
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
RefCountClass(std::shared_ptr< int > value)
std::pair< std::string, PortInfo > InputPort(StringView name, StringView description={})
PortsRemapping input_ports
RefCountClass & operator=(const RefCountClass &from)
BB_TestNode(const std::string &name, const NodeConfiguration &config)