Skip to content

Commit f00e8db

Browse files
committed
add test and code clean up
1 parent a8bd1c7 commit f00e8db

4 files changed

Lines changed: 37 additions & 15 deletions

File tree

File renamed without changes.

PathPlanning/RRTStarCar/rrt_star_car.py renamed to PathPlanning/RRTStarDubins/rrt_star_dubins.py

Lines changed: 22 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,9 @@
1010
import copy
1111
import numpy as np
1212
import dubins_path_planning
13+
import matplotlib.pyplot as plt
14+
15+
show_animation = True
1316

1417

1518
class RRT():
@@ -18,7 +21,7 @@ class RRT():
1821
"""
1922

2023
def __init__(self, start, goal, obstacleList, randArea,
21-
goalSampleRate=10, maxIter=1000):
24+
goalSampleRate=10, maxIter=100):
2225
"""
2326
Setting Parameter
2427
@@ -34,6 +37,7 @@ def __init__(self, start, goal, obstacleList, randArea,
3437
self.maxrand = randArea[1]
3538
self.goalSampleRate = goalSampleRate
3639
self.maxIter = maxIter
40+
self.obstacleList = obstacleList
3741

3842
def Planning(self, animation=True):
3943
"""
@@ -50,7 +54,7 @@ def Planning(self, animation=True):
5054
newNode = self.steer(rnd, nind)
5155
# print(newNode.cost)
5256

53-
if self.CollisionCheck(newNode, obstacleList):
57+
if self.CollisionCheck(newNode, self.obstacleList):
5458
nearinds = self.find_near_nodes(newNode)
5559
newNode = self.choose_parent(newNode, nearinds)
5660
self.nodeList.append(newNode)
@@ -72,7 +76,7 @@ def choose_parent(self, newNode, nearinds):
7276
dlist = []
7377
for i in nearinds:
7478
tNode = self.steer(newNode, i)
75-
if self.CollisionCheck(tNode, obstacleList):
79+
if self.CollisionCheck(tNode, self.obstacleList):
7680
dlist.append(tNode.cost)
7781
else:
7882
dlist.append(float("inf"))
@@ -190,7 +194,7 @@ def rewire(self, newNode, nearinds):
190194
nearNode = self.nodeList[i]
191195
tNode = self.steer(nearNode, nnode - 1)
192196

193-
obstacleOK = self.CollisionCheck(tNode, obstacleList)
197+
obstacleOK = self.CollisionCheck(tNode, self.obstacleList)
194198
imporveCost = nearNode.cost > tNode.cost
195199

196200
if obstacleOK and imporveCost:
@@ -201,7 +205,6 @@ def DrawGraph(self, rnd=None):
201205
u"""
202206
Draw Graph
203207
"""
204-
import matplotlib.pyplot as plt
205208
plt.clf()
206209
if rnd is not None:
207210
plt.plot(rnd.x, rnd.y, "^k")
@@ -211,7 +214,7 @@ def DrawGraph(self, rnd=None):
211214
# plt.plot([node.x, self.nodeList[node.parent].x], [
212215
# node.y, self.nodeList[node.parent].y], "-g")
213216

214-
for (ox, oy, size) in obstacleList:
217+
for (ox, oy, size) in self.obstacleList:
215218
plt.plot(ox, oy, "ok", ms=30 * size)
216219

217220
dubins_path_planning.plot_arrow(
@@ -263,9 +266,8 @@ def __init__(self, x, y, yaw):
263266
self.parent = None
264267

265268

266-
if __name__ == '__main__':
267-
print("Start rrt start planning")
268-
import matplotlib.pyplot as plt
269+
def main():
270+
print("Start rrt star with dubins planning")
269271

270272
# ====Search Path with RRT====
271273
obstacleList = [
@@ -282,12 +284,17 @@ def __init__(self, x, y, yaw):
282284
goal = [10.0, 10.0, math.radians(0.0)]
283285

284286
rrt = RRT(start, goal, randArea=[-2.0, 15.0], obstacleList=obstacleList)
285-
path = rrt.Planning(animation=True)
287+
path = rrt.Planning(animation=show_animation)
286288

287289
# Draw final path
288-
rrt.DrawGraph()
289-
plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
290-
plt.grid(True)
291-
plt.pause(0.001)
290+
if show_animation:
291+
rrt.DrawGraph()
292+
plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r')
293+
plt.grid(True)
294+
plt.pause(0.001)
292295

293-
plt.show()
296+
plt.show()
297+
298+
299+
if __name__ == '__main__':
300+
main()

tests/test_rrt_star_dubins.py

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
from unittest import TestCase
2+
3+
import sys
4+
sys.path.append("./PathPlanning/RRTStarDubins/")
5+
6+
from PathPlanning.RRTStarDubins import rrt_star_dubins as m
7+
8+
print(__file__)
9+
10+
11+
class Test(TestCase):
12+
13+
def test1(self):
14+
m.show_animation = False
15+
m.main()

0 commit comments

Comments
 (0)