@@ -262,6 +262,12 @@ TEST(PortTest, SubtreeStringInput_Issue489)
262262struct Point2D {
263263 int x = 0 ;
264264 int y = 0 ;
265+ bool operator == (const Point2D& other) const {
266+ return x == other.x && y == other.y ;
267+ }
268+ bool operator != (const Point2D& other) const {
269+ return !(*this == other);
270+ }
265271};
266272
267273
@@ -414,29 +420,40 @@ TEST(PortTest, AnyPort)
414420 ASSERT_EQ (status, NodeStatus::SUCCESS);
415421}
416422
417- class NodeWithDefaultVectors : public SyncActionNode
423+ class NodeWithDefaultPoints : public SyncActionNode
418424{
419425public:
420- NodeWithDefaultVectors (const std::string& name, const NodeConfig& config) :
426+ NodeWithDefaultPoints (const std::string& name, const NodeConfig& config) :
421427 SyncActionNode (name, config) {}
422428
423429 NodeStatus tick () override
424430 {
425- Point2D vectA, vectB, vectC;
426- if (getInput (" vectorA" , vectA) && vectA.x == 1 && vectA.y == 2 &&
427- getInput (" vectorB" , vectB) && vectB.x == 3 && vectB.y == 4 &&
428- getInput (" vectorC" , vectC) && vectC.x == 5 && vectC.y == 6 )
429- {
430- return NodeStatus::SUCCESS;
431+ Point2D vectA, vectB, vectC, vectD, input;
432+ if (!getInput (" pointA" , vectA) || vectA != Point2D{1 , 2 }) {
433+ throw std::runtime_error (" failed pointA" );
431434 }
432- return NodeStatus::FAILURE;
435+ if (!getInput (" pointB" , vectB) || vectB != Point2D{3 , 4 }) {
436+ throw std::runtime_error (" failed pointB" );
437+ }
438+ if (!getInput (" pointC" , vectC) || vectC != Point2D{5 , 6 }) {
439+ throw std::runtime_error (" failed pointC" );
440+ }
441+ if (!getInput (" pointD" , vectD) || vectD != Point2D{7 , 8 }) {
442+ throw std::runtime_error (" failed pointD" );
443+ }
444+ if (!getInput (" input" , input) || input != Point2D{9 , 10 }) {
445+ throw std::runtime_error (" failed input" );
446+ }
447+ return NodeStatus::SUCCESS;
433448 }
434449
435450 static PortsList providedPorts ()
436451 {
437- return {BT::InputPort<Point2D>(" vectorA" , Point2D{1 , 2 }, " default value is [1,2]" ),
438- BT::InputPort<Point2D>(" vectorB" , " {vect}" , " default value inside key {vect}" ),
439- BT::InputPort<Point2D>(" vectorC" , " 5,6" , " default value is [5,6]" )};
452+ return {BT::InputPort<Point2D>(" input" , " no default value" ),
453+ BT::InputPort<Point2D>(" pointA" , Point2D{1 , 2 }, " default value is [1,2]" ),
454+ BT::InputPort<Point2D>(" pointB" , " {point}" , " default value inside blackboard {point}" ),
455+ BT::InputPort<Point2D>(" pointC" , " 5,6" , " default value is [5,6]" ),
456+ BT::InputPort<Point2D>(" pointD" , " {=}" , " default value inside blackboard {pointD}" )};
440457 }
441458};
442459
@@ -446,17 +463,73 @@ TEST(PortTest, DefaultInputVectors)
446463 std::string xml_txt = R"(
447464 <root BTCPP_format="4" >
448465 <BehaviorTree>
449- <NodeWithVectors />
466+ <NodeWithDefaultPoints input="9,10" />
450467 </BehaviorTree>
451468 </root>)" ;
452469
453470 BehaviorTreeFactory factory;
454- factory.registerNodeType <NodeWithDefaultVectors >(" NodeWithVectors " );
471+ factory.registerNodeType <NodeWithDefaultPoints >(" NodeWithDefaultPoints " );
455472 auto tree = factory.createTreeFromText (xml_txt);
456473
457- tree.subtrees .front ()->blackboard ->set <Point2D>(" vect" , Point2D{3 , 4 });
474+ tree.subtrees .front ()->blackboard ->set <Point2D>(" point" , Point2D{3 , 4 });
475+ tree.subtrees .front ()->blackboard ->set <Point2D>(" pointD" , Point2D{7 , 8 });
458476
459- auto status = tree.tickOnce ();
477+ BT::NodeStatus status;
478+ ASSERT_NO_THROW (status = tree.tickOnce ());
479+ ASSERT_EQ (status, NodeStatus::SUCCESS);
480+ }
481+
482+ class NodeWithDefaultStrings : public SyncActionNode
483+ {
484+ public:
485+ NodeWithDefaultStrings (const std::string& name, const NodeConfig& config) :
486+ SyncActionNode (name, config) {}
487+
488+ NodeStatus tick () override
489+ {
490+ std::string input, msgA, msgB, msgC;
491+ if (!getInput (" input" , input) || input != " from XML" ) {
492+ throw std::runtime_error (" failed input" );
493+ }
494+ if (!getInput (" msgA" , msgA) || msgA != " hello" ) {
495+ throw std::runtime_error (" failed msgA" );
496+ }
497+ if (!getInput (" msgB" , msgB) || msgB != " ciao" ) {
498+ throw std::runtime_error (" failed msgB" );
499+ }
500+ if (!getInput (" msgC" , msgC) || msgC != " hola" ) {
501+ throw std::runtime_error (" failed msgC" );
502+ }
503+ return NodeStatus::SUCCESS;
504+ }
505+
506+ static PortsList providedPorts ()
507+ {
508+ return {BT::InputPort<std::string>(" input" , " no default" ),
509+ BT::InputPort<std::string>(" msgA" , " hello" , " default value is 'hello'" ),
510+ BT::InputPort<std::string>(" msgB" , " {msg}" , " default value inside blackboard {msg}" ),
511+ BT::InputPort<std::string>(" msgC" , " {=}" , " default value inside blackboard {msgC}" )};
512+ }
513+ };
514+
515+ TEST (PortTest, DefaultInputStrings)
516+ {
517+ std::string xml_txt = R"(
518+ <root BTCPP_format="4" >
519+ <BehaviorTree>
520+ <NodeWithDefaultStrings input="from XML"/>
521+ </BehaviorTree>
522+ </root>)" ;
523+
524+ BehaviorTreeFactory factory;
525+ factory.registerNodeType <NodeWithDefaultStrings>(" NodeWithDefaultStrings" );
526+ auto tree = factory.createTreeFromText (xml_txt);
527+
528+ tree.subtrees .front ()->blackboard ->set <std::string>(" msg" , " ciao" );
529+ tree.subtrees .front ()->blackboard ->set <std::string>(" msgC" , " hola" );
530+
531+ BT::NodeStatus status;
532+ ASSERT_NO_THROW (status = tree.tickOnce ());
460533 ASSERT_EQ (status, NodeStatus::SUCCESS);
461534}
462535
0 commit comments