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
00035 #include <global_planner_tests/many_map_test_suite.h>
00036 #include <global_planner_tests/global_planner_tests.h>
00037 #include <global_planner_tests/easy_costmap.h>
00038 #include <global_planner_tests/util.h>
00039 #include <yaml-cpp/yaml.h>
00040 #include <string>
00041 #include <vector>
00042
00043 namespace global_planner_tests
00044 {
00045 bool many_map_test_suite(nav_core2::GlobalPlanner& planner, TFListenerPtr tf,
00046 const std::string& planner_name, const std::string& maps_list_filename,
00047 bool check_exception_type, bool verbose, bool quit_early)
00048 {
00049
00050 ros::NodeHandle nh("~");
00051 std::shared_ptr<EasyCostmap> easy_costmap = std::make_shared<EasyCostmap>();
00052 planner.initialize(nh, planner_name, tf, easy_costmap);
00053
00054
00055 YAML::Node config = YAML::LoadFile(resolve_filename(maps_list_filename));
00056 std::string prefix = "";
00057 int max_failure_cases = 10;
00058 if (config["standard_prefix"])
00059 {
00060 prefix = config["standard_prefix"].as<std::string>();
00061 }
00062 if (config["max_failure_cases"])
00063 {
00064 max_failure_cases = config["max_failure_cases"].as<int>();
00065 }
00066
00067
00068 struct timeval start, end;
00069 double start_t, end_t, t_diff;
00070 gettimeofday(&start, nullptr);
00071
00072 bool passes_all = true;
00073
00074
00075 for (const std::string base_filename : config["full_coverage_maps"].as<std::vector<std::string> >())
00076 {
00077 std::string map_filename = prefix + base_filename;
00078 ROS_INFO("Testing full coverage map \"%s\"", map_filename.c_str());
00079 easy_costmap->loadMapFromFile(map_filename);
00080
00081 bool ret = global_planner_tests::hasCompleteCoverage(planner, *easy_costmap, max_failure_cases,
00082 check_exception_type, verbose, quit_early);
00083 if (quit_early && !ret) return ret;
00084 passes_all &= ret;
00085 }
00086
00087
00088 for (const std::string base_filename : config["no_coverage_maps"].as<std::vector<std::string> >())
00089 {
00090 std::string map_filename = prefix + base_filename;
00091 ROS_INFO("Testing no coverage map \"%s\"", map_filename.c_str());
00092 easy_costmap->loadMapFromFile(map_filename);
00093
00094 bool invalid_test = global_planner_tests::hasNoPaths(planner, *easy_costmap,
00095 check_exception_type, verbose, quit_early);
00096 if (quit_early && !invalid_test) return invalid_test;
00097 passes_all &= invalid_test;
00098 }
00099
00100 gettimeofday(&end, nullptr);
00101 start_t = start.tv_sec + static_cast<double>(start.tv_usec) / 1e6;
00102 end_t = end.tv_sec + static_cast<double>(end.tv_usec) / 1e6;
00103 t_diff = end_t - start_t;
00104 ROS_INFO("%s Full Planning Time: %.9f", planner_name.c_str(), t_diff);
00105
00106 return passes_all;
00107 }
00108 }