|
| 1 | +#! /usr/bin/env python3 |
| 2 | +# Copyright 2021 Samsung Research America |
| 3 | +# Copyright 2022 Afif Swaidan |
| 4 | +# |
| 5 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 6 | +# you may not use this file except in compliance with the License. |
| 7 | +# You may obtain a copy of the License at |
| 8 | +# |
| 9 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 10 | +# |
| 11 | +# Unless required by applicable law or agreed to in writing, software |
| 12 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 13 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 14 | +# See the License for the specific language governing permissions and |
| 15 | +# limitations under the License. |
| 16 | + |
| 17 | +""" |
| 18 | +This is a Python3 API for a Footprint Collision Checker. |
| 19 | +
|
| 20 | +It provides the needed methods to manipulate the coordinates |
| 21 | +and calculate the cost of a Footprint |
| 22 | +""" |
| 23 | + |
| 24 | +from math import cos, sin |
| 25 | + |
| 26 | +from geometry_msgs.msg import Point32, Polygon |
| 27 | +from nav2_simple_commander.costmap_2d import PyCostmap2D |
| 28 | +from nav2_simple_commander.line_iterator import LineIterator |
| 29 | + |
| 30 | +NO_INFORMATION = 255 |
| 31 | +LETHAL_OBSTACLE = 254 |
| 32 | +INSCRIBED_INFLATED_OBSTACLE = 253 |
| 33 | +MAX_NON_OBSTACLE = 252 |
| 34 | +FREE_SPACE = 0 |
| 35 | + |
| 36 | + |
| 37 | +class FootprintCollisionChecker: |
| 38 | + """ |
| 39 | + FootprintCollisionChecker. |
| 40 | +
|
| 41 | + FootprintCollisionChecker Class for getting the cost |
| 42 | + and checking the collisions of a Footprint |
| 43 | + """ |
| 44 | + |
| 45 | + def __init__(self): |
| 46 | + """Initialize the FootprintCollisionChecker Object.""" |
| 47 | + self.costmap_ = None |
| 48 | + pass |
| 49 | + |
| 50 | + def footprintCost(self, footprint: Polygon): |
| 51 | + """ |
| 52 | + Iterate over all the points in a footprint and check for collision. |
| 53 | +
|
| 54 | + Args |
| 55 | + ---- |
| 56 | + footprint (Polygon): The footprint to calculate the collision cost for |
| 57 | +
|
| 58 | + Returns |
| 59 | + ------- |
| 60 | + LETHAL_OBSTACLE (int): If collision was found, 254 will be returned |
| 61 | + footprint_cost (float): The maximum cost found in the footprint points |
| 62 | +
|
| 63 | + """ |
| 64 | + footprint_cost = 0.0 |
| 65 | + x1 = 0.0 |
| 66 | + y1 = 0.0 |
| 67 | + |
| 68 | + x0, y0 = self.worldToMapValidated(footprint.points[0].x, footprint.points[0].y) |
| 69 | + |
| 70 | + if x0 is None or y0 is None: |
| 71 | + return LETHAL_OBSTACLE |
| 72 | + |
| 73 | + xstart = x0 |
| 74 | + ystart = y0 |
| 75 | + |
| 76 | + for i in range(len(footprint.points) - 1): |
| 77 | + x1, y1 = self.worldToMapValidated( |
| 78 | + footprint.points[i + 1].x, footprint.points[i + 1].y |
| 79 | + ) |
| 80 | + |
| 81 | + if x1 is None or y1 is None: |
| 82 | + return LETHAL_OBSTACLE |
| 83 | + |
| 84 | + footprint_cost = max(float(self.lineCost(x0, x1, y0, y1)), footprint_cost) |
| 85 | + x0 = x1 |
| 86 | + y0 = y1 |
| 87 | + |
| 88 | + if footprint_cost == LETHAL_OBSTACLE: |
| 89 | + return footprint_cost |
| 90 | + |
| 91 | + return max(float(self.lineCost(xstart, x1, ystart, y1)), footprint_cost) |
| 92 | + |
| 93 | + def lineCost(self, x0, x1, y0, y1, step_size=0.5): |
| 94 | + """ |
| 95 | + Iterate over all the points along a line and check for collision. |
| 96 | +
|
| 97 | + Args |
| 98 | + ---- |
| 99 | + x0 (float): Abscissa of the initial point in map coordinates |
| 100 | + y0 (float): Ordinate of the initial point in map coordinates |
| 101 | + x1 (float): Abscissa of the final point in map coordinates |
| 102 | + y1 (float): Ordinate of the final point in map coordinates |
| 103 | + step_size (float): Optional, Increments' resolution, defaults to 0.5 |
| 104 | +
|
| 105 | + Returns |
| 106 | + ------- |
| 107 | + LETHAL_OBSTACLE (int): If collision was found, 254 will be returned |
| 108 | + line_cost (float): The maximum cost found in the line points |
| 109 | +
|
| 110 | + """ |
| 111 | + line_cost = 0.0 |
| 112 | + point_cost = -1.0 |
| 113 | + line_iterator = LineIterator(x0, y0, x1, y1, step_size) |
| 114 | + |
| 115 | + while line_iterator.isValid(): |
| 116 | + point_cost = self.pointCost( |
| 117 | + int(line_iterator.getX()), int(line_iterator.getY()) |
| 118 | + ) |
| 119 | + |
| 120 | + if point_cost == LETHAL_OBSTACLE: |
| 121 | + return point_cost |
| 122 | + |
| 123 | + if line_cost < point_cost: |
| 124 | + line_cost = point_cost |
| 125 | + |
| 126 | + line_iterator.advance() |
| 127 | + |
| 128 | + return line_cost |
| 129 | + |
| 130 | + def worldToMapValidated(self, wx: float, wy: float): |
| 131 | + """ |
| 132 | + Get the map coordinate XY using world coordinate XY. |
| 133 | +
|
| 134 | + Args |
| 135 | + ---- |
| 136 | + wx (float): world coordinate X |
| 137 | + wy (float): world coordinate Y |
| 138 | +
|
| 139 | + Returns |
| 140 | + ------- |
| 141 | + None: if coordinates are invalid |
| 142 | + tuple of int: mx, my (if coordinates are valid) |
| 143 | + mx (int): map coordinate X |
| 144 | + my (int): map coordinate Y |
| 145 | +
|
| 146 | + """ |
| 147 | + if self.costmap_ is None: |
| 148 | + raise ValueError( |
| 149 | + 'Costmap not specified, use setCostmap to specify the costmap first' |
| 150 | + ) |
| 151 | + return self.costmap_.worldToMap(wx, wy) |
| 152 | + |
| 153 | + def pointCost(self, x: int, y: int): |
| 154 | + """ |
| 155 | + Get the cost of a point in the costmap using map coordinates XY. |
| 156 | +
|
| 157 | + Args |
| 158 | + ---- |
| 159 | + mx (int): map coordinate X |
| 160 | + my (int): map coordinate Y |
| 161 | +
|
| 162 | + Returns |
| 163 | + ------- |
| 164 | + np.uint8: cost of a point |
| 165 | +
|
| 166 | + """ |
| 167 | + if self.costmap_ is None: |
| 168 | + raise ValueError( |
| 169 | + 'Costmap not specified, use setCostmap to specify the costmap first' |
| 170 | + ) |
| 171 | + return self.costmap_.getCostXY(x, y) |
| 172 | + |
| 173 | + def setCostmap(self, costmap: PyCostmap2D): |
| 174 | + """ |
| 175 | + Specify which costmap to use. |
| 176 | +
|
| 177 | + Args |
| 178 | + ---- |
| 179 | + costmap (PyCostmap2D): costmap to use in the object's methods |
| 180 | +
|
| 181 | + Returns |
| 182 | + ------- |
| 183 | + None |
| 184 | +
|
| 185 | + """ |
| 186 | + self.costmap_ = costmap |
| 187 | + return None |
| 188 | + |
| 189 | + def footprintCostAtPose(self, x: float, y: float, theta: float, footprint: Polygon): |
| 190 | + """ |
| 191 | + Get the cost of a footprint at a specific Pose in map coordinates. |
| 192 | +
|
| 193 | + Args |
| 194 | + ---- |
| 195 | + x (float): map coordinate X |
| 196 | + y (float): map coordinate Y |
| 197 | + theta (float): absolute rotation angle of the footprint |
| 198 | + footprint (Polygon): the footprint to calculate its cost at the given Pose |
| 199 | +
|
| 200 | + Returns |
| 201 | + ------- |
| 202 | + LETHAL_OBSTACLE (int): If collision was found, 254 will be returned |
| 203 | + footprint_cost (float): The maximum cost found in the footprint points |
| 204 | +
|
| 205 | + """ |
| 206 | + cos_th = cos(theta) |
| 207 | + sin_th = sin(theta) |
| 208 | + oriented_footprint = Polygon() |
| 209 | + |
| 210 | + for i in range(len(footprint.points)): |
| 211 | + new_pt = Point32() |
| 212 | + new_pt.x = x + ( |
| 213 | + footprint.points[i].x * cos_th - footprint.points[i].y * sin_th |
| 214 | + ) |
| 215 | + new_pt.y = y + ( |
| 216 | + footprint.points[i].x * sin_th + footprint.points[i].y * cos_th |
| 217 | + ) |
| 218 | + oriented_footprint.points.append(new_pt) |
| 219 | + |
| 220 | + return self.footprintCost(oriented_footprint) |
0 commit comments