dubins_path.py 9.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351
  1. """
  2. Dubins Path
  3. """
  4. import math
  5. import numpy as np
  6. import matplotlib.pyplot as plt
  7. from scipy.spatial.transform import Rotation as Rot
  8. import CurvesGenerator.draw as draw
  9. # class for PATH element
  10. class PATH:
  11. def __init__(self, L, mode, x, y, yaw):
  12. self.L = L # total path length [float]
  13. self.mode = mode # type of each part of the path [string]
  14. self.x = x # final s positions [m]
  15. self.y = y # final y positions [m]
  16. self.yaw = yaw # final yaw angles [rad]
  17. # utils
  18. def pi_2_pi(theta):
  19. while theta > math.pi:
  20. theta -= 2.0 * math.pi
  21. while theta < -math.pi:
  22. theta += 2.0 * math.pi
  23. return theta
  24. def mod2pi(theta):
  25. return theta - 2.0 * math.pi * math.floor(theta / math.pi / 2.0)
  26. def LSL(alpha, beta, dist):
  27. sin_a = math.sin(alpha)
  28. sin_b = math.sin(beta)
  29. cos_a = math.cos(alpha)
  30. cos_b = math.cos(beta)
  31. cos_a_b = math.cos(alpha - beta)
  32. p_lsl = 2 + dist ** 2 - 2 * cos_a_b + 2 * dist * (sin_a - sin_b)
  33. if p_lsl < 0:
  34. return None, None, None, ["L", "S", "L"]
  35. else:
  36. p_lsl = math.sqrt(p_lsl)
  37. denominate = dist + sin_a - sin_b
  38. t_lsl = mod2pi(-alpha + math.atan2(cos_b - cos_a, denominate))
  39. q_lsl = mod2pi(beta - math.atan2(cos_b - cos_a, denominate))
  40. return t_lsl, p_lsl, q_lsl, ["L", "S", "L"]
  41. def RSR(alpha, beta, dist):
  42. sin_a = math.sin(alpha)
  43. sin_b = math.sin(beta)
  44. cos_a = math.cos(alpha)
  45. cos_b = math.cos(beta)
  46. cos_a_b = math.cos(alpha - beta)
  47. p_rsr = 2 + dist ** 2 - 2 * cos_a_b + 2 * dist * (sin_b - sin_a)
  48. if p_rsr < 0:
  49. return None, None, None, ["R", "S", "R"]
  50. else:
  51. p_rsr = math.sqrt(p_rsr)
  52. denominate = dist - sin_a + sin_b
  53. t_rsr = mod2pi(alpha - math.atan2(cos_a - cos_b, denominate))
  54. q_rsr = mod2pi(-beta + math.atan2(cos_a - cos_b, denominate))
  55. return t_rsr, p_rsr, q_rsr, ["R", "S", "R"]
  56. def LSR(alpha, beta, dist):
  57. sin_a = math.sin(alpha)
  58. sin_b = math.sin(beta)
  59. cos_a = math.cos(alpha)
  60. cos_b = math.cos(beta)
  61. cos_a_b = math.cos(alpha - beta)
  62. p_lsr = -2 + dist ** 2 + 2 * cos_a_b + 2 * dist * (sin_a + sin_b)
  63. if p_lsr < 0:
  64. return None, None, None, ["L", "S", "R"]
  65. else:
  66. p_lsr = math.sqrt(p_lsr)
  67. rec = math.atan2(-cos_a - cos_b, dist + sin_a + sin_b) - math.atan2(-2.0, p_lsr)
  68. t_lsr = mod2pi(-alpha + rec)
  69. q_lsr = mod2pi(-mod2pi(beta) + rec)
  70. return t_lsr, p_lsr, q_lsr, ["L", "S", "R"]
  71. def RSL(alpha, beta, dist):
  72. sin_a = math.sin(alpha)
  73. sin_b = math.sin(beta)
  74. cos_a = math.cos(alpha)
  75. cos_b = math.cos(beta)
  76. cos_a_b = math.cos(alpha - beta)
  77. p_rsl = -2 + dist ** 2 + 2 * cos_a_b - 2 * dist * (sin_a + sin_b)
  78. if p_rsl < 0:
  79. return None, None, None, ["R", "S", "L"]
  80. else:
  81. p_rsl = math.sqrt(p_rsl)
  82. rec = math.atan2(cos_a + cos_b, dist - sin_a - sin_b) - math.atan2(2.0, p_rsl)
  83. t_rsl = mod2pi(alpha - rec)
  84. q_rsl = mod2pi(beta - rec)
  85. return t_rsl, p_rsl, q_rsl, ["R", "S", "L"]
  86. def RLR(alpha, beta, dist):
  87. sin_a = math.sin(alpha)
  88. sin_b = math.sin(beta)
  89. cos_a = math.cos(alpha)
  90. cos_b = math.cos(beta)
  91. cos_a_b = math.cos(alpha - beta)
  92. rec = (6.0 - dist ** 2 + 2.0 * cos_a_b + 2.0 * dist * (sin_a - sin_b)) / 8.0
  93. if abs(rec) > 1.0:
  94. return None, None, None, ["R", "L", "R"]
  95. p_rlr = mod2pi(2 * math.pi - math.acos(rec))
  96. t_rlr = mod2pi(alpha - math.atan2(cos_a - cos_b, dist - sin_a + sin_b) + mod2pi(p_rlr / 2.0))
  97. q_rlr = mod2pi(alpha - beta - t_rlr + mod2pi(p_rlr))
  98. return t_rlr, p_rlr, q_rlr, ["R", "L", "R"]
  99. def LRL(alpha, beta, dist):
  100. sin_a = math.sin(alpha)
  101. sin_b = math.sin(beta)
  102. cos_a = math.cos(alpha)
  103. cos_b = math.cos(beta)
  104. cos_a_b = math.cos(alpha - beta)
  105. rec = (6.0 - dist ** 2 + 2.0 * cos_a_b + 2.0 * dist * (sin_b - sin_a)) / 8.0
  106. if abs(rec) > 1.0:
  107. return None, None, None, ["L", "R", "L"]
  108. p_lrl = mod2pi(2 * math.pi - math.acos(rec))
  109. t_lrl = mod2pi(-alpha - math.atan2(cos_a - cos_b, dist + sin_a - sin_b) + p_lrl / 2.0)
  110. q_lrl = mod2pi(mod2pi(beta) - alpha - t_lrl + mod2pi(p_lrl))
  111. return t_lrl, p_lrl, q_lrl, ["L", "R", "L"]
  112. def interpolate(ind, l, m, maxc, ox, oy, oyaw, px, py, pyaw, directions):
  113. if m == "S":
  114. px[ind] = ox + l / maxc * math.cos(oyaw)
  115. py[ind] = oy + l / maxc * math.sin(oyaw)
  116. pyaw[ind] = oyaw
  117. else:
  118. ldx = math.sin(l) / maxc
  119. if m == "L":
  120. ldy = (1.0 - math.cos(l)) / maxc
  121. elif m == "R":
  122. ldy = (1.0 - math.cos(l)) / (-maxc)
  123. gdx = math.cos(-oyaw) * ldx + math.sin(-oyaw) * ldy
  124. gdy = -math.sin(-oyaw) * ldx + math.cos(-oyaw) * ldy
  125. px[ind] = ox + gdx
  126. py[ind] = oy + gdy
  127. if m == "L":
  128. pyaw[ind] = oyaw + l
  129. elif m == "R":
  130. pyaw[ind] = oyaw - l
  131. if l > 0.0:
  132. directions[ind] = 1
  133. else:
  134. directions[ind] = -1
  135. return px, py, pyaw, directions
  136. def generate_local_course(L, lengths, mode, maxc, step_size):
  137. point_num = int(L / step_size) + len(lengths) + 3
  138. px = [0.0 for _ in range(point_num)]
  139. py = [0.0 for _ in range(point_num)]
  140. pyaw = [0.0 for _ in range(point_num)]
  141. directions = [0 for _ in range(point_num)]
  142. ind = 1
  143. if lengths[0] > 0.0:
  144. directions[0] = 1
  145. else:
  146. directions[0] = -1
  147. if lengths[0] > 0.0:
  148. d = step_size
  149. else:
  150. d = -step_size
  151. ll = 0.0
  152. for m, l, i in zip(mode, lengths, range(len(mode))):
  153. if l > 0.0:
  154. d = step_size
  155. else:
  156. d = -step_size
  157. ox, oy, oyaw = px[ind], py[ind], pyaw[ind]
  158. ind -= 1
  159. if i >= 1 and (lengths[i - 1] * lengths[i]) > 0:
  160. pd = -d - ll
  161. else:
  162. pd = d - ll
  163. while abs(pd) <= abs(l):
  164. ind += 1
  165. px, py, pyaw, directions = \
  166. interpolate(ind, pd, m, maxc, ox, oy, oyaw, px, py, pyaw, directions)
  167. pd += d
  168. ll = l - pd - d # calc remain length
  169. ind += 1
  170. px, py, pyaw, directions = \
  171. interpolate(ind, l, m, maxc, ox, oy, oyaw, px, py, pyaw, directions)
  172. if len(px) <= 1:
  173. return [], [], [], []
  174. # remove unused data
  175. while len(px) >= 1 and px[-1] == 0.0:
  176. px.pop()
  177. py.pop()
  178. pyaw.pop()
  179. directions.pop()
  180. return px, py, pyaw, directions
  181. def planning_from_origin(gx, gy, gyaw, curv, step_size):
  182. D = math.hypot(gx, gy)
  183. d = D * curv
  184. theta = mod2pi(math.atan2(gy, gx))
  185. alpha = mod2pi(-theta)
  186. beta = mod2pi(gyaw - theta)
  187. planners = [LSL, RSR, LSR, RSL, RLR, LRL]
  188. best_cost = float("inf")
  189. bt, bp, bq, best_mode = None, None, None, None
  190. for planner in planners:
  191. t, p, q, mode = planner(alpha, beta, d)
  192. if t is None:
  193. continue
  194. cost = (abs(t) + abs(p) + abs(q))
  195. if best_cost > cost:
  196. bt, bp, bq, best_mode = t, p, q, mode
  197. best_cost = cost
  198. lengths = [bt, bp, bq]
  199. x_list, y_list, yaw_list, directions = generate_local_course(
  200. sum(lengths), lengths, best_mode, curv, step_size)
  201. return x_list, y_list, yaw_list, best_mode, best_cost
  202. def calc_dubins_path(sx, sy, syaw, gx, gy, gyaw, curv, step_size=0.1):
  203. gx = gx - sx
  204. gy = gy - sy
  205. l_rot = Rot.from_euler('z', syaw).as_dcm()[0:2, 0:2]
  206. le_xy = np.stack([gx, gy]).T @ l_rot
  207. le_yaw = gyaw - syaw
  208. lp_x, lp_y, lp_yaw, mode, lengths = planning_from_origin(
  209. le_xy[0], le_xy[1], le_yaw, curv, step_size)
  210. rot = Rot.from_euler('z', -syaw).as_dcm()[0:2, 0:2]
  211. converted_xy = np.stack([lp_x, lp_y]).T @ rot
  212. x_list = converted_xy[:, 0] + sx
  213. y_list = converted_xy[:, 1] + sy
  214. yaw_list = [pi_2_pi(i_yaw + syaw) for i_yaw in lp_yaw]
  215. return PATH(lengths, mode, x_list, y_list, yaw_list)
  216. def main():
  217. # choose states pairs: (s, y, yaw)
  218. # simulation-1
  219. states = [(0, 0, 0), (10, 10, -90), (20, 5, 60), (30, 10, 120),
  220. (35, -5, 30), (25, -10, -120), (15, -15, 100), (0, -10, -90)]
  221. # simulation-2
  222. # states = [(-3, 3, 120), (10, -7, 30), (10, 13, 30), (20, 5, -25),
  223. # (35, 10, 180), (32, -10, 180), (5, -12, 90)]
  224. max_c = 0.25 # max curvature
  225. path_x, path_y, yaw = [], [], []
  226. for i in range(len(states) - 1):
  227. s_x = states[i][0]
  228. s_y = states[i][1]
  229. s_yaw = np.deg2rad(states[i][2])
  230. g_x = states[i + 1][0]
  231. g_y = states[i + 1][1]
  232. g_yaw = np.deg2rad(states[i + 1][2])
  233. path_i = calc_dubins_path(s_x, s_y, s_yaw, g_x, g_y, g_yaw, max_c)
  234. for x, y, iyaw in zip(path_i.x, path_i.y, path_i.yaw):
  235. path_x.append(x)
  236. path_y.append(y)
  237. yaw.append(iyaw)
  238. # animation
  239. plt.ion()
  240. plt.figure(1)
  241. for i in range(len(path_x)):
  242. plt.clf()
  243. plt.plot(path_x, path_y, linewidth=1, color='gray')
  244. for x, y, theta in states:
  245. draw.Arrow(x, y, np.deg2rad(theta), 2, 'blueviolet')
  246. draw.Car(path_x[i], path_y[i], yaw[i], 1.5, 3)
  247. plt.axis("equal")
  248. plt.title("Simulation of Dubins Path")
  249. plt.axis([-10, 42, -20, 20])
  250. plt.draw()
  251. plt.pause(0.001)
  252. plt.pause(1)
  253. if __name__ == '__main__':
  254. main()