|
| 1 | +""" |
| 2 | +Path planning Sample Code with RRT* |
| 3 | +
|
| 4 | +author: Atsushi Sakai(@Atsushi_twi) |
| 5 | +
|
| 6 | +""" |
| 7 | + |
| 8 | +import copy |
| 9 | +import math |
| 10 | +import random |
| 11 | + |
| 12 | +import matplotlib.pyplot as plt |
| 13 | +import numpy as np |
| 14 | + |
| 15 | +show_animation = True |
| 16 | + |
| 17 | + |
| 18 | +class RRTStar: |
| 19 | + """ |
| 20 | + Class for RRT planning |
| 21 | + """ |
| 22 | + |
| 23 | + class Node: |
| 24 | + |
| 25 | + def __init__(self, x, y): |
| 26 | + self.x = x |
| 27 | + self.y = y |
| 28 | + self.cost = 0.0 |
| 29 | + self.parent = None |
| 30 | + |
| 31 | + def __init__(self, start, goal, obstacle_list, rand_area, |
| 32 | + expand_dis=0.5, |
| 33 | + goal_sample_rate=20, |
| 34 | + max_iter=500, |
| 35 | + connect_circle_dist=50.0 |
| 36 | + ): |
| 37 | + """ |
| 38 | + Setting Parameter |
| 39 | +
|
| 40 | + start:Start Position [x,y] |
| 41 | + goal:Goal Position [x,y] |
| 42 | + obstacleList:obstacle Positions [[x,y,size],...] |
| 43 | + randArea:Random Sampling Area [min,max] |
| 44 | +
|
| 45 | + """ |
| 46 | + self.connect_circle_dist = connect_circle_dist |
| 47 | + self.start = self.Node(start[0], start[1]) |
| 48 | + self.end = self.Node(goal[0], goal[1]) |
| 49 | + self.min_rand = rand_area[0] |
| 50 | + self.max_rand = rand_area[1] |
| 51 | + self.expandDis = expand_dis |
| 52 | + self.goalSampleRate = goal_sample_rate |
| 53 | + self.maxIter = max_iter |
| 54 | + self.obstacleList = obstacle_list |
| 55 | + self.node_list = [] |
| 56 | + |
| 57 | + def planning(self, animation=True, search_until_maxiter=True): |
| 58 | + """ |
| 59 | + rrt path planning |
| 60 | +
|
| 61 | + animation: flag for animation on or off |
| 62 | + search_until_maxiter: search until max iteration for path improving or not |
| 63 | + """ |
| 64 | + |
| 65 | + self.node_list = [self.start] |
| 66 | + for i in range(self.maxIter): |
| 67 | + rnd = self.get_random_point() |
| 68 | + nearest_ind = self.get_nearest_list_index(self.node_list, rnd) |
| 69 | + |
| 70 | + new_node = self.steer(rnd, self.node_list[nearest_ind]) |
| 71 | + |
| 72 | + if self.check_collision(new_node, self.obstacleList): |
| 73 | + near_inds = self.find_near_nodes(new_node) |
| 74 | + new_node = self.choose_parent(new_node, near_inds) |
| 75 | + if new_node: |
| 76 | + self.node_list.append(new_node) |
| 77 | + self.rewire(new_node, near_inds) |
| 78 | + |
| 79 | + if animation and i % 5 == 0: |
| 80 | + self.draw_graph(rnd) |
| 81 | + |
| 82 | + if not search_until_maxiter: # check reaching the goal |
| 83 | + d, _ = self.calc_distance_and_angle(new_node, self.end) |
| 84 | + if d <= self.expandDis: |
| 85 | + return self.gen_final_course(len(self.node_list) - 1) |
| 86 | + |
| 87 | + print("reached max iteration") |
| 88 | + |
| 89 | + last_index = self.search_best_goal_node() |
| 90 | + if last_index: |
| 91 | + return self.gen_final_course(last_index) |
| 92 | + |
| 93 | + return None |
| 94 | + |
| 95 | + def choose_parent(self, new_node, near_inds): |
| 96 | + if not near_inds: |
| 97 | + return None |
| 98 | + |
| 99 | + # search nearest cost in near_inds |
| 100 | + costs = [] |
| 101 | + for i in near_inds: |
| 102 | + d, theta = self.calc_distance_and_angle(self.node_list[i], new_node) |
| 103 | + if self.check_collision_extend(self.node_list[i], theta, d): |
| 104 | + costs.append(self.node_list[i].cost + d) |
| 105 | + else: |
| 106 | + costs.append(float("inf")) # the cost of collision node |
| 107 | + min_cost = min(costs) |
| 108 | + |
| 109 | + if min_cost == float("inf"): |
| 110 | + print("There is no good path.(min_cost is inf)") |
| 111 | + return None |
| 112 | + |
| 113 | + new_node.cost = min_cost |
| 114 | + min_ind = near_inds[costs.index(min_cost)] |
| 115 | + new_node.parent = self.node_list[min_ind] |
| 116 | + |
| 117 | + return new_node |
| 118 | + |
| 119 | + def steer(self, rnd, nearest_node): |
| 120 | + new_node = self.Node(rnd[0], rnd[1]) |
| 121 | + d, theta = self.calc_distance_and_angle(nearest_node, new_node) |
| 122 | + if d > self.expandDis: |
| 123 | + new_node.x = nearest_node.x + self.expandDis * math.cos(theta) |
| 124 | + new_node.y = nearest_node.y + self.expandDis * math.sin(theta) |
| 125 | + new_node.cost = float("inf") |
| 126 | + return new_node |
| 127 | + |
| 128 | + def get_random_point(self): |
| 129 | + |
| 130 | + if random.randint(0, 100) > self.goalSampleRate: |
| 131 | + rnd = [random.uniform(self.min_rand, self.max_rand), |
| 132 | + random.uniform(self.min_rand, self.max_rand)] |
| 133 | + else: # goal point sampling |
| 134 | + rnd = [self.end.x, self.end.y] |
| 135 | + |
| 136 | + return rnd |
| 137 | + |
| 138 | + def search_best_goal_node(self): |
| 139 | + dist_to_goal_list = [self.calc_dist_to_goal(n.x, n.y) for n in self.node_list] |
| 140 | + goal_inds = [dist_to_goal_list.index(i) for i in dist_to_goal_list if i <= self.expandDis] |
| 141 | + |
| 142 | + if not goal_inds: |
| 143 | + return None |
| 144 | + |
| 145 | + min_cost = min([self.node_list[i].cost for i in goal_inds]) |
| 146 | + for i in goal_inds: |
| 147 | + if self.node_list[i].cost == min_cost: |
| 148 | + return i |
| 149 | + |
| 150 | + return None |
| 151 | + |
| 152 | + def gen_final_course(self, goal_ind): |
| 153 | + path = [[self.end.x, self.end.y]] |
| 154 | + node = self.node_list[goal_ind] |
| 155 | + while node.parent is not None: |
| 156 | + path.append([node.x, node.y]) |
| 157 | + node = node.parent |
| 158 | + path.append([node.x, node.y]) |
| 159 | + |
| 160 | + return path |
| 161 | + |
| 162 | + def calc_dist_to_goal(self, x, y): |
| 163 | + return np.linalg.norm([x - self.end.x, y - self.end.y]) |
| 164 | + |
| 165 | + def find_near_nodes(self, new_node): |
| 166 | + nnode = len(self.node_list) + 1 |
| 167 | + r = self.connect_circle_dist * math.sqrt((math.log(nnode) / nnode)) |
| 168 | + dist_list = [(node.x - new_node.x) ** 2 + |
| 169 | + (node.y - new_node.y) ** 2 for node in self.node_list] |
| 170 | + near_inds = [dist_list.index(i) for i in dist_list if i <= r ** 2] |
| 171 | + return near_inds |
| 172 | + |
| 173 | + def rewire(self, new_node, near_inds): |
| 174 | + for i in near_inds: |
| 175 | + near_node = self.node_list[i] |
| 176 | + d, theta = self.calc_distance_and_angle(near_node, new_node) |
| 177 | + new_cost = new_node.cost + d |
| 178 | + |
| 179 | + if near_node.cost > new_cost: |
| 180 | + if self.check_collision_extend(near_node, theta, d): |
| 181 | + near_node.parent = new_node |
| 182 | + near_node.cost = new_cost |
| 183 | + self.propagate_cost_to_leaves(new_node) |
| 184 | + |
| 185 | + def propagate_cost_to_leaves(self, parent_node): |
| 186 | + for node in self.node_list: |
| 187 | + if node.parent == parent_node: |
| 188 | + d, _ = self.calc_distance_and_angle(parent_node, node) |
| 189 | + node.cost = parent_node.cost + d |
| 190 | + self.propagate_cost_to_leaves(node) |
| 191 | + |
| 192 | + def check_collision_extend(self, near_node, theta, d): |
| 193 | + |
| 194 | + tmp_node = copy.deepcopy(near_node) |
| 195 | + |
| 196 | + for i in range(int(d / self.expandDis)): |
| 197 | + tmp_node.x += self.expandDis * math.cos(theta) |
| 198 | + tmp_node.y += self.expandDis * math.sin(theta) |
| 199 | + if not self.check_collision(tmp_node, self.obstacleList): |
| 200 | + return False |
| 201 | + |
| 202 | + return True |
| 203 | + |
| 204 | + def draw_graph(self, rnd=None): |
| 205 | + plt.clf() |
| 206 | + if rnd is not None: |
| 207 | + plt.plot(rnd[0], rnd[1], "^k") |
| 208 | + for node in self.node_list: |
| 209 | + if node.parent is not None: |
| 210 | + plt.plot([node.x, node.parent.x], |
| 211 | + [node.y, node.parent.y], |
| 212 | + "-g") |
| 213 | + |
| 214 | + for (ox, oy, size) in self.obstacleList: |
| 215 | + plt.plot(ox, oy, "ok", ms=30 * size) |
| 216 | + |
| 217 | + plt.plot(self.start.x, self.start.y, "xr") |
| 218 | + plt.plot(self.end.x, self.end.y, "xr") |
| 219 | + plt.axis([-2, 15, -2, 15]) |
| 220 | + plt.grid(True) |
| 221 | + plt.pause(0.01) |
| 222 | + |
| 223 | + @staticmethod |
| 224 | + def get_nearest_list_index(node_list, rnd): |
| 225 | + dlist = [(node.x - rnd[0]) ** 2 + (node.y - rnd[1]) |
| 226 | + ** 2 for node in node_list] |
| 227 | + minind = dlist.index(min(dlist)) |
| 228 | + |
| 229 | + return minind |
| 230 | + |
| 231 | + @staticmethod |
| 232 | + def check_collision(node, obstacleList): |
| 233 | + for (ox, oy, size) in obstacleList: |
| 234 | + dx = ox - node.x |
| 235 | + dy = oy - node.y |
| 236 | + d = dx * dx + dy * dy |
| 237 | + if d <= size ** 2: |
| 238 | + return False # collision |
| 239 | + |
| 240 | + return True # safe |
| 241 | + |
| 242 | + @staticmethod |
| 243 | + def calc_distance_and_angle(from_node, to_node): |
| 244 | + dx = to_node.x - from_node.x |
| 245 | + dy = to_node.y - from_node.y |
| 246 | + d = math.sqrt(dx ** 2 + dy ** 2) |
| 247 | + theta = math.atan2(dy, dx) |
| 248 | + return d, theta |
| 249 | + |
| 250 | + |
| 251 | +def main(): |
| 252 | + print("Start " + __file__) |
| 253 | + |
| 254 | + # ====Search Path with RRT==== |
| 255 | + obstacle_list = [ |
| 256 | + (5, 5, 1), |
| 257 | + (3, 6, 2), |
| 258 | + (3, 8, 2), |
| 259 | + (3, 10, 2), |
| 260 | + (7, 5, 2), |
| 261 | + (9, 5, 2) |
| 262 | + ] # [x,y,size(radius)] |
| 263 | + |
| 264 | + # Set Initial parameters |
| 265 | + rrt = RRTStar(start=[0, 0], |
| 266 | + goal=[10, 10], |
| 267 | + rand_area=[-2, 15], |
| 268 | + obstacle_list=obstacle_list) |
| 269 | + path = rrt.planning(animation=show_animation, search_until_maxiter=False) |
| 270 | + |
| 271 | + if path is None: |
| 272 | + print("Cannot find path") |
| 273 | + else: |
| 274 | + print("found path!!") |
| 275 | + |
| 276 | + # Draw final path |
| 277 | + if show_animation: |
| 278 | + rrt.draw_graph() |
| 279 | + plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') |
| 280 | + plt.grid(True) |
| 281 | + plt.pause(0.01) # Need for Mac |
| 282 | + plt.show() |
| 283 | + |
| 284 | + |
| 285 | +if __name__ == '__main__': |
| 286 | + main() |
0 commit comments