Skip to content

Commit 97c5701

Browse files
author
Kemal Bektas
committed
Update nav2_system_tests to use cancel checker
Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com>
1 parent f71266d commit 97c5701

File tree

3 files changed

+31
-14
lines changed

3 files changed

+31
-14
lines changed

nav2_system_tests/src/error_codes/planner/planner_error_plugin.hpp

Lines changed: 18 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,8 @@ class UnknownErrorPlanner : public nav2_core::GlobalPlanner
5151

5252
nav_msgs::msg::Path createPlan(
5353
const geometry_msgs::msg::PoseStamped &,
54-
const geometry_msgs::msg::PoseStamped &) override
54+
const geometry_msgs::msg::PoseStamped &,
55+
std::function<bool()>) override
5556
{
5657
throw nav2_core::PlannerException("Unknown Error");
5758
}
@@ -61,7 +62,8 @@ class StartOccupiedErrorPlanner : public UnknownErrorPlanner
6162
{
6263
nav_msgs::msg::Path createPlan(
6364
const geometry_msgs::msg::PoseStamped &,
64-
const geometry_msgs::msg::PoseStamped &) override
65+
const geometry_msgs::msg::PoseStamped &,
66+
std::function<bool()>) override
6567
{
6668
throw nav2_core::StartOccupied("Start Occupied");
6769
}
@@ -71,7 +73,8 @@ class GoalOccupiedErrorPlanner : public UnknownErrorPlanner
7173
{
7274
nav_msgs::msg::Path createPlan(
7375
const geometry_msgs::msg::PoseStamped &,
74-
const geometry_msgs::msg::PoseStamped &) override
76+
const geometry_msgs::msg::PoseStamped &,
77+
std::function<bool()>) override
7578
{
7679
throw nav2_core::GoalOccupied("Goal occupied");
7780
}
@@ -81,7 +84,8 @@ class StartOutsideMapErrorPlanner : public UnknownErrorPlanner
8184
{
8285
nav_msgs::msg::Path createPlan(
8386
const geometry_msgs::msg::PoseStamped &,
84-
const geometry_msgs::msg::PoseStamped &) override
87+
const geometry_msgs::msg::PoseStamped &,
88+
std::function<bool()>) override
8589
{
8690
throw nav2_core::StartOutsideMapBounds("Start OutsideMapBounds");
8791
}
@@ -91,7 +95,8 @@ class GoalOutsideMapErrorPlanner : public UnknownErrorPlanner
9195
{
9296
nav_msgs::msg::Path createPlan(
9397
const geometry_msgs::msg::PoseStamped &,
94-
const geometry_msgs::msg::PoseStamped &) override
98+
const geometry_msgs::msg::PoseStamped &,
99+
std::function<bool()>) override
95100
{
96101
throw nav2_core::GoalOutsideMapBounds("Goal outside map bounds");
97102
}
@@ -101,7 +106,8 @@ class NoValidPathErrorPlanner : public UnknownErrorPlanner
101106
{
102107
nav_msgs::msg::Path createPlan(
103108
const geometry_msgs::msg::PoseStamped &,
104-
const geometry_msgs::msg::PoseStamped &) override
109+
const geometry_msgs::msg::PoseStamped &,
110+
std::function<bool()>) override
105111
{
106112
return nav_msgs::msg::Path();
107113
}
@@ -112,7 +118,8 @@ class TimedOutErrorPlanner : public UnknownErrorPlanner
112118
{
113119
nav_msgs::msg::Path createPlan(
114120
const geometry_msgs::msg::PoseStamped &,
115-
const geometry_msgs::msg::PoseStamped &) override
121+
const geometry_msgs::msg::PoseStamped &,
122+
std::function<bool()>) override
116123
{
117124
throw nav2_core::PlannerTimedOut("Planner Timed Out");
118125
}
@@ -122,7 +129,8 @@ class TFErrorPlanner : public UnknownErrorPlanner
122129
{
123130
nav_msgs::msg::Path createPlan(
124131
const geometry_msgs::msg::PoseStamped &,
125-
const geometry_msgs::msg::PoseStamped &) override
132+
const geometry_msgs::msg::PoseStamped &,
133+
std::function<bool()>) override
126134
{
127135
throw nav2_core::PlannerTFError("TF Error");
128136
}
@@ -132,7 +140,8 @@ class NoViapointsGivenErrorPlanner : public UnknownErrorPlanner
132140
{
133141
nav_msgs::msg::Path createPlan(
134142
const geometry_msgs::msg::PoseStamped &,
135-
const geometry_msgs::msg::PoseStamped &) override
143+
const geometry_msgs::msg::PoseStamped &,
144+
std::function<bool()>) override
136145
{
137146
throw nav2_core::NoViapointsGiven("No Via points given");
138147
}

nav2_system_tests/src/planning/planner_tester.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,8 @@ class NavFnPlannerTester : public nav2_planner::PlannerServer
8787
return false;
8888
}
8989
try {
90-
path = planners_["GridBased"]->createPlan(start, goal);
90+
auto dummy_cancel_checker = []() {return false;};
91+
path = planners_["GridBased"]->createPlan(start, goal, dummy_cancel_checker);
9192
// The situation when createPlan() did not throw any exception
9293
// does not guarantee that plan was created correctly.
9394
// So it should be checked additionally that path is correct.

nav2_system_tests/src/planning/test_planner_plugins.cpp

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -57,9 +57,11 @@ void testSmallPathValidityAndOrientation(std::string plugin, double length)
5757
goal.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(-M_PI);
5858
goal.header.frame_id = "map";
5959

60+
auto dummy_cancel_checker = []() {return false;};
61+
6062
// Test without use_final_approach_orientation
6163
// expecting end path pose orientation to be equal to goal orientation
62-
auto path = obj->getPlan(start, goal, "GridBased");
64+
auto path = obj->getPlan(start, goal, "GridBased", dummy_cancel_checker);
6365
EXPECT_GT((int)path.poses.size(), 0);
6466
EXPECT_NEAR(tf2::getYaw(path.poses.back().pose.orientation), -M_PI, 0.01);
6567
// obj->onCleanup(state);
@@ -93,7 +95,9 @@ void testSmallPathValidityAndNoOrientation(std::string plugin, double length)
9395
goal.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(-M_PI);
9496
goal.header.frame_id = "map";
9597

96-
auto path = obj->getPlan(start, goal, "GridBased");
98+
auto dummy_cancel_checker = []() {return false;};
99+
100+
auto path = obj->getPlan(start, goal, "GridBased", dummy_cancel_checker);
97101
EXPECT_GT((int)path.poses.size(), 0);
98102

99103
int path_size = path.poses.size();
@@ -127,11 +131,14 @@ TEST(testPluginMap, Failures)
127131
geometry_msgs::msg::PoseStamped goal;
128132
std::string plugin_fake = "fake";
129133
std::string plugin_none = "";
130-
auto path = obj->getPlan(start, goal, plugin_none);
134+
135+
auto dummy_cancel_checker = []() {return false;};
136+
137+
auto path = obj->getPlan(start, goal, plugin_none, dummy_cancel_checker);
131138
EXPECT_EQ(path.header.frame_id, std::string("map"));
132139

133140
try {
134-
path = obj->getPlan(start, goal, plugin_fake);
141+
path = obj->getPlan(start, goal, plugin_fake, dummy_cancel_checker);
135142
FAIL() << "Failed to throw invalid planner id exception";
136143
} catch (const nav2_core::InvalidPlanner & ex) {
137144
EXPECT_EQ(ex.what(), std::string("Planner id fake is invalid"));

0 commit comments

Comments
 (0)