|  | 
|  | 1 | +""" | 
|  | 2 | +D* Lite grid planning | 
|  | 3 | +author: vss2sn ([email protected]) | 
|  | 4 | +Link to papers: | 
|  | 5 | +D* Lite (Link: http://idm-lab.org/bib/abstracts/papers/aaai02b.pd) | 
|  | 6 | +Improved Fast Replanning for Robot Navigation in Unknown Terrain | 
|  | 7 | +(Link: http://www.cs.cmu.edu/~maxim/files/dlite_icra02.pdf) | 
|  | 8 | +Implemented maintaining similarity with the pseudocode for understanding. | 
|  | 9 | +Code can be significantly optimized by using a priority queue for U, etc. | 
|  | 10 | +Avoiding additional imports based on repository philosophy. | 
|  | 11 | +""" | 
|  | 12 | +import math | 
|  | 13 | +import matplotlib.pyplot as plt | 
|  | 14 | +import random | 
|  | 15 | + | 
|  | 16 | +show_animation = True | 
|  | 17 | +pause_time = 0.001 | 
|  | 18 | +p_create_random_obstacle = 0 | 
|  | 19 | + | 
|  | 20 | + | 
|  | 21 | +class Node: | 
|  | 22 | +    def __init__(self, x: int = 0, y: int = 0, cost: float = 0.0): | 
|  | 23 | +        self.x = x | 
|  | 24 | +        self.y = y | 
|  | 25 | +        self.cost = cost | 
|  | 26 | + | 
|  | 27 | + | 
|  | 28 | +def add_coordinates(node1: Node, node2: Node): | 
|  | 29 | +    new_node = Node() | 
|  | 30 | +    new_node.x = node1.x + node2.x | 
|  | 31 | +    new_node.y = node1.y + node2.y | 
|  | 32 | +    new_node.cost = node1.cost + node2.cost | 
|  | 33 | +    return new_node | 
|  | 34 | + | 
|  | 35 | + | 
|  | 36 | +def compare_coordinates(node1: Node, node2: Node): | 
|  | 37 | +    return node1.x == node2.x and node1.y == node2.y | 
|  | 38 | + | 
|  | 39 | + | 
|  | 40 | +class DStarLite: | 
|  | 41 | + | 
|  | 42 | +    # Please adjust the heuristic function (h) if you change the list of | 
|  | 43 | +    # possible motions | 
|  | 44 | +    motions = [ | 
|  | 45 | +        Node(1, 0, 1), | 
|  | 46 | +        Node(0, 1, 1), | 
|  | 47 | +        Node(-1, 0, 1), | 
|  | 48 | +        Node(0, -1, 1), | 
|  | 49 | +        Node(1, 1, math.sqrt(2)), | 
|  | 50 | +        Node(1, -1, math.sqrt(2)), | 
|  | 51 | +        Node(-1, 1, math.sqrt(2)), | 
|  | 52 | +        Node(-1, -1, math.sqrt(2)) | 
|  | 53 | +    ] | 
|  | 54 | + | 
|  | 55 | +    def __init__(self, ox: list, oy: list): | 
|  | 56 | +        # Ensure that within the algorithm implementation all node coordinates | 
|  | 57 | +        # are indices in the grid and extend | 
|  | 58 | +        # from 0 to abs(<axis>_max - <axis>_min) | 
|  | 59 | +        self.x_min_world = int(min(ox)) | 
|  | 60 | +        self.y_min_world = int(min(oy)) | 
|  | 61 | +        self.x_max = int(abs(max(ox) - self.x_min_world)) | 
|  | 62 | +        self.y_max = int(abs(max(oy) - self.y_min_world)) | 
|  | 63 | +        self.obstacles = [Node(x - self.x_min_world, y - self.y_min_world) | 
|  | 64 | +                          for x, y in zip(ox, oy)] | 
|  | 65 | +        self.start = Node(0, 0) | 
|  | 66 | +        self.goal = Node(0, 0) | 
|  | 67 | +        self.U = list() | 
|  | 68 | +        self.km = 0.0 | 
|  | 69 | +        self.kold = 0.0 | 
|  | 70 | +        self.rhs = list() | 
|  | 71 | +        self.g = list() | 
|  | 72 | +        self.detected_obstacles = list() | 
|  | 73 | +        if show_animation: | 
|  | 74 | +            self.detected_obstacles_for_plotting_x = list() | 
|  | 75 | +            self.detected_obstacles_for_plotting_y = list() | 
|  | 76 | + | 
|  | 77 | +    def create_grid(self, val: float): | 
|  | 78 | +        grid = list() | 
|  | 79 | +        for _ in range(0, self.x_max): | 
|  | 80 | +            grid_row = list() | 
|  | 81 | +            for _ in range(0, self.y_max): | 
|  | 82 | +                grid_row.append(val) | 
|  | 83 | +            grid.append(grid_row) | 
|  | 84 | +        return grid | 
|  | 85 | + | 
|  | 86 | +    def is_obstacle(self, node: Node): | 
|  | 87 | +        return any([compare_coordinates(node, obstacle) | 
|  | 88 | +                    for obstacle in self.obstacles]) or \ | 
|  | 89 | +               any([compare_coordinates(node, obstacle) | 
|  | 90 | +                    for obstacle in self.detected_obstacles]) | 
|  | 91 | + | 
|  | 92 | +    def c(self, node1: Node, node2: Node): | 
|  | 93 | +        if self.is_obstacle(node2): | 
|  | 94 | +            # Attempting to move from or to an obstacle | 
|  | 95 | +            return math.inf | 
|  | 96 | +        new_node = Node(node1.x-node2.x, node1.y-node2.y) | 
|  | 97 | +        detected_motion = list(filter(lambda motion: | 
|  | 98 | +                                      compare_coordinates(motion, new_node), | 
|  | 99 | +                                      self.motions)) | 
|  | 100 | +        return detected_motion[0].cost | 
|  | 101 | + | 
|  | 102 | +    def h(self, s: Node): | 
|  | 103 | +        # Cannot use the 2nd euclidean norm as this might sometimes generate | 
|  | 104 | +        # heuristics that overestimate the cost, making them inadmissible, | 
|  | 105 | +        # due to rounding errors etc (when combined with calculate_key) | 
|  | 106 | +        # To be admissible heuristic should | 
|  | 107 | +        # never overestimate the cost of a move | 
|  | 108 | +        # hence not using the line below | 
|  | 109 | +        # return math.hypot(self.start.x - s.x, self.start.y - s.y) | 
|  | 110 | + | 
|  | 111 | +        # Below is the same as 1; modify if you modify the cost of each move in | 
|  | 112 | +        # motion | 
|  | 113 | +        # return max(abs(self.start.x - s.x), abs(self.start.y - s.y)) | 
|  | 114 | +        return 1 | 
|  | 115 | + | 
|  | 116 | +    def calculate_key(self, s: Node): | 
|  | 117 | +        return (min(self.g[s.x][s.y], self.rhs[s.x][s.y]) + self.h(s) | 
|  | 118 | +                + self.km, min(self.g[s.x][s.y], self.rhs[s.x][s.y])) | 
|  | 119 | + | 
|  | 120 | +    def is_valid(self, node: Node): | 
|  | 121 | +        if 0 <= node.x < self.x_max and 0 <= node.y < self.y_max: | 
|  | 122 | +            return True | 
|  | 123 | +        return False | 
|  | 124 | + | 
|  | 125 | +    def get_neighbours(self, u: Node): | 
|  | 126 | +        return [add_coordinates(u, motion) for motion in self.motions | 
|  | 127 | +                if self.is_valid(add_coordinates(u, motion))] | 
|  | 128 | + | 
|  | 129 | +    def pred(self, u: Node): | 
|  | 130 | +        # Grid, so each vertex is connected to the ones around it | 
|  | 131 | +        return self.get_neighbours(u) | 
|  | 132 | + | 
|  | 133 | +    def succ(self, u: Node): | 
|  | 134 | +        # Grid, so each vertex is connected to the ones around it | 
|  | 135 | +        return self.get_neighbours(u) | 
|  | 136 | + | 
|  | 137 | +    def initialize(self, start: Node, goal: Node): | 
|  | 138 | +        self.start.x = start.x - self.x_min_world | 
|  | 139 | +        self.start.y = start.y - self.y_min_world | 
|  | 140 | +        self.goal.x = goal.x - self.x_min_world | 
|  | 141 | +        self.goal.y = goal.y - self.y_min_world | 
|  | 142 | +        self.U = list()  # Would normally be a priority queue | 
|  | 143 | +        self.km = 0.0 | 
|  | 144 | +        self.rhs = self.create_grid(math.inf) | 
|  | 145 | +        self.g = self.create_grid(math.inf) | 
|  | 146 | +        self.rhs[self.goal.x][self.goal.y] = 0 | 
|  | 147 | +        self.U.append((self.goal, self.calculate_key(self.goal))) | 
|  | 148 | +        self.detected_obstacles = list() | 
|  | 149 | + | 
|  | 150 | +    def update_vertex(self, u: Node): | 
|  | 151 | +        if not compare_coordinates(u, self.goal): | 
|  | 152 | +            self.rhs[u.x][u.y] = min([self.c(u, sprime) + | 
|  | 153 | +                                      self.g[sprime.x][sprime.y] | 
|  | 154 | +                                      for sprime in self.succ(u)]) | 
|  | 155 | +        if any([compare_coordinates(u, node) for node, key in self.U]): | 
|  | 156 | +            self.U = [(node, key) for node, key in self.U | 
|  | 157 | +                      if not compare_coordinates(node, u)] | 
|  | 158 | +            self.U.sort(key=lambda x: x[1]) | 
|  | 159 | +        if self.g[u.x][u.y] != self.rhs[u.x][u.y]: | 
|  | 160 | +            self.U.append((u, self.calculate_key(u))) | 
|  | 161 | +            self.U.sort(key=lambda x: x[1]) | 
|  | 162 | + | 
|  | 163 | +    def compare_keys(self, key_pair1: tuple[float, float], | 
|  | 164 | +                     key_pair2: tuple[float, float]): | 
|  | 165 | +        return key_pair1[0] < key_pair2[0] or \ | 
|  | 166 | +               (key_pair1[0] == key_pair2[0] and key_pair1[1] < key_pair2[1]) | 
|  | 167 | + | 
|  | 168 | +    def compute_shortest_path(self): | 
|  | 169 | +        self.U.sort(key=lambda x: x[1]) | 
|  | 170 | +        while (len(self.U) > 0 and | 
|  | 171 | +               self.compare_keys(self.U[0][1], | 
|  | 172 | +                                 self.calculate_key(self.start))) or \ | 
|  | 173 | +                self.rhs[self.start.x][self.start.y] != \ | 
|  | 174 | +                self.g[self.start.x][self.start.y]: | 
|  | 175 | +            self.kold = self.U[0][1] | 
|  | 176 | +            u = self.U[0][0] | 
|  | 177 | +            self.U.pop(0) | 
|  | 178 | +            if self.compare_keys(self.kold, self.calculate_key(u)): | 
|  | 179 | +                self.U.append((u, self.calculate_key(u))) | 
|  | 180 | +                self.U.sort(key=lambda x: x[1]) | 
|  | 181 | +            elif self.g[u.x][u.y] > self.rhs[u.x][u.y]: | 
|  | 182 | +                self.g[u.x][u.y] = self.rhs[u.x][u.y] | 
|  | 183 | +                for s in self.pred(u): | 
|  | 184 | +                    self.update_vertex(s) | 
|  | 185 | +            else: | 
|  | 186 | +                self.g[u.x][u.y] = math.inf | 
|  | 187 | +                for s in self.pred(u) + [u]: | 
|  | 188 | +                    self.update_vertex(s) | 
|  | 189 | +            self.U.sort(key=lambda x: x[1]) | 
|  | 190 | + | 
|  | 191 | +    def detect_changes(self): | 
|  | 192 | +        changed_vertices = list() | 
|  | 193 | +        if len(self.spoofed_obstacles) > 0: | 
|  | 194 | +            for spoofed_obstacle in self.spoofed_obstacles[0]: | 
|  | 195 | +                if compare_coordinates(spoofed_obstacle, self.start) or \ | 
|  | 196 | +                   compare_coordinates(spoofed_obstacle, self.goal): | 
|  | 197 | +                    continue | 
|  | 198 | +                changed_vertices.append(spoofed_obstacle) | 
|  | 199 | +                self.detected_obstacles.append(spoofed_obstacle) | 
|  | 200 | +                if show_animation: | 
|  | 201 | +                    self.detected_obstacles_for_plotting_x.append( | 
|  | 202 | +                        spoofed_obstacle.x + self.x_min_world) | 
|  | 203 | +                    self.detected_obstacles_for_plotting_y.append( | 
|  | 204 | +                        spoofed_obstacle.y + self.y_min_world) | 
|  | 205 | +                    plt.plot(self.detected_obstacles_for_plotting_x, | 
|  | 206 | +                             self.detected_obstacles_for_plotting_y, ".k") | 
|  | 207 | +                    plt.pause(pause_time) | 
|  | 208 | +            self.spoofed_obstacles.pop(0) | 
|  | 209 | + | 
|  | 210 | +        # Allows random generation of obstacles | 
|  | 211 | +        random.seed() | 
|  | 212 | +        if random.random() > 1 - p_create_random_obstacle: | 
|  | 213 | +            x = random.randint(0, self.x_max) | 
|  | 214 | +            y = random.randint(0, self.y_max) | 
|  | 215 | +            new_obs = Node(x, y) | 
|  | 216 | +            if compare_coordinates(new_obs, self.start) or \ | 
|  | 217 | +               compare_coordinates(new_obs, self.goal): | 
|  | 218 | +                return changed_vertices | 
|  | 219 | +            changed_vertices.append(Node(x, y)) | 
|  | 220 | +            self.detected_obstacles.append(Node(x, y)) | 
|  | 221 | +            if show_animation: | 
|  | 222 | +                self.detected_obstacles_for_plotting_x.append(x + | 
|  | 223 | +                                                              self.x_min_world) | 
|  | 224 | +                self.detected_obstacles_for_plotting_y.append(y + | 
|  | 225 | +                                                              self.y_min_world) | 
|  | 226 | +                plt.plot(self.detected_obstacles_for_plotting_x, | 
|  | 227 | +                         self.detected_obstacles_for_plotting_y, ".k") | 
|  | 228 | +                plt.pause(pause_time) | 
|  | 229 | +        return changed_vertices | 
|  | 230 | + | 
|  | 231 | +    def compute_current_path(self): | 
|  | 232 | +        path = list() | 
|  | 233 | +        current_point = Node(self.start.x, self.start.y) | 
|  | 234 | +        while not compare_coordinates(current_point, self.goal): | 
|  | 235 | +            path.append(current_point) | 
|  | 236 | +            current_point = min(self.succ(current_point), | 
|  | 237 | +                                key=lambda sprime: | 
|  | 238 | +                                self.c(current_point, sprime) + | 
|  | 239 | +                                self.g[sprime.x][sprime.y]) | 
|  | 240 | +        path.append(self.goal) | 
|  | 241 | +        return path | 
|  | 242 | + | 
|  | 243 | +    def compare_paths(self, path1: list, path2: list): | 
|  | 244 | +        if len(path1) != len(path2): | 
|  | 245 | +            return False | 
|  | 246 | +        for node1, node2 in zip(path1, path2): | 
|  | 247 | +            if not compare_coordinates(node1, node2): | 
|  | 248 | +                return False | 
|  | 249 | +        return True | 
|  | 250 | + | 
|  | 251 | +    def display_path(self, path: list, colour: str, alpha: int = 1): | 
|  | 252 | +        px = [(node.x + self.x_min_world) for node in path] | 
|  | 253 | +        py = [(node.y + self.y_min_world) for node in path] | 
|  | 254 | +        drawing = plt.plot(px, py, colour, alpha=alpha) | 
|  | 255 | +        plt.pause(pause_time) | 
|  | 256 | +        return drawing | 
|  | 257 | + | 
|  | 258 | +    def main(self, start: Node, goal: Node, | 
|  | 259 | +             spoofed_ox: list, spoofed_oy: list): | 
|  | 260 | +        self.spoofed_obstacles = [[Node(x - self.x_min_world, | 
|  | 261 | +                                        y - self.y_min_world) | 
|  | 262 | +                                   for x, y in zip(rowx, rowy)] | 
|  | 263 | +                                  for rowx, rowy in zip(spoofed_ox, spoofed_oy) | 
|  | 264 | +                                  ] | 
|  | 265 | +        pathx = [] | 
|  | 266 | +        pathy = [] | 
|  | 267 | +        self.initialize(start, goal) | 
|  | 268 | +        last = self.start | 
|  | 269 | +        self.compute_shortest_path() | 
|  | 270 | +        pathx.append(self.start.x + self.x_min_world) | 
|  | 271 | +        pathy.append(self.start.y + self.y_min_world) | 
|  | 272 | + | 
|  | 273 | +        if show_animation: | 
|  | 274 | +            current_path = self.compute_current_path() | 
|  | 275 | +            previous_path = current_path.copy() | 
|  | 276 | +            previous_path_image = self.display_path(previous_path, ".c", | 
|  | 277 | +                                                    alpha=0.3) | 
|  | 278 | +            current_path_image = self.display_path(current_path, ".c") | 
|  | 279 | + | 
|  | 280 | +        while not compare_coordinates(self.goal, self.start): | 
|  | 281 | +            if self.g[self.start.x][self.start.y] == math.inf: | 
|  | 282 | +                print("No path possible") | 
|  | 283 | +                return False, pathx, pathy | 
|  | 284 | +            self.start = min(self.succ(self.start), | 
|  | 285 | +                             key=lambda sprime: | 
|  | 286 | +                             self.c(self.start, sprime) + | 
|  | 287 | +                             self.g[sprime.x][sprime.y]) | 
|  | 288 | +            pathx.append(self.start.x + self.x_min_world) | 
|  | 289 | +            pathy.append(self.start.y + self.y_min_world) | 
|  | 290 | +            if show_animation: | 
|  | 291 | +                current_path.pop(0) | 
|  | 292 | +                plt.plot(pathx, pathy, "-r") | 
|  | 293 | +                plt.pause(pause_time) | 
|  | 294 | +            changed_vertices = self.detect_changes() | 
|  | 295 | +            if len(changed_vertices) != 0: | 
|  | 296 | +                print("New obstacle detected") | 
|  | 297 | +                self.km += self.h(last) | 
|  | 298 | +                last = self.start | 
|  | 299 | +                for u in changed_vertices: | 
|  | 300 | +                    if compare_coordinates(u, self.start): | 
|  | 301 | +                        continue | 
|  | 302 | +                    self.rhs[u.x][u.y] = math.inf | 
|  | 303 | +                    self.g[u.x][u.y] = math.inf | 
|  | 304 | +                    self.update_vertex(u) | 
|  | 305 | +                self.compute_shortest_path() | 
|  | 306 | + | 
|  | 307 | +                if show_animation: | 
|  | 308 | +                    new_path = self.compute_current_path() | 
|  | 309 | +                    if not self.compare_paths(current_path, new_path): | 
|  | 310 | +                        current_path_image[0].remove() | 
|  | 311 | +                        previous_path_image[0].remove() | 
|  | 312 | +                        previous_path = current_path.copy() | 
|  | 313 | +                        current_path = new_path.copy() | 
|  | 314 | +                        previous_path_image = self.display_path(previous_path, | 
|  | 315 | +                                                                ".c", | 
|  | 316 | +                                                                alpha=0.3) | 
|  | 317 | +                        current_path_image = self.display_path(current_path, | 
|  | 318 | +                                                               ".c") | 
|  | 319 | +                        plt.pause(pause_time) | 
|  | 320 | +        print("Path found") | 
|  | 321 | +        return True, pathx, pathy | 
|  | 322 | + | 
|  | 323 | + | 
|  | 324 | +def main(): | 
|  | 325 | + | 
|  | 326 | +    # start and goal position | 
|  | 327 | +    sx = 10  # [m] | 
|  | 328 | +    sy = 10  # [m] | 
|  | 329 | +    gx = 50  # [m] | 
|  | 330 | +    gy = 50  # [m] | 
|  | 331 | + | 
|  | 332 | +    # set obstacle positions | 
|  | 333 | +    ox, oy = [], [] | 
|  | 334 | +    for i in range(-10, 60): | 
|  | 335 | +        ox.append(i) | 
|  | 336 | +        oy.append(-10.0) | 
|  | 337 | +    for i in range(-10, 60): | 
|  | 338 | +        ox.append(60.0) | 
|  | 339 | +        oy.append(i) | 
|  | 340 | +    for i in range(-10, 61): | 
|  | 341 | +        ox.append(i) | 
|  | 342 | +        oy.append(60.0) | 
|  | 343 | +    for i in range(-10, 61): | 
|  | 344 | +        ox.append(-10.0) | 
|  | 345 | +        oy.append(i) | 
|  | 346 | +    for i in range(-10, 40): | 
|  | 347 | +        ox.append(20.0) | 
|  | 348 | +        oy.append(i) | 
|  | 349 | +    for i in range(0, 40): | 
|  | 350 | +        ox.append(40.0) | 
|  | 351 | +        oy.append(60.0 - i) | 
|  | 352 | + | 
|  | 353 | +    if show_animation: | 
|  | 354 | +        plt.plot(ox, oy, ".k") | 
|  | 355 | +        plt.plot(sx, sy, "og") | 
|  | 356 | +        plt.plot(gx, gy, "xb") | 
|  | 357 | +        plt.grid(True) | 
|  | 358 | +        plt.axis("equal") | 
|  | 359 | +        label_column = ['Start', 'Goal', 'Path taken', | 
|  | 360 | +                        'Current computed path', 'Previous computed path', | 
|  | 361 | +                        'Obstacles'] | 
|  | 362 | +        columns = [plt.plot([], [], symbol, color=colour, alpha=alpha)[0] | 
|  | 363 | +                   for symbol, colour, alpha in [['o', 'g', 1], | 
|  | 364 | +                                                 ['x', 'b', 1], | 
|  | 365 | +                                                 ['-', 'r', 1], | 
|  | 366 | +                                                 ['.', 'c', 1], | 
|  | 367 | +                                                 ['.', 'c', 0.3], | 
|  | 368 | +                                                 ['.', 'k', 1]]] | 
|  | 369 | +        plt.legend(columns, label_column, bbox_to_anchor=(1, 1), title="Key:", | 
|  | 370 | +                   fontsize="xx-small") | 
|  | 371 | +        plt.plot() | 
|  | 372 | +        plt.pause(pause_time) | 
|  | 373 | + | 
|  | 374 | +    # Obstacles discovered at time = row | 
|  | 375 | +    # time = 1, obstacles discovered at (0, 2), (9, 2), (4, 0) | 
|  | 376 | +    # time = 2, obstacles discovered at (0, 1), (7, 7) | 
|  | 377 | +    # ... | 
|  | 378 | +    # when the spoofed obstacles are: | 
|  | 379 | +    # spoofed_ox = [[0, 9, 4], [0, 7], [], [], [], [], [], [5]] | 
|  | 380 | +    # spoofed_oy = [[2, 2, 0], [1, 7], [], [], [], [], [], [4]] | 
|  | 381 | + | 
|  | 382 | +    # Reroute | 
|  | 383 | +    # spoofed_ox = [[], [], [], [], [], [], [], [40 for _ in range(10, 21)]] | 
|  | 384 | +    # spoofed_oy = [[], [], [], [], [], [], [], [i for i in range(10, 21)]] | 
|  | 385 | + | 
|  | 386 | +    # Obstacles that demostrate large rerouting | 
|  | 387 | +    spoofed_ox = [[], [], [], | 
|  | 388 | +                  [i for i in range(0, 21)] + [0 for _ in range(0, 20)]] | 
|  | 389 | +    spoofed_oy = [[], [], [], | 
|  | 390 | +                  [20 for _ in range(0, 21)] + [i for i in range(0, 20)]] | 
|  | 391 | + | 
|  | 392 | +    dstarlite = DStarLite(ox, oy) | 
|  | 393 | +    dstarlite.main(Node(x=sx, y=sy), Node(x=gx, y=gy), | 
|  | 394 | +                   spoofed_ox=spoofed_ox, spoofed_oy=spoofed_oy) | 
|  | 395 | + | 
|  | 396 | + | 
|  | 397 | +if __name__ == "__main__": | 
|  | 398 | +    main() | 
0 commit comments