39 #include <yaml-cpp/yaml.h> 47 const std::string& planner_name,
const std::string& maps_list_filename,
48 bool check_exception_type,
bool verbose,
bool quit_early)
52 std::shared_ptr<EasyCostmap> easy_costmap = std::make_shared<EasyCostmap>();
53 planner.
initialize(nh, planner_name, tf, easy_costmap);
57 std::string prefix =
"";
58 int max_failure_cases = 10;
59 if (config[
"standard_prefix"])
61 prefix = config[
"standard_prefix"].as<std::string>();
63 if (config[
"max_failure_cases"])
65 max_failure_cases = config[
"max_failure_cases"].as<
int>();
69 struct timeval start, end;
70 double start_t, end_t, t_diff;
71 gettimeofday(&start,
nullptr);
73 bool passes_all =
true;
76 for (
const std::string base_filename : config[
"full_coverage_maps"].as<std::vector<std::string> >())
78 std::string map_filename = prefix + base_filename;
79 ROS_INFO(
"Testing full coverage map \"%s\"", map_filename.c_str());
80 easy_costmap->loadMapFromFile(map_filename);
83 check_exception_type, verbose, quit_early);
84 if (quit_early && !ret)
return ret;
89 for (
const std::string base_filename : config[
"no_coverage_maps"].as<std::vector<std::string> >())
91 std::string map_filename = prefix + base_filename;
92 ROS_INFO(
"Testing no coverage map \"%s\"", map_filename.c_str());
93 easy_costmap->loadMapFromFile(map_filename);
96 check_exception_type, verbose, quit_early);
97 if (quit_early && !invalid_test)
return invalid_test;
98 passes_all &= invalid_test;
101 gettimeofday(&end,
nullptr);
102 start_t = start.tv_sec +
static_cast<double>(start.tv_usec) / 1e6;
103 end_t = end.tv_sec +
static_cast<double>(end.tv_usec) / 1e6;
104 t_diff = end_t - start_t;
105 ROS_INFO(
"%s Full Planning Time: %.9f", planner_name.c_str(), t_diff);
std::string resolve_filename(const std::string &filename)
Replace a package:// prefix with the actual path to the given package.
virtual void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, Costmap::Ptr costmap)=0
bool many_map_test_suite(nav_core2::GlobalPlanner &planner, TFListenerPtr tf, const std::string &planner_name, const std::string &maps_list_filename="package://global_planner_tests/config/standard_tests.yaml", bool check_exception_type=true, bool verbose=false, bool quit_early=true)
Run a collection of global_planner_tests on the provided maps.
bool hasCompleteCoverage(nav_core2::GlobalPlanner &planner, const nav_core2::Costmap &costmap, int max_failure_cases=10, bool check_exception_type=true, bool verbose=false, bool quit_early=true)
Run a bunch of tests, assuming there is a valid path from any free cell to any other free cell...
std::shared_ptr< tf::TransformListener > TFListenerPtr
bool hasNoPaths(nav_core2::GlobalPlanner &planner, const nav_core2::Costmap &costmap, bool check_exception_type=true, bool verbose=false, bool quit_early=true)
Run a bunch of tests, assuming there are no valid paths from any free cell to any other free cell...