-
Notifications
You must be signed in to change notification settings - Fork 11
/
Copy pathrrtStar.py
200 lines (151 loc) · 5.91 KB
/
rrtStar.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
import os
import sys
import math
import numpy as np
import env, plotting, utils, queue
class Node:
def __init__(self, n):
self.x = n[0]
self.y = n[1]
self.parent = None
class RrtStar:
def __init__(
self, x_start, x_goal, step_len, goal_sample_rate, search_radius, iter_max
):
self.s_start = Node(x_start)
self.s_goal = Node(x_goal)
self.step_len = step_len
self.goal_sample_rate = goal_sample_rate
self.search_radius = search_radius
self.iter_max = iter_max
self.vertex = [self.s_start]
self.path = []
self.env = env.Env()
self.plotting = plotting.Plotting(x_start, x_goal)
self.utils = utils.Utils()
self.x_range = self.env.x_range
self.y_range = self.env.y_range
self.obs_circle = self.env.obs_circle
self.obs_rectangle = self.env.obs_rectangle
self.obs_boundary = self.env.obs_boundary
def planning(self):
for k in range(self.iter_max):
node_rand = self.generate_random_node(self.goal_sample_rate)
node_near = self.nearest_neighbor(self.vertex, node_rand)
node_new = self.new_state(node_near, node_rand)
if k % 2000 == 0:
print("rrtStar sampling iterations: ", k)
self.plotting.animation_online(self.vertex, "rrtStar", True)
if node_new and not self.utils.is_collision(node_near, node_new):
neighbor_index = self.find_near_neighbor(node_new)
self.vertex.append(node_new)
if neighbor_index:
self.choose_parent(node_new, neighbor_index)
self.rewire(node_new, neighbor_index)
index = self.search_goal_parent()
self.path = self.extract_path(self.vertex[index])
self.plotting.animation(
self.vertex, self.path, "rrt*, N = " + str(self.iter_max)
)
def new_state(self, node_start, node_goal):
dist, theta = self.get_distance_and_angle(node_start, node_goal)
dist = min(self.step_len, dist)
node_new = Node(
(
node_start.x + dist * math.cos(theta),
node_start.y + dist * math.sin(theta),
)
)
node_new.parent = node_start
return node_new
def choose_parent(self, node_new, neighbor_index):
cost = [self.get_new_cost(self.vertex[i], node_new) for i in neighbor_index]
cost_min_index = neighbor_index[int(np.argmin(cost))]
node_new.parent = self.vertex[cost_min_index]
def rewire(self, node_new, neighbor_index):
for i in neighbor_index:
node_neighbor = self.vertex[i]
if self.cost(node_neighbor) > self.get_new_cost(node_new, node_neighbor):
node_neighbor.parent = node_new
def search_goal_parent(self):
dist_list = [
math.hypot(n.x - self.s_goal.x, n.y - self.s_goal.y) for n in self.vertex
]
node_index = [i for i in range(len(dist_list)) if dist_list[i] <= self.step_len]
if len(node_index) > 0:
cost_list = [
dist_list[i] + self.cost(self.vertex[i])
for i in node_index
if not self.utils.is_collision(self.vertex[i], self.s_goal)
]
return node_index[int(np.argmin(cost_list))]
return len(self.vertex) - 1
def get_new_cost(self, node_start, node_end):
dist, _ = self.get_distance_and_angle(node_start, node_end)
return self.cost(node_start) + dist
def generate_random_node(self, goal_sample_rate):
delta = self.utils.delta
if np.random.random() > goal_sample_rate:
return Node(
(
np.random.uniform(self.x_range[0] + delta, self.x_range[1] - delta),
np.random.uniform(self.y_range[0] + delta, self.y_range[1] - delta),
)
)
return self.s_goal
def find_near_neighbor(self, node_new):
n = len(self.vertex) + 1
r = min(self.search_radius * math.sqrt((math.log(n) / n)), self.step_len)
dist_table = [
math.hypot(nd.x - node_new.x, nd.y - node_new.y) for nd in self.vertex
]
dist_table_index = [
ind
for ind in range(len(dist_table))
if dist_table[ind] <= r
and not self.utils.is_collision(node_new, self.vertex[ind])
]
return dist_table_index
@staticmethod
def nearest_neighbor(node_list, n):
return node_list[
int(np.argmin([math.hypot(nd.x - n.x, nd.y - n.y) for nd in node_list]))
]
@staticmethod
def cost(node_p):
node = node_p
cost = 0.0
while node.parent:
cost += math.hypot(node.x - node.parent.x, node.y - node.parent.y)
node = node.parent
return cost
def update_cost(self, parent_node):
OPEN = queue.QueueFIFO()
OPEN.put(parent_node)
while not OPEN.empty():
node = OPEN.get()
if len(node.child) == 0:
continue
for node_c in node.child:
node_c.Cost = self.get_new_cost(node, node_c)
OPEN.put(node_c)
def extract_path(self, node_end):
path = [[self.s_goal.x, self.s_goal.y]]
node = node_end
while node.parent is not None:
path.append([node.x, node.y])
node = node.parent
path.append([node.x, node.y])
return path
@staticmethod
def get_distance_and_angle(node_start, node_end):
dx = node_end.x - node_start.x
dy = node_end.y - node_start.y
return math.hypot(dx, dy), math.atan2(dy, dx)
def main():
x_start = (18, 8) # Starting node
x_goal = (37, 18) # Goal node
rrt_star = RrtStar(x_start, x_goal, 10, 0.10, 20, 5000)
rrt_star.planning()
if __name__ == "__main__":
main()