map_grid.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 
35 #include <dwb_critics/map_grid.h>
37 #include <nav_core2/exceptions.h>
38 #include <string>
39 #include <algorithm>
40 
41 namespace dwb_critics
42 {
43 
44 // Customization of the CostmapQueue validCellToQueue method
46 {
47  unsigned char cost = costmap_(cell.x_, cell.y_);
48  if (cost == costmap_.LETHAL_OBSTACLE ||
50  cost == costmap_.NO_INFORMATION)
51  {
52  parent_.setAsObstacle(cell.x_, cell.y_);
53  return false;
54  }
55 
56  return true;
57 }
58 
60 {
61  queue_ = std::make_shared<MapGridQueue>(*costmap_, *this);
62 
63  // Always set to true, but can be overriden by subclasses
64  stop_on_failure_ = true;
65 
66  std::string aggro_str;
67  critic_nh_.param("aggregation_type", aggro_str, std::string("last"));
68  std::transform(aggro_str.begin(), aggro_str.end(), aggro_str.begin(), ::tolower);
69  if (aggro_str == "last")
70  {
72  }
73  else if (aggro_str == "sum")
74  {
76  }
77  else if (aggro_str == "product")
78  {
80  }
81  else
82  {
83  ROS_ERROR_NAMED("MapGridCritic", "aggregation_type parameter \"%s\" invalid. Using Last.", aggro_str.c_str());
85  }
86 }
87 
88 void MapGridCritic::setAsObstacle(unsigned int x, unsigned int y)
89 {
91 }
92 
94 {
95  queue_->reset();
96  if (costmap_->getInfo() == cell_values_.getInfo())
97  {
99  }
100  else
101  {
102  obstacle_score_ = static_cast<double>(costmap_->getWidth() * costmap_->getHeight());
105  cell_values_.setInfo(costmap_->getInfo());
106  }
107 }
108 
110 {
111  while (!queue_->isEmpty())
112  {
113  costmap_queue::CellData cell = queue_->getNextCell();
114  cell_values_.setValue(cell.x_, cell.y_,
115  std::abs(static_cast<int>(cell.src_x_) - static_cast<int>(cell.x_))
116  + std::abs(static_cast<int>(cell.src_y_) - static_cast<int>(cell.y_)));
117  }
118 }
119 
120 double MapGridCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj)
121 {
122  double score = 0.0;
123  unsigned int start_index = 0;
125  {
126  score = 1.0;
127  }
129  {
130  start_index = traj.poses.size() - 1;
131  }
132  double grid_dist;
133 
134  for (unsigned int i = start_index; i < traj.poses.size(); ++i)
135  {
136  grid_dist = scorePose(traj.poses[i]);
137  if (stop_on_failure_)
138  {
139  if (grid_dist == obstacle_score_)
140  {
141  throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Obstacle.");
142  }
143  else if (grid_dist == unreachable_score_)
144  {
145  throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Unreachable Area.");
146  }
147  }
148 
149  switch (aggregationType_)
150  {
152  score = grid_dist;
153  break;
155  score += grid_dist;
156  break;
158  if (score > 0)
159  {
160  score *= grid_dist;
161  }
162  break;
163  }
164  }
165 
166  return score;
167 }
168 
169 double MapGridCritic::scorePose(const geometry_msgs::Pose2D& pose)
170 {
171  unsigned int cell_x, cell_y;
172  // we won't allow trajectories that go off the map... shouldn't happen that often anyways
173  if (!worldToGridBounded(costmap_->getInfo(), pose.x, pose.y, cell_x, cell_y))
174  {
175  throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Goes Off Grid.");
176  }
177  return getScore(cell_x, cell_y);
178 }
179 
180 void MapGridCritic::addCriticVisualization(sensor_msgs::PointCloud& pc)
181 {
182  sensor_msgs::ChannelFloat32 grid_scores;
183  grid_scores.name = name_;
184 
186  unsigned int size_x = costmap.getWidth();
187  unsigned int size_y = costmap.getHeight();
188  grid_scores.values.resize(size_x * size_y);
189  unsigned int i = 0;
190  for (unsigned int cy = 0; cy < size_y; cy++)
191  {
192  for (unsigned int cx = 0; cx < size_x; cx++)
193  {
194  grid_scores.values[i] = getScore(cx, cy);
195  i++;
196  }
197  }
198  pc.channels.push_back(grid_scores);
199 }
200 
201 } // namespace dwb_critics
void reset() override
Clear the queue and set cell_values_ to the appropriate number of unreachableCellScore.
Definition: map_grid.cpp:93
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
bool validCellToQueue(const costmap_queue::CellData &cell) override
Definition: map_grid.cpp:45
nav_core2::BasicCostmap costmap
virtual double scorePose(const geometry_msgs::Pose2D &pose)
Retrieve the score for a single pose.
Definition: map_grid.cpp:169
void propogateManhattanDistances()
Go through the queue and set the cells to the Manhattan distance from their parents.
Definition: map_grid.cpp:109
void setAsObstacle(unsigned int x, unsigned int y)
Sets the score of a particular cell to the obstacle cost.
Definition: map_grid.cpp:88
static const unsigned char NO_INFORMATION
void setDefaultValue(const T new_value)
ScoreAggregationType aggregationType_
Definition: map_grid.h:129
void reset() override
void addCriticVisualization(sensor_msgs::PointCloud &pc) override
Definition: map_grid.cpp:180
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void setInfo(const NavGridInfo &new_info) override
void setValue(const unsigned int x, const unsigned int y, const T &value) override
double getScore(unsigned int x, unsigned int y)
Retrieve the score for a particular cell of the costmap.
Definition: map_grid.h:82
nav_core2::Costmap & costmap_
NavGridInfo getInfo() const
void onInit() override
Definition: map_grid.cpp:59
#define ROS_ERROR_NAMED(name,...)
static const unsigned char LETHAL_OBSTACLE
std::shared_ptr< MapGridQueue > queue_
Definition: map_grid.h:125
nav_grid::VectorNavGrid< double > cell_values_
Definition: map_grid.h:126
double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
Definition: map_grid.cpp:120
double unreachable_score_
Special cell_values.
Definition: map_grid.h:127
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)


dwb_critics
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:06:22