heatmap_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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   // *************** Initialize the Planner ****************************************************************************
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   // *************** Get a list of every free cell**********************************************************************
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   // *************** Attempt planning between every pair of free cells**************************************************
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       // Print progress updates
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         // Mark the start and end cells of the planning failure
00116         failures[i] += 1;
00117         failures[j] += 1;
00118       }
00119       if (!ros::ok()) return false;
00120     }
00121   }
00122 
00123   // *************** Construct/Print an ASCII map of the failures*******************************************************
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 }


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