Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
map_grid.cpp
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.hpp"
36 #include <cmath>
37 #include <string>
38 #include <vector>
39 #include <utility>
40 #include <algorithm>
41 #include <memory>
42 #include "dwb_core/exceptions.hpp"
43 #include "nav2_costmap_2d/cost_values.hpp"
44 #include "nav2_ros_common/node_utils.hpp"
45 
46 using std::abs;
48 
49 namespace dwb_critics
50 {
51 
52 // Customization of the CostmapQueue validCellToQueue method
54 {
55  return true;
56 }
57 
58 void MapGridCritic::onInit()
59 {
60  costmap_ = costmap_ros_->getCostmap();
61  queue_ = std::make_shared<MapGridQueue>(*costmap_, *this);
62 
63  // Always set to true, but can be overridden by subclasses
64  stop_on_failure_ = true;
65 
66  auto node = node_.lock();
67  if (!node) {
68  throw std::runtime_error{"Failed to lock node"};
69  }
70 
71  nav2::declare_parameter_if_not_declared(
72  node,
73  dwb_plugin_name_ + "." + name_ + ".aggregation_type",
74  rclcpp::ParameterValue(std::string("last")));
75 
76  std::string aggro_str;
77  node->get_parameter(dwb_plugin_name_ + "." + name_ + ".aggregation_type", aggro_str);
78  std::transform(aggro_str.begin(), aggro_str.end(), aggro_str.begin(), ::tolower);
79  if (aggro_str == "last") {
80  aggregationType_ = ScoreAggregationType::Last;
81  } else if (aggro_str == "sum") {
82  aggregationType_ = ScoreAggregationType::Sum;
83  } else if (aggro_str == "product") {
84  aggregationType_ = ScoreAggregationType::Product;
85  } else {
86  RCLCPP_ERROR(
87  rclcpp::get_logger(
88  "MapGridCritic"), "aggregation_type parameter \"%s\" invalid. Using Last.",
89  aggro_str.c_str());
90  aggregationType_ = ScoreAggregationType::Last;
91  }
92 }
93 
94 void MapGridCritic::setAsObstacle(unsigned int index)
95 {
96  cell_values_[index] = obstacle_score_;
97 }
98 
100 {
101  queue_->reset();
102  cell_values_.resize(costmap_->getSizeInCellsX() * costmap_->getSizeInCellsY());
103  obstacle_score_ = static_cast<double>(cell_values_.size());
104  unreachable_score_ = obstacle_score_ + 1.0;
105  std::fill(cell_values_.begin(), cell_values_.end(), unreachable_score_);
106 }
107 
109 {
110  while (!queue_->isEmpty()) {
111  costmap_queue::CellData cell = queue_->getNextCell();
112  cell_values_[cell.index_] = CellData::absolute_difference(cell.src_x_, cell.x_) +
113  CellData::absolute_difference(cell.src_y_, cell.y_);
114  }
115 }
116 
117 double MapGridCritic::scoreTrajectory(const dwb_msgs::msg::Trajectory2D & traj)
118 {
119  double score = 0.0;
120  unsigned int start_index = 0;
121  if (aggregationType_ == ScoreAggregationType::Product) {
122  score = 1.0;
123  } else if (aggregationType_ == ScoreAggregationType::Last && !stop_on_failure_) {
124  start_index = traj.poses.size() - 1;
125  }
126  double grid_dist;
127 
128  for (unsigned int i = start_index; i < traj.poses.size(); ++i) {
129  grid_dist = scorePose(traj.poses[i]);
130  if (stop_on_failure_) {
131  if (grid_dist == obstacle_score_) {
132  throw dwb_core::
133  IllegalTrajectoryException(name_, "Trajectory Hits Obstacle.");
134  } else if (grid_dist == unreachable_score_) {
135  throw dwb_core::
136  IllegalTrajectoryException(name_, "Trajectory Hits Unreachable Area.");
137  }
138  }
139 
140  switch (aggregationType_) {
141  case ScoreAggregationType::Last:
142  score = grid_dist;
143  break;
144  case ScoreAggregationType::Sum:
145  score += grid_dist;
146  break;
147  case ScoreAggregationType::Product:
148  if (score > 0) {
149  score *= grid_dist;
150  }
151  break;
152  }
153  }
154 
155  return score;
156 }
157 
158 double MapGridCritic::scorePose(const geometry_msgs::msg::Pose & pose)
159 {
160  unsigned int cell_x, cell_y;
161  // we won't allow trajectories that go off the map... shouldn't happen that often anyways
162  if (!costmap_->worldToMap(pose.position.x, pose.position.y, cell_x, cell_y)) {
163  throw dwb_core::
164  IllegalTrajectoryException(name_, "Trajectory Goes Off Grid.");
165  }
166  return getScore(cell_x, cell_y);
167 }
168 
170  std::vector<std::pair<std::string, std::vector<float>>> & cost_channels)
171 {
172  std::pair<std::string, std::vector<float>> grid_scores;
173  grid_scores.first = name_;
174 
175  nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
176  unsigned int size_x = costmap->getSizeInCellsX();
177  unsigned int size_y = costmap->getSizeInCellsY();
178  grid_scores.second.resize(size_x * size_y);
179  unsigned int i = 0;
180  for (unsigned int cy = 0; cy < size_y; cy++) {
181  for (unsigned int cx = 0; cx < size_x; cx++) {
182  grid_scores.second[i] = getScore(cx, cy);
183  i++;
184  }
185  }
186  cost_channels.push_back(grid_scores);
187 }
188 
189 } // namespace dwb_critics
Storage for cell information used during queue expansion.
bool validCellToQueue(const costmap_queue::CellData &cell) override
Check to see if we should add this cell to the queue. Always true unless overridden.
Definition: map_grid.cpp:53
double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj) override
Return a raw score for the given trajectory.
Definition: map_grid.cpp:117
void addCriticVisualization(std::vector< std::pair< std::string, std::vector< float >>> &cost_channels) override
Add information to the given pointcloud for debugging costmap-grid based scores.
Definition: map_grid.cpp:169
void reset() override
Clear the queueDWB_CRITICS_MAP_GRID_He and set cell_values_ to the appropriate number of unreachableC...
Definition: map_grid.cpp:99
void setAsObstacle(unsigned int index)
Sets the score of a particular cell to the obstacle cost.
Definition: map_grid.cpp:94
double getScore(unsigned int x, unsigned int y)
Retrieve the score for a particular cell of the costmap.
Definition: map_grid.hpp:85
double unreachable_score_
Special cell_values.
Definition: map_grid.hpp:136
void propagateManhattanDistances()
Go through the queue and set the cells to the Manhattan distance from their parents.
Definition: map_grid.cpp:108
virtual double scorePose(const geometry_msgs::msg::Pose &pose)
Retrieve the score for a single pose.
Definition: map_grid.cpp:158
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:291
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551