rrt_connect3D.py 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132
  1. # rrt connect algorithm
  2. """
  3. This is rrt connect implementation for 3D
  4. @author: yue qi
  5. """
  6. import numpy as np
  7. from numpy.matlib import repmat
  8. from collections import defaultdict
  9. import time
  10. import matplotlib.pyplot as plt
  11. import os
  12. import sys
  13. sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../../Sampling-based Planning/")
  14. from rrt_3D.env3D import env
  15. from rrt_3D.utils3D import getDist, sampleFree, nearest, steer, isCollide, near, visualization, cost, path, edgeset
  16. class rrt_connect():
  17. def __init__(self):
  18. self.env = env()
  19. self.Parent = {}
  20. self.V = []
  21. self.E = set()
  22. self.i = 0
  23. self.maxiter = 10000
  24. self.stepsize = 0.5
  25. self.Path = []
  26. self.done = False
  27. self.qinit = tuple(self.env.start)
  28. self.qgoal = tuple(self.env.goal)
  29. self.x0, self.xt = tuple(self.env.start), tuple(self.env.goal)
  30. self.qnew = None
  31. self.ind = 0
  32. self.fig = plt.figure(figsize=(10, 8))
  33. #----------Normal RRT algorithm
  34. def BUILD_RRT(self, qinit):
  35. tree = Tree(qinit)
  36. for k in range(self.maxiter):
  37. qrand = self.RANDOM_CONFIG()
  38. self.EXTEND(tree, qrand)
  39. return tree
  40. def EXTEND(self, tree, q):
  41. qnear = tuple(self.NEAREST_NEIGHBOR(q, tree))
  42. qnew, dist = steer(self, qnear, q)
  43. self.qnew = qnew # store qnew outside
  44. if self.NEW_CONFIG(q, qnear, qnew, dist=dist):
  45. tree.add_vertex(qnew)
  46. tree.add_edge(qnear, qnew)
  47. if qnew == q:
  48. return 'Reached'
  49. else:
  50. return 'Advanced'
  51. return 'Trapped'
  52. def NEAREST_NEIGHBOR(self, q, tree):
  53. # find the nearest neighbor in the tree
  54. V = np.array(tree.V)
  55. if len(V) == 1:
  56. return V[0]
  57. xr = repmat(q, len(V), 1)
  58. dists = np.linalg.norm(xr - V, axis=1)
  59. return tuple(tree.V[np.argmin(dists)])
  60. def RANDOM_CONFIG(self):
  61. return tuple(sampleFree(self))
  62. def NEW_CONFIG(self, q, qnear, qnew, dist = None):
  63. # to check if the new configuration is valid or not by
  64. # making a move is used for steer
  65. # check in bound
  66. collide, _ = isCollide(self, qnear, qnew, dist = dist)
  67. return not collide
  68. #----------RRT connect algorithm
  69. def CONNECT(self, Tree, q):
  70. print('in connect')
  71. while True:
  72. S = self.EXTEND(Tree, q)
  73. if S != 'Advanced':
  74. break
  75. return S
  76. def RRT_CONNECT_PLANNER(self, qinit, qgoal):
  77. Tree_A = Tree(qinit)
  78. Tree_B = Tree(qgoal)
  79. for k in range(self.maxiter):
  80. print(k)
  81. qrand = self.RANDOM_CONFIG()
  82. if self.EXTEND(Tree_A, qrand) != 'Trapped':
  83. print('trapped')
  84. qnew = self.qnew # get qnew from outside
  85. if self.CONNECT(Tree_B, qnew) == 'Reached':
  86. print('reached')
  87. # return self.PATH(Tree_A, Tree_B)
  88. return
  89. Tree_A, Tree_B = self.SWAP(Tree_A, Tree_B)
  90. print('Failure')
  91. return 'Failure'
  92. # def PATH(self, tree_a, tree_b):
  93. def SWAP(self, tree_a, tree_b):
  94. tree_a, tree_b = tree_b, tree_a
  95. return tree_a, tree_b
  96. class Tree():
  97. def __init__(self, node):
  98. self.V = []
  99. self.Parent = {}
  100. self.V.append(node)
  101. self.Parent[node] = None
  102. def add_vertex(self, node):
  103. if node not in self.V:
  104. self.V.append(node)
  105. def add_edge(self, parent, child):
  106. # here edge is defined a tuple of (parent, child) (qnear, qnew)
  107. self.Parent[child] = parent
  108. if __name__ == '__main__':
  109. p = rrt_connect()
  110. starttime = time.time()
  111. p.RRT_CONNECT_PLANNER(p.qinit, p.qgoal)
  112. print('time used = ' + str(time.time() - starttime))