Skip to content

Commit

Permalink
Fix CI with BT test from btv4.X API update (ros-navigation#4452)
Browse files Browse the repository at this point in the history
* fix CI with BT test from btv4.X API update

* Update test_bt_utils.cpp

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>
  • Loading branch information
SteveMacenski authored and ajtudela committed Jun 21, 2024
1 parent 351fe0a commit 3d48c4d
Showing 1 changed file with 6 additions and 49 deletions.
55 changes: 6 additions & 49 deletions nav2_behavior_tree/test/test_bt_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,7 @@ TEST(PointPortTest, test_wrong_syntax)

BT::BehaviorTreeFactory factory;
factory.registerNodeType<TestNode<geometry_msgs::msg::Point>>("PointPort");
auto tree = factory.createTreeFromText(xml_txt);

geometry_msgs::msg::Point value;
tree.rootNode()->getInput("test", value);
EXPECT_EQ(value.x, 0.0);
EXPECT_EQ(value.y, 0.0);
EXPECT_EQ(value.z, 0.0);
EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);

xml_txt =
R"(
Expand All @@ -75,11 +69,7 @@ TEST(PointPortTest, test_wrong_syntax)
</BehaviorTree>
</root>)";

tree = factory.createTreeFromText(xml_txt);
tree.rootNode()->getInput("test", value);
EXPECT_EQ(value.x, 0.0);
EXPECT_EQ(value.y, 0.0);
EXPECT_EQ(value.z, 0.0);
EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);
}

TEST(PointPortTest, test_correct_syntax)
Expand Down Expand Up @@ -115,14 +105,8 @@ TEST(QuaternionPortTest, test_wrong_syntax)

BT::BehaviorTreeFactory factory;
factory.registerNodeType<TestNode<geometry_msgs::msg::Quaternion>>("QuaternionPort");
auto tree = factory.createTreeFromText(xml_txt);

geometry_msgs::msg::Quaternion value;
tree.rootNode()->getInput("test", value);
EXPECT_EQ(value.x, 0.0);
EXPECT_EQ(value.y, 0.0);
EXPECT_EQ(value.z, 0.0);
EXPECT_EQ(value.w, 1.0);
EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);

xml_txt =
R"(
Expand All @@ -132,12 +116,7 @@ TEST(QuaternionPortTest, test_wrong_syntax)
</BehaviorTree>
</root>)";

tree = factory.createTreeFromText(xml_txt);
tree.rootNode()->getInput("test", value);
EXPECT_EQ(value.x, 0.0);
EXPECT_EQ(value.y, 0.0);
EXPECT_EQ(value.z, 0.0);
EXPECT_EQ(value.w, 1.0);
EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);
}

TEST(QuaternionPortTest, test_correct_syntax)
Expand Down Expand Up @@ -174,19 +153,7 @@ TEST(PoseStampedPortTest, test_wrong_syntax)

BT::BehaviorTreeFactory factory;
factory.registerNodeType<TestNode<geometry_msgs::msg::PoseStamped>>("PoseStampedPort");
auto tree = factory.createTreeFromText(xml_txt);

geometry_msgs::msg::PoseStamped value;
tree.rootNode()->getInput("test", value);
EXPECT_EQ(rclcpp::Time(value.header.stamp).nanoseconds(), 0);
EXPECT_EQ(value.header.frame_id, "");
EXPECT_EQ(value.pose.position.x, 0.0);
EXPECT_EQ(value.pose.position.y, 0.0);
EXPECT_EQ(value.pose.position.z, 0.0);
EXPECT_EQ(value.pose.orientation.x, 0.0);
EXPECT_EQ(value.pose.orientation.y, 0.0);
EXPECT_EQ(value.pose.orientation.z, 0.0);
EXPECT_EQ(value.pose.orientation.w, 1.0);
EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);

xml_txt =
R"(
Expand All @@ -196,17 +163,7 @@ TEST(PoseStampedPortTest, test_wrong_syntax)
</BehaviorTree>
</root>)";

tree = factory.createTreeFromText(xml_txt);
tree.rootNode()->getInput("test", value);
EXPECT_EQ(rclcpp::Time(value.header.stamp).nanoseconds(), 0);
EXPECT_EQ(value.header.frame_id, "");
EXPECT_EQ(value.pose.position.x, 0.0);
EXPECT_EQ(value.pose.position.y, 0.0);
EXPECT_EQ(value.pose.position.z, 0.0);
EXPECT_EQ(value.pose.orientation.x, 0.0);
EXPECT_EQ(value.pose.orientation.y, 0.0);
EXPECT_EQ(value.pose.orientation.z, 0.0);
EXPECT_EQ(value.pose.orientation.w, 1.0);
EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception);
}

TEST(PoseStampedPortTest, test_correct_syntax)
Expand Down

0 comments on commit 3d48c4d

Please sign in to comment.