Nav2 Navigation Stack - humble  humble
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 
22  unsigned int num_quantizations,
23  rclcpp_lifecycle::LifecycleNode::SharedPtr node)
24 : FootprintCollisionChecker(costmap)
25 {
26  if (node) {
27  clock_ = node->get_clock();
28  logger_ = node->get_logger();
29  }
30 
31  // Convert number of regular bins into angles
32  float bin_size = 2 * M_PI / static_cast<float>(num_quantizations);
33  angles_.reserve(num_quantizations);
34  for (unsigned int i = 0; i != num_quantizations; i++) {
35  angles_.push_back(bin_size * i);
36  }
37 }
38 
39 // GridCollisionChecker::GridCollisionChecker(
40 // nav2_costmap_2d::Costmap2D * costmap,
41 // std::vector<float> & angles)
42 // : FootprintCollisionChecker(costmap),
43 // angles_(angles)
44 // {
45 // }
46 
48  const nav2_costmap_2d::Footprint & footprint,
49  const bool & radius,
50  const double & possible_inscribed_cost)
51 {
52  possible_inscribed_cost_ = possible_inscribed_cost;
53  footprint_is_radius_ = radius;
54 
55  // Use radius, no caching required
56  if (radius) {
57  return;
58  }
59 
60  // No change, no updates required
61  if (footprint == unoriented_footprint_) {
62  return;
63  }
64 
65  oriented_footprints_.clear();
66  oriented_footprints_.reserve(angles_.size());
67  double sin_th, cos_th;
68  geometry_msgs::msg::Point new_pt;
69  const unsigned int footprint_size = footprint.size();
70 
71  // Precompute the orientation bins for checking to use
72  for (unsigned int i = 0; i != angles_.size(); i++) {
73  sin_th = sin(angles_[i]);
74  cos_th = cos(angles_[i]);
75  nav2_costmap_2d::Footprint oriented_footprint;
76  oriented_footprint.reserve(footprint_size);
77 
78  for (unsigned int j = 0; j < footprint_size; j++) {
79  new_pt.x = footprint[j].x * cos_th - footprint[j].y * sin_th;
80  new_pt.y = footprint[j].x * sin_th + footprint[j].y * cos_th;
81  oriented_footprint.push_back(new_pt);
82  }
83 
84  oriented_footprints_.push_back(oriented_footprint);
85  }
86 
87  unoriented_footprint_ = footprint;
88 }
89 
91  const float & x,
92  const float & y,
93  const float & angle_bin,
94  const bool & traverse_unknown)
95 {
96  // Check to make sure cell is inside the map
97  if (outsideRange(costmap_->getSizeInCellsX(), x) ||
98  outsideRange(costmap_->getSizeInCellsY(), y))
99  {
100  return true;
101  }
102 
103  // Assumes setFootprint already set
104  double wx, wy;
105  costmap_->mapToWorld(static_cast<double>(x), static_cast<double>(y), wx, wy);
106 
107  if (!footprint_is_radius_) {
108  // if footprint, then we check for the footprint's points, but first see
109  // if the robot is even potentially in an inscribed collision
110  footprint_cost_ = costmap_->getCost(
111  static_cast<unsigned int>(x), static_cast<unsigned int>(y));
112 
113  if (footprint_cost_ < possible_inscribed_cost_) {
114  if (possible_inscribed_cost_ > 0) {
115  return false;
116  } else {
117  RCLCPP_ERROR_THROTTLE(
118  logger_, *clock_, 1000,
119  "Inflation layer either not found or inflation is not set sufficiently for "
120  "optimized non-circular collision checking capabilities. It is HIGHLY recommended to set"
121  " the inflation radius to be at MINIMUM half of the robot's largest cross-section. See "
122  "github.com/ros-planning/navigation2/tree/main/nav2_smac_planner#potential-fields"
123  " for full instructions. This will substantially impact run-time performance.");
124  }
125  }
126 
127  // If its inscribed, in collision, or unknown in the middle,
128  // no need to even check the footprint, its invalid
129  if (footprint_cost_ == UNKNOWN && !traverse_unknown) {
130  return true;
131  }
132 
133  if (footprint_cost_ == INSCRIBED || footprint_cost_ == OCCUPIED) {
134  return true;
135  }
136 
137  // if possible inscribed, need to check actual footprint pose.
138  // Use precomputed oriented footprints are done on initialization,
139  // offset by translation value to collision check
140  geometry_msgs::msg::Point new_pt;
141  const nav2_costmap_2d::Footprint & oriented_footprint = oriented_footprints_[angle_bin];
142  nav2_costmap_2d::Footprint current_footprint;
143  current_footprint.reserve(oriented_footprint.size());
144  for (unsigned int i = 0; i < oriented_footprint.size(); ++i) {
145  new_pt.x = wx + oriented_footprint[i].x;
146  new_pt.y = wy + oriented_footprint[i].y;
147  current_footprint.push_back(new_pt);
148  }
149 
150  footprint_cost_ = footprintCost(current_footprint);
151 
152  if (footprint_cost_ == UNKNOWN && traverse_unknown) {
153  return false;
154  }
155 
156  // if occupied or unknown and not to traverse unknown space
157  return footprint_cost_ >= OCCUPIED;
158  } else {
159  // if radius, then we can check the center of the cost assuming inflation is used
160  footprint_cost_ = costmap_->getCost(
161  static_cast<unsigned int>(x), static_cast<unsigned int>(y));
162 
163  if (footprint_cost_ == UNKNOWN && traverse_unknown) {
164  return false;
165  }
166 
167  // if occupied or unknown and not to traverse unknown space
168  return static_cast<double>(footprint_cost_) >= INSCRIBED;
169  }
170 }
171 
173  const unsigned int & i,
174  const bool & traverse_unknown)
175 {
176  footprint_cost_ = costmap_->getCost(i);
177  if (footprint_cost_ == UNKNOWN && traverse_unknown) {
178  return false;
179  }
180 
181  // if occupied or unknown and not to traverse unknown space
182  return footprint_cost_ >= INSCRIBED;
183 }
184 
186 {
187  // Assumes inCollision called prior
188  return static_cast<float>(footprint_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
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
Definition: costmap_2d.cpp:281
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:266
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:506
double footprintCost(const Footprint footprint)
Find the footprint cost in oriented footprint.
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.
void setFootprint(const nav2_costmap_2d::Footprint &footprint, const bool &radius, const double &possible_inscribed_cost)
A constructor for nav2_smac_planner::GridCollisionChecker for use when irregular bin intervals are ap...
GridCollisionChecker(nav2_costmap_2d::Costmap2D *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...
float getCost()
Get cost at footprint pose in costmap.