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


dwb_critics
Author(s): David V. Lu!!
autogenerated on Sun Jan 10 2021 04:08:44