many_map_test_suite.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
39 #include <yaml-cpp/yaml.h>
40 #include <string>
41 #include <vector>
42 
43 namespace global_planner_tests
44 {
46  const std::string& planner_name, const std::string& maps_list_filename,
47  bool check_exception_type, bool verbose, bool quit_early)
48 {
49  // Initialize Costmap
50  ros::NodeHandle nh("~");
51  std::shared_ptr<EasyCostmap> easy_costmap = std::make_shared<EasyCostmap>();
52  planner.initialize(nh, planner_name, tf, easy_costmap);
53 
54  // Read Configuration
55  YAML::Node config = YAML::LoadFile(resolve_filename(maps_list_filename));
56  std::string prefix = "";
57  int max_failure_cases = 10;
58  if (config["standard_prefix"])
59  {
60  prefix = config["standard_prefix"].as<std::string>();
61  }
62  if (config["max_failure_cases"])
63  {
64  max_failure_cases = config["max_failure_cases"].as<int>();
65  }
66 
67  // Start the timer
68  struct timeval start, end;
69  double start_t, end_t, t_diff;
70  gettimeofday(&start, nullptr);
71 
72  bool passes_all = true;
73 
74  // Check all the Full Coverage Maps
75  for (const std::string base_filename : config["full_coverage_maps"].as<std::vector<std::string> >())
76  {
77  std::string map_filename = prefix + base_filename;
78  ROS_INFO("Testing full coverage map \"%s\"", map_filename.c_str());
79  easy_costmap->loadMapFromFile(map_filename);
80 
81  bool ret = global_planner_tests::hasCompleteCoverage(planner, *easy_costmap, max_failure_cases,
82  check_exception_type, verbose, quit_early);
83  if (quit_early && !ret) return ret;
84  passes_all &= ret;
85  }
86 
87  // Check all the No Coverage Maps
88  for (const std::string base_filename : config["no_coverage_maps"].as<std::vector<std::string> >())
89  {
90  std::string map_filename = prefix + base_filename;
91  ROS_INFO("Testing no coverage map \"%s\"", map_filename.c_str());
92  easy_costmap->loadMapFromFile(map_filename);
93 
94  bool invalid_test = global_planner_tests::hasNoPaths(planner, *easy_costmap,
95  check_exception_type, verbose, quit_early);
96  if (quit_early && !invalid_test) return invalid_test;
97  passes_all &= invalid_test;
98  }
99 
100  gettimeofday(&end, nullptr);
101  start_t = start.tv_sec + static_cast<double>(start.tv_usec) / 1e6;
102  end_t = end.tv_sec + static_cast<double>(end.tv_usec) / 1e6;
103  t_diff = end_t - start_t;
104  ROS_INFO("%s Full Planning Time: %.9f", planner_name.c_str(), t_diff);
105 
106  return passes_all;
107 }
108 } // namespace global_planner_tests
std::string resolve_filename(const std::string &filename)
Replace a package:// prefix with the actual path to the given package.
Definition: util.cpp:43
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.
#define ROS_INFO(...)
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...


global_planner_tests
Author(s):
autogenerated on Wed Jun 26 2019 20:06:09