From 98e3502b994afa2d1ada68066047b9f862764f94 Mon Sep 17 00:00:00 2001 From: stevemacenski Date: Thu, 16 Nov 2023 07:55:47 -0800 Subject: [PATCH] updating tests --- nav2_smac_planner/test/test_a_star.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/nav2_smac_planner/test/test_a_star.cpp b/nav2_smac_planner/test/test_a_star.cpp index b6107b141db..873446a7a17 100644 --- a/nav2_smac_planner/test/test_a_star.cpp +++ b/nav2_smac_planner/test/test_a_star.cpp @@ -168,8 +168,8 @@ TEST(AStarTest, test_a_star_se2) EXPECT_TRUE(a_star.createPath(path, num_it, tolerance, expansions.get())); // check path is the right size and collision free - EXPECT_EQ(num_it, 3186); - EXPECT_EQ(path.size(), 64u); + EXPECT_EQ(num_it, 3146); + EXPECT_EQ(path.size(), 63u); for (unsigned int i = 0; i != path.size(); i++) { EXPECT_EQ(costmapA->getCost(path[i].x, path[i].y), 0); } @@ -233,8 +233,8 @@ TEST(AStarTest, test_a_star_lattice) EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); // check path is the right size and collision free - EXPECT_EQ(num_it, 26); - EXPECT_GT(path.size(), 47u); + EXPECT_EQ(num_it, 22); + EXPECT_GT(path.size(), 46u); for (unsigned int i = 0; i != path.size(); i++) { EXPECT_EQ(costmapA->getCost(path[i].x, path[i].y), 0); }