35 #include <global_planner_tests/many_map_test_suite.h> 38 #include <gtest/gtest.h> 42 using global_planner_tests::many_map_test_suite;
46 TEST(GlobalPlanner, DijkstraVonNeumann)
50 std::string ns =
"DijkstraVonNeumann";
53 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::Dijkstra");
54 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
55 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
59 TEST(GlobalPlanner, DijkstraGrid)
63 std::string ns =
"DijkstraGrid";
66 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::Dijkstra");
67 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
68 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
72 TEST(GlobalPlanner, DijkstraGradientStep)
76 std::string ns =
"DijkstraGradientStep";
79 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::Dijkstra");
80 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
81 nh.
setParam(
"planner/grid_step_near_high",
true);
82 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
86 TEST(GlobalPlanner, DijkstraGradient)
90 std::string ns =
"DijkstraGradient";
93 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::Dijkstra");
94 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
95 nh.
setParam(
"planner/grid_step_near_high",
false);
96 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
100 TEST(GlobalPlanner, AStarVonNeumannManK)
104 std::string ns =
"AStarVonNeumannManK";
107 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
108 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
109 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
110 nh.
setParam(
"planner/use_kernel",
true);
111 nh.
setParam(
"planner/manhattan_heuristic",
true);
112 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
116 TEST(GlobalPlanner, AStarVonNeumannK)
120 std::string ns =
"AStarVonNeumannK";
123 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
124 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
125 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
126 nh.
setParam(
"planner/use_kernel",
true);
127 nh.
setParam(
"planner/manhattan_heuristic",
false);
128 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
132 TEST(GlobalPlanner, AStarVonNeumannMan)
136 std::string ns =
"AStarVonNeumannMan";
139 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
140 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
141 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
142 nh.
setParam(
"planner/use_kernel",
false);
143 nh.
setParam(
"planner/manhattan_heuristic",
true);
144 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
148 TEST(GlobalPlanner, AStarVonNeumann)
152 std::string ns =
"AStarVonNeumann";
155 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
156 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
157 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
158 nh.
setParam(
"planner/use_kernel",
false);
159 nh.
setParam(
"planner/manhattan_heuristic",
false);
160 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
164 TEST(GlobalPlanner, AStarVonNeumannManThreshK)
168 std::string ns =
"AStarVonNeumannManThreshK";
171 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
172 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
173 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
174 nh.
setParam(
"planner/use_kernel",
true);
175 nh.
setParam(
"planner/manhattan_heuristic",
true);
176 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
180 TEST(GlobalPlanner, AStarVonNeumannThreshK)
184 std::string ns =
"AStarVonNeumannThreshK";
187 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
188 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
189 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
190 nh.
setParam(
"planner/use_kernel",
true);
191 nh.
setParam(
"planner/manhattan_heuristic",
false);
192 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
196 TEST(GlobalPlanner, AStarVonNeumannManThresh)
200 std::string ns =
"AStarVonNeumannManThresh";
203 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
204 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
205 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
206 nh.
setParam(
"planner/use_kernel",
false);
207 nh.
setParam(
"planner/manhattan_heuristic",
true);
208 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
212 TEST(GlobalPlanner, AStarVonNeumannThresh)
216 std::string ns =
"AStarVonNeumannThresh";
219 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
220 nh.
setParam(
"planner/traceback",
"dlux_plugins::VonNeumannPath");
221 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
222 nh.
setParam(
"planner/use_kernel",
false);
223 nh.
setParam(
"planner/manhattan_heuristic",
false);
224 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
228 TEST(GlobalPlanner, AStarGridManK)
232 std::string ns =
"AStarGridManK";
235 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
236 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
237 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
238 nh.
setParam(
"planner/use_kernel",
true);
239 nh.
setParam(
"planner/manhattan_heuristic",
true);
240 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
244 TEST(GlobalPlanner, AStarGridK)
248 std::string ns =
"AStarGridK";
251 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
252 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
253 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
254 nh.
setParam(
"planner/use_kernel",
true);
255 nh.
setParam(
"planner/manhattan_heuristic",
false);
256 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
260 TEST(GlobalPlanner, AStarGridMan)
264 std::string ns =
"AStarGridMan";
267 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
268 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
269 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
270 nh.
setParam(
"planner/use_kernel",
false);
271 nh.
setParam(
"planner/manhattan_heuristic",
true);
272 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
280 std::string ns =
"AStarGrid";
283 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
284 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
285 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
286 nh.
setParam(
"planner/use_kernel",
false);
287 nh.
setParam(
"planner/manhattan_heuristic",
false);
288 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
292 TEST(GlobalPlanner, AStarGridManThreshK)
296 std::string ns =
"AStarGridManThreshK";
299 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
300 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
301 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
302 nh.
setParam(
"planner/use_kernel",
true);
303 nh.
setParam(
"planner/manhattan_heuristic",
true);
304 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
308 TEST(GlobalPlanner, AStarGridThreshK)
312 std::string ns =
"AStarGridThreshK";
315 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
316 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
317 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
318 nh.
setParam(
"planner/use_kernel",
true);
319 nh.
setParam(
"planner/manhattan_heuristic",
false);
320 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
324 TEST(GlobalPlanner, AStarGridManThresh)
328 std::string ns =
"AStarGridManThresh";
331 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
332 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
333 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
334 nh.
setParam(
"planner/use_kernel",
false);
335 nh.
setParam(
"planner/manhattan_heuristic",
true);
336 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
340 TEST(GlobalPlanner, AStarGridThresh)
344 std::string ns =
"AStarGridThresh";
347 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
348 nh.
setParam(
"planner/traceback",
"dlux_plugins::GridPath");
349 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
350 nh.
setParam(
"planner/use_kernel",
false);
351 nh.
setParam(
"planner/manhattan_heuristic",
false);
352 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
356 TEST(GlobalPlanner, AStarGradientStepManK)
360 std::string ns =
"AStarGradientStepManK";
363 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
364 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
365 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
366 nh.
setParam(
"planner/use_kernel",
true);
367 nh.
setParam(
"planner/manhattan_heuristic",
true);
368 nh.
setParam(
"planner/grid_step_near_high",
true);
369 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
373 TEST(GlobalPlanner, AStarGradientManK)
377 std::string ns =
"AStarGradientManK";
380 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
381 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
382 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
383 nh.
setParam(
"planner/use_kernel",
true);
384 nh.
setParam(
"planner/manhattan_heuristic",
true);
385 nh.
setParam(
"planner/grid_step_near_high",
false);
386 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
390 TEST(GlobalPlanner, AStarGradientStepK)
394 std::string ns =
"AStarGradientStepK";
397 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
398 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
399 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
400 nh.
setParam(
"planner/use_kernel",
true);
401 nh.
setParam(
"planner/manhattan_heuristic",
false);
402 nh.
setParam(
"planner/grid_step_near_high",
true);
403 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
407 TEST(GlobalPlanner, AStarGradientK)
411 std::string ns =
"AStarGradientK";
414 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
415 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
416 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
417 nh.
setParam(
"planner/use_kernel",
true);
418 nh.
setParam(
"planner/manhattan_heuristic",
false);
419 nh.
setParam(
"planner/grid_step_near_high",
false);
420 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
424 TEST(GlobalPlanner, AStarGradientStepMan)
428 std::string ns =
"AStarGradientStepMan";
431 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
432 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
433 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
434 nh.
setParam(
"planner/use_kernel",
false);
435 nh.
setParam(
"planner/manhattan_heuristic",
true);
436 nh.
setParam(
"planner/grid_step_near_high",
true);
437 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
441 TEST(GlobalPlanner, AStarGradientMan)
445 std::string ns =
"AStarGradientMan";
448 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
449 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
450 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
451 nh.
setParam(
"planner/use_kernel",
false);
452 nh.
setParam(
"planner/manhattan_heuristic",
true);
453 nh.
setParam(
"planner/grid_step_near_high",
false);
454 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
458 TEST(GlobalPlanner, AStarGradientStep)
462 std::string ns =
"AStarGradientStep";
465 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
466 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
467 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
468 nh.
setParam(
"planner/use_kernel",
false);
469 nh.
setParam(
"planner/manhattan_heuristic",
false);
470 nh.
setParam(
"planner/grid_step_near_high",
true);
471 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
475 TEST(GlobalPlanner, AStarGradient)
479 std::string ns =
"AStarGradient";
482 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
483 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
484 nh.
setParam(
"planner/minimum_requeue_change", 0.0);
485 nh.
setParam(
"planner/use_kernel",
false);
486 nh.
setParam(
"planner/manhattan_heuristic",
false);
487 nh.
setParam(
"planner/grid_step_near_high",
false);
488 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
492 TEST(GlobalPlanner, AStarGradientStepManThreshK)
496 std::string ns =
"AStarGradientStepManThreshK";
499 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
500 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
501 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
502 nh.
setParam(
"planner/use_kernel",
true);
503 nh.
setParam(
"planner/manhattan_heuristic",
true);
504 nh.
setParam(
"planner/grid_step_near_high",
true);
505 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
509 TEST(GlobalPlanner, AStarGradientManThreshK)
513 std::string ns =
"AStarGradientManThreshK";
516 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
517 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
518 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
519 nh.
setParam(
"planner/use_kernel",
true);
520 nh.
setParam(
"planner/manhattan_heuristic",
true);
521 nh.
setParam(
"planner/grid_step_near_high",
false);
522 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
526 TEST(GlobalPlanner, AStarGradientStepThreshK)
530 std::string ns =
"AStarGradientStepThreshK";
533 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
534 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
535 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
536 nh.
setParam(
"planner/use_kernel",
true);
537 nh.
setParam(
"planner/manhattan_heuristic",
false);
538 nh.
setParam(
"planner/grid_step_near_high",
true);
539 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
543 TEST(GlobalPlanner, AStarGradientThreshK)
547 std::string ns =
"AStarGradientThreshK";
550 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
551 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
552 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
553 nh.
setParam(
"planner/use_kernel",
true);
554 nh.
setParam(
"planner/manhattan_heuristic",
false);
555 nh.
setParam(
"planner/grid_step_near_high",
false);
556 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
560 TEST(GlobalPlanner, AStarGradientStepManThresh)
564 std::string ns =
"AStarGradientStepManThresh";
567 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
568 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
569 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
570 nh.
setParam(
"planner/use_kernel",
false);
571 nh.
setParam(
"planner/manhattan_heuristic",
true);
572 nh.
setParam(
"planner/grid_step_near_high",
true);
573 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
577 TEST(GlobalPlanner, AStarGradientManThresh)
581 std::string ns =
"AStarGradientManThresh";
584 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
585 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
586 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
587 nh.
setParam(
"planner/use_kernel",
false);
588 nh.
setParam(
"planner/manhattan_heuristic",
true);
589 nh.
setParam(
"planner/grid_step_near_high",
false);
590 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
594 TEST(GlobalPlanner, AStarGradientStepThresh)
598 std::string ns =
"AStarGradientStepThresh";
601 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
602 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
603 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
604 nh.
setParam(
"planner/use_kernel",
false);
605 nh.
setParam(
"planner/manhattan_heuristic",
false);
606 nh.
setParam(
"planner/grid_step_near_high",
true);
607 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
611 TEST(GlobalPlanner, AStarGradientThresh)
615 std::string ns =
"AStarGradientThresh";
618 nh.
setParam(
"planner/potential_calculator",
"dlux_plugins::AStar");
619 nh.
setParam(
"planner/traceback",
"dlux_plugins::GradientPath");
620 nh.
setParam(
"planner/minimum_requeue_change", 1.0);
621 nh.
setParam(
"planner/use_kernel",
false);
622 nh.
setParam(
"planner/manhattan_heuristic",
false);
623 nh.
setParam(
"planner/grid_step_near_high",
false);
624 EXPECT_TRUE(many_map_test_suite(planner, tf, ns));
628 int main(
int argc,
char **argv)
631 testing::InitGoogleTest(&argc, argv);
632 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