diff --git a/nav2_behavior_tree/test/test_bt_utils.cpp b/nav2_behavior_tree/test/test_bt_utils.cpp index 1c008d6478..d495587955 100644 --- a/nav2_behavior_tree/test/test_bt_utils.cpp +++ b/nav2_behavior_tree/test/test_bt_utils.cpp @@ -59,13 +59,7 @@ TEST(PointPortTest, test_wrong_syntax) BT::BehaviorTreeFactory factory; factory.registerNodeType>("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"( @@ -75,11 +69,7 @@ TEST(PointPortTest, test_wrong_syntax) )"; - 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) @@ -115,14 +105,8 @@ TEST(QuaternionPortTest, test_wrong_syntax) BT::BehaviorTreeFactory factory; factory.registerNodeType>("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"( @@ -132,12 +116,7 @@ TEST(QuaternionPortTest, test_wrong_syntax) )"; - 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) @@ -174,19 +153,7 @@ TEST(PoseStampedPortTest, test_wrong_syntax) BT::BehaviorTreeFactory factory; factory.registerNodeType>("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"( @@ -196,17 +163,7 @@ TEST(PoseStampedPortTest, test_wrong_syntax) )"; - 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)