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/global_planner_tests.h>
00035 #include <global_planner_tests/easy_costmap.h>
00036 #include <pluginlib/class_loader.h>
00037 #include <string>
00038
00039 int main(int argc, char** argv)
00040 {
00041 ros::init(argc, argv, "plan");
00042 ros::NodeHandle private_nh("~");
00043 TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
00044
00045 std::string map_filename;
00046 private_nh.param("map_filename", map_filename, std::string("package://global_planner_tests/maps/smile.png"));
00047 nav_core2::Costmap::Ptr global_costmap = std::make_shared<global_planner_tests::EasyCostmap>(map_filename);
00048
00049 pluginlib::ClassLoader<nav_core2::GlobalPlanner> global_planner_loader("nav_core2", "nav_core2::GlobalPlanner");
00050
00051 std::string planner_name;
00052 private_nh.param("global_planner", planner_name, std::string("dlux_global_planner::DluxGlobalPlanner"));
00053 boost::shared_ptr<nav_core2::GlobalPlanner> global_planner = global_planner_loader.createInstance(planner_name);
00054 global_planner->initialize(private_nh, global_planner_loader.getName(planner_name), tf, global_costmap);
00055
00056 if (global_planner_tests::hasCompleteCoverage(*global_planner, *global_costmap, 10, true, true, false))
00057 {
00058 printf("PASSES\n");
00059 }
00060 else
00061 {
00062 printf("FAILS\n");
00063 }
00064
00065 return (0);
00066 }