Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
collision_checker.cpp
1 // Copyright (c) 2021, Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License. Reserved.
14 
15 #include "nav2_smac_planner/collision_checker.hpp"
16 
17 namespace nav2_smac_planner
18 {
19 
21  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
22  unsigned int num_quantizations,
23  rclcpp_lifecycle::LifecycleNode::SharedPtr node)
24 : FootprintCollisionChecker(costmap_ros ? costmap_ros->getCostmap() : nullptr)
25 {
26  if (node) {
27  clock_ = node->get_clock();
28  logger_ = node->get_logger();
29  }
30 
31  if (costmap_ros) {
32  costmap_ros_ = costmap_ros;
33  }
34 
35  // Convert number of regular bins into angles
36  float bin_size = 2 * M_PI / static_cast<float>(num_quantizations);
37  angles_.reserve(num_quantizations);
38  for (unsigned int i = 0; i != num_quantizations; i++) {
39  angles_.push_back(bin_size * i);
40  }
41 }
42 
43 // GridCollisionChecker::GridCollisionChecker(
44 // nav2_costmap_2d::Costmap2D * costmap,
45 // std::vector<float> & angles)
46 // : FootprintCollisionChecker(costmap),
47 // angles_(angles)
48 // {
49 // }
50 
52  const nav2_costmap_2d::Footprint & footprint,
53  const bool & radius,
54  const double & possible_collision_cost)
55 {
56  possible_collision_cost_ = static_cast<float>(possible_collision_cost);
57  if (possible_collision_cost_ <= 0.0f) {
58  RCLCPP_ERROR_THROTTLE(
59  logger_, *clock_, 1000,
60  "Inflation layer either not found or inflation is not set sufficiently for "
61  "optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
62  " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
63  "github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
64  " for full instructions. This will substantially impact run-time performance.");
65  }
66 
67  footprint_is_radius_ = radius;
68 
69  // Use radius, no caching required
70  if (radius) {
71  return;
72  }
73 
74  // No change, no updates required
75  if (footprint == unoriented_footprint_) {
76  return;
77  }
78 
79  oriented_footprints_.clear();
80  oriented_footprints_.reserve(angles_.size());
81  double sin_th, cos_th;
82  geometry_msgs::msg::Point new_pt;
83  const unsigned int footprint_size = footprint.size();
84 
85  // Precompute the orientation bins for checking to use
86  for (unsigned int i = 0; i != angles_.size(); i++) {
87  sin_th = sin(angles_[i]);
88  cos_th = cos(angles_[i]);
89  nav2_costmap_2d::Footprint oriented_footprint;
90  oriented_footprint.reserve(footprint_size);
91 
92  for (unsigned int j = 0; j < footprint_size; j++) {
93  new_pt.x = footprint[j].x * cos_th - footprint[j].y * sin_th;
94  new_pt.y = footprint[j].x * sin_th + footprint[j].y * cos_th;
95  oriented_footprint.push_back(new_pt);
96  }
97 
98  oriented_footprints_.push_back(oriented_footprint);
99  }
100 
101  unoriented_footprint_ = footprint;
102 }
103 
105  const float & x,
106  const float & y,
107  const float & angle_bin,
108  const bool & traverse_unknown)
109 {
110  // Check to make sure cell is inside the map
111  if (outsideRange(costmap_->getSizeInCellsX(), x) ||
112  outsideRange(costmap_->getSizeInCellsY(), y))
113  {
114  return true;
115  }
116 
117  // Assumes setFootprint already set
118  center_cost_ = static_cast<float>(costmap_->getCost(
119  static_cast<unsigned int>(x + 0.5f), static_cast<unsigned int>(y + 0.5f)));
120 
121  if (!footprint_is_radius_) {
122  // if footprint, then we check for the footprint's points, but first see
123  // if the robot is even potentially in an inscribed collision
124  if (center_cost_ < possible_collision_cost_ && possible_collision_cost_ > 0.0f) {
125  return false;
126  }
127 
128  // If its inscribed, in collision, or unknown in the middle,
129  // no need to even check the footprint, its invalid
130  if (center_cost_ == UNKNOWN && !traverse_unknown) {
131  return true;
132  }
133 
134  if (center_cost_ == INSCRIBED || center_cost_ == OCCUPIED) {
135  return true;
136  }
137 
138  // if possible inscribed, need to check actual footprint pose.
139  // Use precomputed oriented footprints are done on initialization,
140  // offset by translation value to collision check
141  double wx, wy;
142  costmap_->mapToWorld(static_cast<double>(x), static_cast<double>(y), wx, wy);
143  geometry_msgs::msg::Point new_pt;
144  const nav2_costmap_2d::Footprint & oriented_footprint = oriented_footprints_[angle_bin];
145  nav2_costmap_2d::Footprint current_footprint;
146  current_footprint.reserve(oriented_footprint.size());
147  for (unsigned int i = 0; i < oriented_footprint.size(); ++i) {
148  new_pt.x = wx + oriented_footprint[i].x;
149  new_pt.y = wy + oriented_footprint[i].y;
150  current_footprint.push_back(new_pt);
151  }
152 
153  float footprint_cost = static_cast<float>(footprintCost(current_footprint));
154 
155  if (footprint_cost == UNKNOWN && traverse_unknown) {
156  return false;
157  }
158 
159  // if occupied or unknown and not to traverse unknown space
160  return footprint_cost >= OCCUPIED;
161  } else {
162  // if radius, then we can check the center of the cost assuming inflation is used
163  if (center_cost_ == UNKNOWN && traverse_unknown) {
164  return false;
165  }
166 
167  // if occupied or unknown and not to traverse unknown space
168  return center_cost_ >= INSCRIBED;
169  }
170 }
171 
173  const unsigned int & i,
174  const bool & traverse_unknown)
175 {
176  center_cost_ = costmap_->getCost(i);
177  if (center_cost_ == UNKNOWN && traverse_unknown) {
178  return false;
179  }
180 
181  // if occupied or unknown and not to traverse unknown space
182  return center_cost_ >= INSCRIBED;
183 }
184 
186 {
187  // Assumes inCollision called prior
188  return static_cast<float>(center_cost_);
189 }
190 
191 bool GridCollisionChecker::outsideRange(const unsigned int & max, const float & value)
192 {
193  return value < 0.0f || value > max;
194 }
195 
196 } // namespace nav2_smac_planner
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
Definition: costmap_2d.cpp:279
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:514
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:519
double footprintCost(const Footprint &footprint)
Find the footprint cost in oriented footprint.
void setFootprint(const nav2_costmap_2d::Footprint &footprint, const bool &radius, const double &possible_collision_cost)
A constructor for nav2_smac_planner::GridCollisionChecker for use when irregular bin intervals are ap...
GridCollisionChecker(std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap, unsigned int num_quantizations, rclcpp_lifecycle::LifecycleNode::SharedPtr node)
A constructor for nav2_smac_planner::GridCollisionChecker for use when regular bin intervals are appr...
bool inCollision(const float &x, const float &y, const float &theta, const bool &traverse_unknown)
Check if in collision with costmap and footprint at pose.
bool outsideRange(const unsigned int &max, const float &value)
Check if value outside the range.
float getCost()
Get cost at footprint pose in costmap.