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 <nav_grid/coordinate_conversion.h>
00037 #include <pluginlib/class_loader.h>
00038 #include <algorithm>
00039 #include <string>
00040 #include <vector>
00041
00042 using global_planner_tests::PoseList;
00043 using global_planner_tests::groupCells;
00044 using global_planner_tests::planExists;
00045
00055 int main(int argc, char** argv)
00056 {
00057
00058 ros::init(argc, argv, "plan");
00059 ros::NodeHandle private_nh("~");
00060 TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
00061
00062 std::string map_filename;
00063 private_nh.param("map_filename", map_filename, std::string("package://global_planner_tests/maps/smile.png"));
00064 std::shared_ptr<global_planner_tests::EasyCostmap> global_costmap =
00065 std::make_shared<global_planner_tests::EasyCostmap>(map_filename);
00066
00067 pluginlib::ClassLoader<nav_core2::GlobalPlanner> global_planner_loader("nav_core2", "nav_core2::GlobalPlanner");
00068
00069 std::string planner_name;
00070 private_nh.param("global_planner", planner_name, std::string("dlux_global_planner::DluxGlobalPlanner"));
00071 boost::shared_ptr<nav_core2::GlobalPlanner> global_planner = global_planner_loader.createInstance(planner_name);
00072 global_planner->initialize(private_nh, global_planner_loader.getName(planner_name), tf, global_costmap);
00073
00074
00075 PoseList free_cells, occupied_cells;
00076 groupCells(*global_costmap, free_cells, occupied_cells);
00077
00078 int saved_pct = -1;
00079 unsigned int n = free_cells.size();
00080 if (n == 0)
00081 {
00082 return 0;
00083 }
00084
00085
00086 int passing_plans = 0, total_plans = 0;
00087 std::vector<unsigned int> failures(n, 0);
00088
00089 for (unsigned int j = 0; j < n; j++)
00090 {
00091 for (unsigned int i = 0; i < n; i++)
00092 {
00093
00094 {
00095 int pct = (total_plans / static_cast<float>(n * n)) * 20;
00096 if (pct != saved_pct)
00097 {
00098 float passing = 0.0;
00099 if (total_plans > 0)
00100 {
00101 passing = 100.0 * passing_plans / total_plans;
00102 }
00103 ROS_INFO("%d%% complete. %d tests, %.0f%% passing", pct * 100 / 20, total_plans, passing);
00104 saved_pct = pct;
00105 }
00106 }
00107 total_plans = total_plans + 1;
00108
00109 if (planExists(*global_planner, free_cells[i], free_cells[j]))
00110 {
00111 passing_plans = passing_plans + 1;
00112 }
00113 else
00114 {
00115
00116 failures[i] += 1;
00117 failures[j] += 1;
00118 }
00119 if (!ros::ok()) return false;
00120 }
00121 }
00122
00123
00124 const nav_grid::NavGridInfo& info = global_costmap->getInfo();
00125 std::vector<char> mmap(info.width * info.height, '.');
00126 unsigned int highest = *std::max_element(failures.begin(), failures.end());
00127
00128 for (unsigned int i = 0; i < n; i++)
00129 {
00130 unsigned int x, y;
00131 worldToGridBounded(info, free_cells[i].pose.x, free_cells[i].pose.y, x, y);
00132 int ct = failures[i];
00133 if (ct == 0)
00134 {
00135 mmap[ global_costmap->getIndex(x, y) ] = ' ';
00136 }
00137 else
00138 {
00139 double f = static_cast<double>(ct) / highest;
00140 int m = static_cast<int>(f * 9);
00141 mmap[ global_costmap->getIndex(x, y) ] = '0' + m;
00142 }
00143 }
00144 for (int j = info.height - 1; j >= 0; j--)
00145 {
00146 for (unsigned int i = 0; i < info.width; i++)
00147 {
00148 printf("%c", mmap[ global_costmap->getIndex(i, j) ]);
00149 }
00150 printf("\n");
00151 }
00152
00153 ROS_INFO("%d/%d valid plans found.", passing_plans, total_plans);
00154 return 0;
00155 }