34 #include <global_planner_tests/many_map_test_suite.h> 37 #include <gtest/gtest.h> 41 using global_planner_tests::many_map_test_suite;
44 void dlux_test(std::string ns, std::string potential_calculator =
"", std::string traceback =
"")
50 if (potential_calculator.length() > 0)
51 nh.
setParam(
"potential_calculator", potential_calculator);
52 if (traceback.length() > 0)
54 EXPECT_TRUE(many_map_test_suite(planner, tf, ns)) << potential_calculator <<
" " + traceback;
57 TEST(GlobalPlanner, AStarVon)
59 dlux_test(
"AStarVon",
"dlux_plugins::AStar",
"dlux_plugins::VonNeumannPath");
62 TEST(GlobalPlanner, AStarGrid)
64 dlux_test(
"AStarGrid",
"dlux_plugins::AStar",
"dlux_plugins::GridPath");
67 TEST(GlobalPlanner, AStarGradient)
69 dlux_test(
"AStarGradient",
"dlux_plugins::AStar",
"dlux_plugins::GradientPath");
72 TEST(GlobalPlanner, DijkstraVon)
74 dlux_test(
"DijkstraVon",
"dlux_plugins::Dijkstra",
"dlux_plugins::VonNeumannPath");
77 TEST(GlobalPlanner, DijkstraGrid)
79 dlux_test(
"DijkstraGrid",
"dlux_plugins::Dijkstra",
"dlux_plugins::GridPath");
82 TEST(GlobalPlanner, DijkstraGradient)
84 dlux_test(
"DijkstraGradient",
"dlux_plugins::Dijkstra",
"dlux_plugins::GradientPath");
87 int main(
int argc,
char **argv)
90 testing::InitGoogleTest(&argc, argv);
91 return RUN_ALL_TESTS();
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void dlux_test(std::string ns, std::string potential_calculator="", std::string traceback="")
int main(int argc, char **argv)
TEST(GlobalPlanner, AStarVon)
std::shared_ptr< tf::TransformListener > TFListenerPtr
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const