|
| 1 | +""" |
| 2 | +Clothoidal Path Planner |
| 3 | +Author: Daniel Ingram (daniel-s-ingram) |
| 4 | +Reference paper: https://www.researchgate.net/publication/237062806 |
| 5 | +""" |
| 6 | + |
| 7 | +import matplotlib.pyplot as plt |
| 8 | +import numpy as np |
| 9 | +import scipy.integrate as integrate |
| 10 | +from collections import namedtuple |
| 11 | +from scipy.optimize import fsolve |
| 12 | +from math import atan2, cos, hypot, pi, sin |
| 13 | +from matplotlib import animation |
| 14 | + |
| 15 | +Point = namedtuple("Point", ["x", "y"]) |
| 16 | + |
| 17 | + |
| 18 | +def draw_clothoids( |
| 19 | + theta1_vals, |
| 20 | + theta2_vals, |
| 21 | + num_clothoids=75, |
| 22 | + num_steps=100, |
| 23 | + save_animation=False |
| 24 | +): |
| 25 | + p1 = Point(0, 0) |
| 26 | + p2 = Point(10, 0) |
| 27 | + clothoids = [] |
| 28 | + for theta1 in theta1_vals: |
| 29 | + for theta2 in theta2_vals: |
| 30 | + clothoid = get_clothoid_points(p1, p2, theta1, theta2, num_steps) |
| 31 | + clothoids.append(clothoid) |
| 32 | + |
| 33 | + fig = plt.figure(figsize=(10, 10)) |
| 34 | + x_min, x_max, y_min, y_max = get_axes_limits(clothoids) |
| 35 | + axes = plt.axes(xlim=(x_min, x_max), ylim=(y_min, y_max)) |
| 36 | + |
| 37 | + axes.plot(p1.x, p1.y, 'ro') |
| 38 | + axes.plot(p2.x, p2.y, 'ro') |
| 39 | + lines = [axes.plot([], [], 'b-')[0] for _ in range(len(clothoids))] |
| 40 | + |
| 41 | + def animate(i): |
| 42 | + for line, clothoid in zip(lines, clothoids): |
| 43 | + x = [p.x for p in clothoid[:i]] |
| 44 | + y = [p.y for p in clothoid[:i]] |
| 45 | + line.set_data(x, y) |
| 46 | + |
| 47 | + return lines |
| 48 | + |
| 49 | + anim = animation.FuncAnimation( |
| 50 | + fig, |
| 51 | + animate, |
| 52 | + frames=num_steps, |
| 53 | + interval=25, |
| 54 | + blit=True |
| 55 | + ) |
| 56 | + if save_animation: |
| 57 | + anim.save('clothoid.gif', fps=30, writer="imagemagick") |
| 58 | + plt.show() |
| 59 | + |
| 60 | + |
| 61 | +def get_clothoid_points(p1, p2, theta1, theta2, num_steps=100): |
| 62 | + dx = p2.x - p1.x |
| 63 | + dy = p2.y - p1.y |
| 64 | + r = hypot(dx, dy) |
| 65 | + |
| 66 | + phi = atan2(dy, dx) |
| 67 | + phi1 = normalize_angle(theta1 - phi) |
| 68 | + phi2 = normalize_angle(theta2 - phi) |
| 69 | + delta = phi2 - phi1 |
| 70 | + |
| 71 | + try: |
| 72 | + A = solve_for_root(phi1, phi2, delta) |
| 73 | + L = compute_length(r, phi1, delta, A) |
| 74 | + curv = compute_curvature(delta, A, L) |
| 75 | + curv_rate = compute_curvature_rate(A, L) |
| 76 | + except Exception as e: |
| 77 | + print(f"Failed to generate clothoid points: {e}") |
| 78 | + return None |
| 79 | + |
| 80 | + points = [] |
| 81 | + for s in np.linspace(0, L, num_steps): |
| 82 | + try: |
| 83 | + x = p1.x + s*X(curv_rate*s**2, curv*s, theta1) |
| 84 | + y = p1.y + s*Y(curv_rate*s**2, curv*s, theta1) |
| 85 | + points.append(Point(x, y)) |
| 86 | + except Exception as e: |
| 87 | + print(f"Skipping failed clothoid point: {e}") |
| 88 | + |
| 89 | + return points |
| 90 | + |
| 91 | + |
| 92 | +def X(a, b, c): |
| 93 | + return integrate.quad(lambda t: cos((a/2)*t**2 + b*t + c), 0, 1)[0] |
| 94 | + |
| 95 | + |
| 96 | +def Y(a, b, c): |
| 97 | + return integrate.quad(lambda t: sin((a/2)*t**2 + b*t + c), 0, 1)[0] |
| 98 | + |
| 99 | + |
| 100 | +def solve_for_root(theta1, theta2, delta): |
| 101 | + initial_guess = 3*(theta1 + theta2) |
| 102 | + return fsolve(lambda x: Y(2*x, delta - x, theta1), [initial_guess]) |
| 103 | + |
| 104 | + |
| 105 | +def compute_length(r, theta1, delta, A): |
| 106 | + return r / X(2*A, delta - A, theta1) |
| 107 | + |
| 108 | + |
| 109 | +def compute_curvature(delta, A, L): |
| 110 | + return (delta - A) / L |
| 111 | + |
| 112 | + |
| 113 | +def compute_curvature_rate(A, L): |
| 114 | + return 2 * A / (L**2) |
| 115 | + |
| 116 | + |
| 117 | +def normalize_angle(angle_rad): |
| 118 | + return (angle_rad + pi) % (2 * pi) - pi |
| 119 | + |
| 120 | + |
| 121 | +def get_axes_limits(clothoids): |
| 122 | + x_vals = [p.x for clothoid in clothoids for p in clothoid] |
| 123 | + y_vals = [p.y for clothoid in clothoids for p in clothoid] |
| 124 | + |
| 125 | + x_min = min(x_vals) |
| 126 | + x_max = max(x_vals) |
| 127 | + y_min = min(y_vals) |
| 128 | + y_max = max(y_vals) |
| 129 | + |
| 130 | + x_offset = 0.1*(x_max - x_min) |
| 131 | + y_offset = 0.1*(y_max - y_min) |
| 132 | + |
| 133 | + x_min = x_min - x_offset |
| 134 | + x_max = x_max + x_offset |
| 135 | + y_min = y_min - y_offset |
| 136 | + y_max = y_max + y_offset |
| 137 | + |
| 138 | + return x_min, x_max, y_min, y_max |
| 139 | + |
| 140 | + |
| 141 | +if __name__ == "__main__": |
| 142 | + theta1_vals = [0] |
| 143 | + theta2_vals = np.linspace(-pi, pi, 75) |
| 144 | + draw_clothoids(theta1_vals, theta2_vals, save_animation=False) |
0 commit comments