35 #include <global_planner_tests/many_map_test_suite.h> 38 #include <gtest/gtest.h> 41 using global_planner_tests::many_map_test_suite;
45 TEST(GlobalPlanner, DijkstraVonNeumann)
49 std::string ns =
"DijkstraVonNeumann";
52 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::Dijkstra");
53 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
54 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
58 TEST(GlobalPlanner, DijkstraGrid)
62 std::string ns =
"DijkstraGrid";
65 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::Dijkstra");
66 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
67 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
71 TEST(GlobalPlanner, DijkstraGradientStep)
75 std::string ns =
"DijkstraGradientStep";
78 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::Dijkstra");
79 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
80 nh.
setParam(
"planner/grid_step_near_high",
true);
81 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
85 TEST(GlobalPlanner, DijkstraGradient)
89 std::string ns =
"DijkstraGradient";
92 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::Dijkstra");
93 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
94 nh.
setParam(
"planner/grid_step_near_high",
false);
95 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
99 TEST(GlobalPlanner, AStarVonNeumannManK)
103 std::string ns =
"AStarVonNeumannManK";
106 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
107 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
108 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
109 nh.
setParam(
"planner/use_kernel",
true);
110 nh.
setParam(
"planner/manhattan_heuristic",
true);
111 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
115 TEST(GlobalPlanner, AStarVonNeumannK)
119 std::string ns =
"AStarVonNeumannK";
122 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
123 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
124 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
125 nh.
setParam(
"planner/use_kernel",
true);
126 nh.
setParam(
"planner/manhattan_heuristic",
false);
127 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
131 TEST(GlobalPlanner, AStarVonNeumannMan)
135 std::string ns =
"AStarVonNeumannMan";
138 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
139 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
140 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
141 nh.
setParam(
"planner/use_kernel",
false);
142 nh.
setParam(
"planner/manhattan_heuristic",
true);
143 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
147 TEST(GlobalPlanner, AStarVonNeumann)
151 std::string ns =
"AStarVonNeumann";
154 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
155 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
156 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
157 nh.
setParam(
"planner/use_kernel",
false);
158 nh.
setParam(
"planner/manhattan_heuristic",
false);
159 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
163 TEST(GlobalPlanner, AStarVonNeumannManThreshK)
167 std::string ns =
"AStarVonNeumannManThreshK";
170 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
171 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
172 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
173 nh.
setParam(
"planner/use_kernel",
true);
174 nh.
setParam(
"planner/manhattan_heuristic",
true);
175 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
179 TEST(GlobalPlanner, AStarVonNeumannThreshK)
183 std::string ns =
"AStarVonNeumannThreshK";
186 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
187 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
188 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
189 nh.
setParam(
"planner/use_kernel",
true);
190 nh.
setParam(
"planner/manhattan_heuristic",
false);
191 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
195 TEST(GlobalPlanner, AStarVonNeumannManThresh)
199 std::string ns =
"AStarVonNeumannManThresh";
202 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
203 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
204 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
205 nh.
setParam(
"planner/use_kernel",
false);
206 nh.
setParam(
"planner/manhattan_heuristic",
true);
207 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
211 TEST(GlobalPlanner, AStarVonNeumannThresh)
215 std::string ns =
"AStarVonNeumannThresh";
218 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
219 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
220 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
221 nh.
setParam(
"planner/use_kernel",
false);
222 nh.
setParam(
"planner/manhattan_heuristic",
false);
223 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
227 TEST(GlobalPlanner, AStarGridManK)
231 std::string ns =
"AStarGridManK";
234 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
235 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
236 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
237 nh.
setParam(
"planner/use_kernel",
true);
238 nh.
setParam(
"planner/manhattan_heuristic",
true);
239 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
243 TEST(GlobalPlanner, AStarGridK)
247 std::string ns =
"AStarGridK";
250 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
251 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
252 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
253 nh.
setParam(
"planner/use_kernel",
true);
254 nh.
setParam(
"planner/manhattan_heuristic",
false);
255 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
259 TEST(GlobalPlanner, AStarGridMan)
263 std::string ns =
"AStarGridMan";
266 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
267 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
268 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
269 nh.
setParam(
"planner/use_kernel",
false);
270 nh.
setParam(
"planner/manhattan_heuristic",
true);
271 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
279 std::string ns =
"AStarGrid";
282 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
283 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
284 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
285 nh.
setParam(
"planner/use_kernel",
false);
286 nh.
setParam(
"planner/manhattan_heuristic",
false);
287 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
291 TEST(GlobalPlanner, AStarGridManThreshK)
295 std::string ns =
"AStarGridManThreshK";
298 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
299 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
300 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
301 nh.
setParam(
"planner/use_kernel",
true);
302 nh.
setParam(
"planner/manhattan_heuristic",
true);
303 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
307 TEST(GlobalPlanner, AStarGridThreshK)
311 std::string ns =
"AStarGridThreshK";
314 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
315 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
316 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
317 nh.
setParam(
"planner/use_kernel",
true);
318 nh.
setParam(
"planner/manhattan_heuristic",
false);
319 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
323 TEST(GlobalPlanner, AStarGridManThresh)
327 std::string ns =
"AStarGridManThresh";
330 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
331 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
332 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
333 nh.
setParam(
"planner/use_kernel",
false);
334 nh.
setParam(
"planner/manhattan_heuristic",
true);
335 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
339 TEST(GlobalPlanner, AStarGridThresh)
343 std::string ns =
"AStarGridThresh";
346 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
347 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
348 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
349 nh.
setParam(
"planner/use_kernel",
false);
350 nh.
setParam(
"planner/manhattan_heuristic",
false);
351 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
355 TEST(GlobalPlanner, AStarGradientStepManK)
359 std::string ns =
"AStarGradientStepManK";
362 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
363 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
364 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
365 nh.
setParam(
"planner/use_kernel",
true);
366 nh.
setParam(
"planner/manhattan_heuristic",
true);
367 nh.
setParam(
"planner/grid_step_near_high",
true);
368 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
372 TEST(GlobalPlanner, AStarGradientManK)
376 std::string ns =
"AStarGradientManK";
379 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
380 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
381 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
382 nh.
setParam(
"planner/use_kernel",
true);
383 nh.
setParam(
"planner/manhattan_heuristic",
true);
384 nh.
setParam(
"planner/grid_step_near_high",
false);
385 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
389 TEST(GlobalPlanner, AStarGradientStepK)
393 std::string ns =
"AStarGradientStepK";
396 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
397 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
398 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
399 nh.
setParam(
"planner/use_kernel",
true);
400 nh.
setParam(
"planner/manhattan_heuristic",
false);
401 nh.
setParam(
"planner/grid_step_near_high",
true);
402 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
406 TEST(GlobalPlanner, AStarGradientK)
410 std::string ns =
"AStarGradientK";
413 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
414 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
415 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
416 nh.
setParam(
"planner/use_kernel",
true);
417 nh.
setParam(
"planner/manhattan_heuristic",
false);
418 nh.
setParam(
"planner/grid_step_near_high",
false);
419 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
423 TEST(GlobalPlanner, AStarGradientStepMan)
427 std::string ns =
"AStarGradientStepMan";
430 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
431 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
432 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
433 nh.
setParam(
"planner/use_kernel",
false);
434 nh.
setParam(
"planner/manhattan_heuristic",
true);
435 nh.
setParam(
"planner/grid_step_near_high",
true);
436 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
440 TEST(GlobalPlanner, AStarGradientMan)
444 std::string ns =
"AStarGradientMan";
447 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
448 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
449 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
450 nh.
setParam(
"planner/use_kernel",
false);
451 nh.
setParam(
"planner/manhattan_heuristic",
true);
452 nh.
setParam(
"planner/grid_step_near_high",
false);
453 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
457 TEST(GlobalPlanner, AStarGradientStep)
461 std::string ns =
"AStarGradientStep";
464 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
465 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
466 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
467 nh.
setParam(
"planner/use_kernel",
false);
468 nh.
setParam(
"planner/manhattan_heuristic",
false);
469 nh.
setParam(
"planner/grid_step_near_high",
true);
470 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
474 TEST(GlobalPlanner, AStarGradient)
478 std::string ns =
"AStarGradient";
481 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
482 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
483 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
484 nh.
setParam(
"planner/use_kernel",
false);
485 nh.
setParam(
"planner/manhattan_heuristic",
false);
486 nh.
setParam(
"planner/grid_step_near_high",
false);
487 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
491 TEST(GlobalPlanner, AStarGradientStepManThreshK)
495 std::string ns =
"AStarGradientStepManThreshK";
498 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
499 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
500 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
501 nh.
setParam(
"planner/use_kernel",
true);
502 nh.
setParam(
"planner/manhattan_heuristic",
true);
503 nh.
setParam(
"planner/grid_step_near_high",
true);
504 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
508 TEST(GlobalPlanner, AStarGradientManThreshK)
512 std::string ns =
"AStarGradientManThreshK";
515 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
516 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
517 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
518 nh.
setParam(
"planner/use_kernel",
true);
519 nh.
setParam(
"planner/manhattan_heuristic",
true);
520 nh.
setParam(
"planner/grid_step_near_high",
false);
521 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
525 TEST(GlobalPlanner, AStarGradientStepThreshK)
529 std::string ns =
"AStarGradientStepThreshK";
532 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
533 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
534 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
535 nh.
setParam(
"planner/use_kernel",
true);
536 nh.
setParam(
"planner/manhattan_heuristic",
false);
537 nh.
setParam(
"planner/grid_step_near_high",
true);
538 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
542 TEST(GlobalPlanner, AStarGradientThreshK)
546 std::string ns =
"AStarGradientThreshK";
549 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
550 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
551 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
552 nh.
setParam(
"planner/use_kernel",
true);
553 nh.
setParam(
"planner/manhattan_heuristic",
false);
554 nh.
setParam(
"planner/grid_step_near_high",
false);
555 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
559 TEST(GlobalPlanner, AStarGradientStepManThresh)
563 std::string ns =
"AStarGradientStepManThresh";
566 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
567 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
568 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
569 nh.
setParam(
"planner/use_kernel",
false);
570 nh.
setParam(
"planner/manhattan_heuristic",
true);
571 nh.
setParam(
"planner/grid_step_near_high",
true);
572 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
576 TEST(GlobalPlanner, AStarGradientManThresh)
580 std::string ns =
"AStarGradientManThresh";
583 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
584 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
585 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
586 nh.
setParam(
"planner/use_kernel",
false);
587 nh.
setParam(
"planner/manhattan_heuristic",
true);
588 nh.
setParam(
"planner/grid_step_near_high",
false);
589 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
593 TEST(GlobalPlanner, AStarGradientStepThresh)
597 std::string ns =
"AStarGradientStepThresh";
600 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
601 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
602 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
603 nh.
setParam(
"planner/use_kernel",
false);
604 nh.
setParam(
"planner/manhattan_heuristic",
false);
605 nh.
setParam(
"planner/grid_step_near_high",
true);
606 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
610 TEST(GlobalPlanner, AStarGradientThresh)
614 std::string ns =
"AStarGradientThresh";
617 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
618 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
619 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
620 nh.
setParam(
"planner/use_kernel",
false);
621 nh.
setParam(
"planner/manhattan_heuristic",
false);
622 nh.
setParam(
"planner/grid_step_near_high",
false);
623 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
627 int main(
int argc,
char **argv)
630 testing::InitGoogleTest(&argc, argv);
631 return RUN_ALL_TESTS();
TEST(GlobalPlanner, DijkstraVonNeumann)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
std::shared_ptr< tf::TransformListener > TFListenerPtr
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const