heatmap_node.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  */
37 #include <pluginlib/class_loader.h>
38 #include <algorithm>
39 #include <string>
40 #include <vector>
41 
45 
55 int main(int argc, char** argv)
56 {
57  // *************** Initialize the Planner ****************************************************************************
58  ros::init(argc, argv, "plan");
59  ros::NodeHandle private_nh("~");
60  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
61 
62  std::string map_filename;
63  private_nh.param("map_filename", map_filename, std::string("package://global_planner_tests/maps/smile.png"));
64  std::shared_ptr<global_planner_tests::EasyCostmap> global_costmap =
65  std::make_shared<global_planner_tests::EasyCostmap>(map_filename);
66 
67  pluginlib::ClassLoader<nav_core2::GlobalPlanner> global_planner_loader("nav_core2", "nav_core2::GlobalPlanner");
68 
69  std::string planner_name;
70  private_nh.param("global_planner", planner_name, std::string("dlux_global_planner::DluxGlobalPlanner"));
71  boost::shared_ptr<nav_core2::GlobalPlanner> global_planner = global_planner_loader.createInstance(planner_name);
72  global_planner->initialize(private_nh, global_planner_loader.getName(planner_name), tf, global_costmap);
73 
74  // *************** Get a list of every free cell**********************************************************************
75  PoseList free_cells, occupied_cells;
76  groupCells(*global_costmap, free_cells, occupied_cells);
77 
78  int saved_pct = -1;
79  unsigned int n = free_cells.size();
80  if (n == 0)
81  {
82  return 0;
83  }
84 
85  // *************** Attempt planning between every pair of free cells**************************************************
86  int passing_plans = 0, total_plans = 0;
87  std::vector<unsigned int> failures(n, 0);
88 
89  for (unsigned int j = 0; j < n; j++)
90  {
91  for (unsigned int i = 0; i < n; i++)
92  {
93  // Print progress updates
94  {
95  int pct = (total_plans / static_cast<float>(n * n)) * 20;
96  if (pct != saved_pct)
97  {
98  float passing = 0.0;
99  if (total_plans > 0)
100  {
101  passing = 100.0 * passing_plans / total_plans;
102  }
103  ROS_INFO("%d%% complete. %d tests, %.0f%% passing", pct * 100 / 20, total_plans, passing);
104  saved_pct = pct;
105  }
106  }
107  total_plans = total_plans + 1;
108 
109  if (planExists(*global_planner, free_cells[i], free_cells[j]))
110  {
111  passing_plans = passing_plans + 1;
112  }
113  else
114  {
115  // Mark the start and end cells of the planning failure
116  failures[i] += 1;
117  failures[j] += 1;
118  }
119  if (!ros::ok()) return false;
120  }
121  }
122 
123  // *************** Construct/Print an ASCII map of the failures*******************************************************
124  const nav_grid::NavGridInfo& info = global_costmap->getInfo();
125  std::vector<char> mmap(info.width * info.height, '.');
126  unsigned int highest = *std::max_element(failures.begin(), failures.end());
127 
128  for (unsigned int i = 0; i < n; i++)
129  {
130  unsigned int x, y;
131  worldToGridBounded(info, free_cells[i].pose.x, free_cells[i].pose.y, x, y);
132  int ct = failures[i];
133  if (ct == 0)
134  {
135  mmap[ global_costmap->getIndex(x, y) ] = ' ';
136  }
137  else
138  {
139  double f = static_cast<double>(ct) / highest;
140  int m = static_cast<int>(f * 9);
141  mmap[ global_costmap->getIndex(x, y) ] = '0' + m;
142  }
143  }
144  for (int j = info.height - 1; j >= 0; j--)
145  {
146  for (unsigned int i = 0; i < info.width; i++)
147  {
148  printf("%c", mmap[ global_costmap->getIndex(i, j) ]);
149  }
150  printf("\n");
151  }
152 
153  ROS_INFO("%d/%d valid plans found.", passing_plans, total_plans);
154  return 0;
155 }
std::vector< nav_2d_msgs::Pose2DStamped > PoseList
f
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & x() const
bool planExists(nav_core2::GlobalPlanner &planner, nav_2d_msgs::Pose2DStamped start, nav_2d_msgs::Pose2DStamped goal)
Simple check to see if a plan exists. Returns a boolean instead of returning path or throwing an exce...
int main(int argc, char **argv)
std::shared_ptr< tf::TransformListener > TFListenerPtr
void groupCells(const nav_core2::Costmap &costmap, PoseList &free_cells, PoseList &occupied_cells, bool include_edges=true)
Populate two lists of poses from a costmap. one with all the free cells, the other with all the occup...
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)


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