|
| 1 | +""" |
| 2 | +
|
| 3 | +Path planning code with LQR RRT* |
| 4 | +
|
| 5 | +author: AtsushiSakai(@Atsushi_twi) |
| 6 | +
|
| 7 | +""" |
| 8 | + |
| 9 | +import sys |
| 10 | +sys.path.append("../LQRPlanner/") |
| 11 | + |
| 12 | +import random |
| 13 | +import math |
| 14 | +import copy |
| 15 | +import numpy as np |
| 16 | +import matplotlib.pyplot as plt |
| 17 | +import LQRplanner |
| 18 | + |
| 19 | +show_animation = True |
| 20 | + |
| 21 | +LQRplanner.show_animation = False |
| 22 | + |
| 23 | +STEP_SIZE = 0.05 |
| 24 | + |
| 25 | + |
| 26 | +class RRT(): |
| 27 | + """ |
| 28 | + Class for RRT Planning |
| 29 | + """ |
| 30 | + |
| 31 | + def __init__(self, start, goal, obstacleList, randArea, |
| 32 | + goalSampleRate=10, maxIter=100): |
| 33 | + """ |
| 34 | + Setting Parameter |
| 35 | +
|
| 36 | + start:Start Position [x,y] |
| 37 | + goal:Goal Position [x,y] |
| 38 | + obstacleList:obstacle Positions [[x,y,size],...] |
| 39 | + randArea:Ramdom Samping Area [min,max] |
| 40 | +
|
| 41 | + """ |
| 42 | + self.start = Node(start[0], start[1]) |
| 43 | + self.end = Node(goal[0], goal[1]) |
| 44 | + self.minrand = randArea[0] |
| 45 | + self.maxrand = randArea[1] |
| 46 | + self.goalSampleRate = goalSampleRate |
| 47 | + self.maxIter = maxIter |
| 48 | + self.obstacleList = obstacleList |
| 49 | + |
| 50 | + def Planning(self, animation=True): |
| 51 | + """ |
| 52 | + Pathplanning |
| 53 | +
|
| 54 | + animation: flag for animation on or off |
| 55 | + """ |
| 56 | + |
| 57 | + self.nodeList = [self.start] |
| 58 | + for i in range(self.maxIter): |
| 59 | + rnd = self.get_random_point() |
| 60 | + nind = self.GetNearestListIndex(self.nodeList, rnd) |
| 61 | + |
| 62 | + newNode = self.steer(rnd, nind) |
| 63 | + if newNode is None: |
| 64 | + continue |
| 65 | + |
| 66 | + if self.CollisionCheck(newNode, self.obstacleList): |
| 67 | + nearinds = self.find_near_nodes(newNode) |
| 68 | + newNode = self.choose_parent(newNode, nearinds) |
| 69 | + if newNode is None: |
| 70 | + continue |
| 71 | + self.nodeList.append(newNode) |
| 72 | + self.rewire(newNode, nearinds) |
| 73 | + |
| 74 | + if animation and i % 5 == 0: |
| 75 | + self.DrawGraph(rnd=rnd) |
| 76 | + |
| 77 | + # generate coruse |
| 78 | + lastIndex = self.get_best_last_index() |
| 79 | + if lastIndex is None: |
| 80 | + return None |
| 81 | + path = self.gen_final_course(lastIndex) |
| 82 | + return path |
| 83 | + |
| 84 | + def choose_parent(self, newNode, nearinds): |
| 85 | + if len(nearinds) == 0: |
| 86 | + return newNode |
| 87 | + |
| 88 | + dlist = [] |
| 89 | + for i in nearinds: |
| 90 | + tNode = self.steer(newNode, i) |
| 91 | + if tNode is None: |
| 92 | + continue |
| 93 | + |
| 94 | + if self.CollisionCheck(tNode, self.obstacleList): |
| 95 | + dlist.append(tNode.cost) |
| 96 | + else: |
| 97 | + dlist.append(float("inf")) |
| 98 | + |
| 99 | + mincost = min(dlist) |
| 100 | + minind = nearinds[dlist.index(mincost)] |
| 101 | + |
| 102 | + if mincost == float("inf"): |
| 103 | + print("mincost is inf") |
| 104 | + return newNode |
| 105 | + |
| 106 | + newNode = self.steer(newNode, minind) |
| 107 | + |
| 108 | + return newNode |
| 109 | + |
| 110 | + def pi_2_pi(self, angle): |
| 111 | + while(angle > math.pi): |
| 112 | + angle = angle - 2.0 * math.pi |
| 113 | + |
| 114 | + while(angle < -math.pi): |
| 115 | + angle = angle + 2.0 * math.pi |
| 116 | + |
| 117 | + return angle |
| 118 | + |
| 119 | + def sample_path(self, wx, wy, step): |
| 120 | + |
| 121 | + px, py, clen = [], [], [] |
| 122 | + |
| 123 | + for i in range(len(wx) - 1): |
| 124 | + |
| 125 | + for t in np.arange(0.0, 1.0, step): |
| 126 | + px.append(t * wx[i + 1] + (1.0 - t) * wx[i]) |
| 127 | + py.append(t * wy[i + 1] + (1.0 - t) * wy[i]) |
| 128 | + |
| 129 | + dx = np.diff(px) |
| 130 | + dy = np.diff(py) |
| 131 | + |
| 132 | + clen = [math.sqrt(idx**2 + idy**2) for (idx, idy) in zip(dx, dy)] |
| 133 | + |
| 134 | + return px, py, clen |
| 135 | + |
| 136 | + def steer(self, rnd, nind): |
| 137 | + |
| 138 | + nearestNode = self.nodeList[nind] |
| 139 | + |
| 140 | + wx, wy = LQRplanner.LQRplanning( |
| 141 | + nearestNode.x, nearestNode.y, rnd.x, rnd.y) |
| 142 | + |
| 143 | + px, py, clen = self.sample_path(wx, wy, STEP_SIZE) |
| 144 | + |
| 145 | + if px is None: |
| 146 | + return None |
| 147 | + |
| 148 | + newNode = copy.deepcopy(nearestNode) |
| 149 | + newNode.x = px[-1] |
| 150 | + newNode.y = py[-1] |
| 151 | + |
| 152 | + newNode.path_x = px |
| 153 | + newNode.path_y = py |
| 154 | + newNode.cost += sum([abs(c) for c in clen]) |
| 155 | + newNode.parent = nind |
| 156 | + |
| 157 | + return newNode |
| 158 | + |
| 159 | + def get_random_point(self): |
| 160 | + |
| 161 | + if random.randint(0, 100) > self.goalSampleRate: |
| 162 | + rnd = [random.uniform(self.minrand, self.maxrand), |
| 163 | + random.uniform(self.minrand, self.maxrand), |
| 164 | + random.uniform(-math.pi, math.pi) |
| 165 | + ] |
| 166 | + else: # goal point sampling |
| 167 | + # print("goal sample") |
| 168 | + rnd = [self.end.x, self.end.y] |
| 169 | + |
| 170 | + node = Node(rnd[0], rnd[1]) |
| 171 | + |
| 172 | + return node |
| 173 | + |
| 174 | + def get_best_last_index(self): |
| 175 | + # print("get_best_last_index") |
| 176 | + |
| 177 | + XYTH = 0.5 |
| 178 | + |
| 179 | + goalinds = [] |
| 180 | + for (i, node) in enumerate(self.nodeList): |
| 181 | + if self.calc_dist_to_goal(node.x, node.y) <= XYTH: |
| 182 | + goalinds.append(i) |
| 183 | + |
| 184 | + if len(goalinds) == 0: |
| 185 | + return None |
| 186 | + |
| 187 | + mincost = min([self.nodeList[i].cost for i in goalinds]) |
| 188 | + for i in goalinds: |
| 189 | + if self.nodeList[i].cost == mincost: |
| 190 | + return i |
| 191 | + |
| 192 | + return None |
| 193 | + |
| 194 | + def gen_final_course(self, goalind): |
| 195 | + path = [[self.end.x, self.end.y]] |
| 196 | + while self.nodeList[goalind].parent is not None: |
| 197 | + node = self.nodeList[goalind] |
| 198 | + for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)): |
| 199 | + path.append([ix, iy]) |
| 200 | + # path.append([node.x, node.y]) |
| 201 | + goalind = node.parent |
| 202 | + path.append([self.start.x, self.start.y]) |
| 203 | + return path |
| 204 | + |
| 205 | + def calc_dist_to_goal(self, x, y): |
| 206 | + return np.linalg.norm([x - self.end.x, y - self.end.y]) |
| 207 | + |
| 208 | + def find_near_nodes(self, newNode): |
| 209 | + nnode = len(self.nodeList) |
| 210 | + r = 50.0 * math.sqrt((math.log(nnode) / nnode)) |
| 211 | + dlist = [(node.x - newNode.x) ** 2 + |
| 212 | + (node.y - newNode.y) ** 2 |
| 213 | + for node in self.nodeList] |
| 214 | + nearinds = [dlist.index(i) for i in dlist if i <= r ** 2] |
| 215 | + return nearinds |
| 216 | + |
| 217 | + def rewire(self, newNode, nearinds): |
| 218 | + |
| 219 | + nnode = len(self.nodeList) |
| 220 | + |
| 221 | + for i in nearinds: |
| 222 | + nearNode = self.nodeList[i] |
| 223 | + tNode = self.steer(nearNode, nnode - 1) |
| 224 | + if tNode is None: |
| 225 | + continue |
| 226 | + |
| 227 | + obstacleOK = self.CollisionCheck(tNode, self.obstacleList) |
| 228 | + imporveCost = nearNode.cost > tNode.cost |
| 229 | + |
| 230 | + if obstacleOK and imporveCost: |
| 231 | + # print("rewire") |
| 232 | + self.nodeList[i] = tNode |
| 233 | + |
| 234 | + def DrawGraph(self, rnd=None): |
| 235 | + """ |
| 236 | + Draw Graph |
| 237 | + """ |
| 238 | + plt.clf() |
| 239 | + if rnd is not None: |
| 240 | + plt.plot(rnd.x, rnd.y, "^k") |
| 241 | + for node in self.nodeList: |
| 242 | + if node.parent is not None: |
| 243 | + plt.plot(node.path_x, node.path_y, "-g") |
| 244 | + |
| 245 | + for (ox, oy, size) in self.obstacleList: |
| 246 | + plt.plot(ox, oy, "ok", ms=30 * size) |
| 247 | + |
| 248 | + plt.plot(self.start.x, self.start.y, "or") |
| 249 | + plt.plot(self.end.x, self.end.y, "or") |
| 250 | + |
| 251 | + plt.axis([-2, 15, -2, 15]) |
| 252 | + plt.grid(True) |
| 253 | + plt.pause(0.01) |
| 254 | + |
| 255 | + def GetNearestListIndex(self, nodeList, rnd): |
| 256 | + dlist = [(node.x - rnd.x) ** 2 + |
| 257 | + (node.y - rnd.y) ** 2 |
| 258 | + for node in nodeList] |
| 259 | + minind = dlist.index(min(dlist)) |
| 260 | + |
| 261 | + return minind |
| 262 | + |
| 263 | + def CollisionCheck(self, node, obstacleList): |
| 264 | + |
| 265 | + for (ox, oy, size) in obstacleList: |
| 266 | + for (ix, iy) in zip(node.path_x, node.path_y): |
| 267 | + dx = ox - ix |
| 268 | + dy = oy - iy |
| 269 | + d = dx * dx + dy * dy |
| 270 | + if d <= size ** 2: |
| 271 | + return False # collision |
| 272 | + |
| 273 | + return True # safe |
| 274 | + |
| 275 | + |
| 276 | +class Node(): |
| 277 | + """ |
| 278 | + RRT Node |
| 279 | + """ |
| 280 | + |
| 281 | + def __init__(self, x, y): |
| 282 | + self.x = x |
| 283 | + self.y = y |
| 284 | + self.path_x = [] |
| 285 | + self.path_y = [] |
| 286 | + self.cost = 0.0 |
| 287 | + self.parent = None |
| 288 | + |
| 289 | + |
| 290 | +def main(): |
| 291 | + print("Start rrt start planning") |
| 292 | + |
| 293 | + # ====Search Path with RRT==== |
| 294 | + obstacleList = [ |
| 295 | + (5, 5, 1), |
| 296 | + (4, 6, 1), |
| 297 | + (4, 7.5, 1), |
| 298 | + (4, 9, 1), |
| 299 | + (6, 5, 1), |
| 300 | + (7, 5, 1) |
| 301 | + ] # [x,y,size] |
| 302 | + |
| 303 | + # Set Initial parameters |
| 304 | + start = [0.0, 0.0] |
| 305 | + goal = [6.0, 7.0] |
| 306 | + |
| 307 | + rrt = RRT(start, goal, randArea=[-2.0, 15.0], obstacleList=obstacleList) |
| 308 | + path = rrt.Planning(animation=show_animation) |
| 309 | + |
| 310 | + # Draw final path |
| 311 | + if show_animation: |
| 312 | + rrt.DrawGraph() |
| 313 | + plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') |
| 314 | + plt.grid(True) |
| 315 | + plt.pause(0.001) |
| 316 | + plt.show() |
| 317 | + |
| 318 | + |
| 319 | +if __name__ == '__main__': |
| 320 | + main() |
0 commit comments