Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <global_planner_tests/many_map_test_suite.h>
00035 #include <dlux_global_planner/dlux_global_planner.h>
00036 #include <ros/ros.h>
00037 #include <gtest/gtest.h>
00038 #include <string>
00039
00040 using global_planner_tests::many_map_test_suite;
00041 using dlux_global_planner::DluxGlobalPlanner;
00042
00043 void dlux_test(std::string ns, std::string potential_calculator = "", std::string traceback = "")
00044 {
00045 TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
00046 DluxGlobalPlanner planner;
00047
00048 ros::NodeHandle nh("~/" + ns);
00049 if (potential_calculator.length() > 0)
00050 nh.setParam("potential_calculator", potential_calculator);
00051 if (traceback.length() > 0)
00052 nh.setParam("traceback", traceback);
00053 EXPECT_TRUE(many_map_test_suite(planner, tf, ns)) << potential_calculator << " " + traceback;
00054 }
00055
00056 TEST(GlobalPlanner, AStarVon)
00057 {
00058 dlux_test("AStarVon", "dlux_plugins::AStar", "dlux_plugins::VonNeumannPath");
00059 }
00060
00061 TEST(GlobalPlanner, AStarGrid)
00062 {
00063 dlux_test("AStarGrid", "dlux_plugins::AStar", "dlux_plugins::GridPath");
00064 }
00065
00066 TEST(GlobalPlanner, AStarGradient)
00067 {
00068 dlux_test("AStarGradient", "dlux_plugins::AStar", "dlux_plugins::GradientPath");
00069 }
00070
00071 TEST(GlobalPlanner, DijkstraVon)
00072 {
00073 dlux_test("DijkstraVon", "dlux_plugins::Dijkstra", "dlux_plugins::VonNeumannPath");
00074 }
00075
00076 TEST(GlobalPlanner, DijkstraGrid)
00077 {
00078 dlux_test("DijkstraGrid", "dlux_plugins::Dijkstra", "dlux_plugins::GridPath");
00079 }
00080
00081 TEST(GlobalPlanner, DijkstraGradient)
00082 {
00083 dlux_test("DijkstraGradient", "dlux_plugins::Dijkstra", "dlux_plugins::GradientPath");
00084 }
00085
00086 int main(int argc, char **argv)
00087 {
00088 ros::init(argc, argv, "planner_tests");
00089 testing::InitGoogleTest(&argc, argv);
00090 return RUN_ALL_TESTS();
00091 }