Skip to content

Commit 5a6970e

Browse files
authored
Merge pull request AtsushiSakai#151 from toolleeo/improved_arm_obstacle_navigation__visualization
Added modified version of the arm obstacle avoidance simulation.
2 parents 7a17e3a + a558096 commit 5a6970e

File tree

1 file changed

+277
-0
lines changed

1 file changed

+277
-0
lines changed
Lines changed: 277 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,277 @@
1+
"""
2+
Obstacle navigation using A* on a toroidal grid
3+
4+
Author: Daniel Ingram (daniel-s-ingram)
5+
Tullio Facchinetti ([email protected])
6+
"""
7+
from math import pi
8+
import numpy as np
9+
import matplotlib.pyplot as plt
10+
from matplotlib.colors import from_levels_and_colors
11+
import sys
12+
13+
plt.ion()
14+
15+
# Simulation parameters
16+
M = 100
17+
obstacles = [[1.75, 0.75, 0.6], [0.55, 1.5, 0.5], [0, -1, 0.7]]
18+
19+
20+
def press(event):
21+
"""Exit from the simulation."""
22+
if event.key == 'q' or event.key == 'Q':
23+
print('Quitting upon request.')
24+
sys.exit(0)
25+
26+
def main():
27+
# Arm geometry in the working space
28+
link_length = [0.5, 1.5]
29+
initial_link_angle = [0, 0]
30+
arm = NLinkArm(link_length, initial_link_angle)
31+
# (x, y) co-ordinates in the joint space [cell]
32+
start = (10, 50)
33+
goal = (58, 56)
34+
grid = get_occupancy_grid(arm, obstacles)
35+
route = astar_torus(grid, start, goal)
36+
if len(route) >= 0:
37+
animate(grid, arm, route)
38+
39+
40+
def animate(grid, arm, route):
41+
fig, axs = plt.subplots(1, 2)
42+
fig.canvas.mpl_connect('key_press_event', press)
43+
colors = ['white', 'black', 'red', 'pink', 'yellow', 'green', 'orange']
44+
levels = [0, 1, 2, 3, 4, 5, 6, 7]
45+
cmap, norm = from_levels_and_colors(levels, colors)
46+
for i, node in enumerate(route):
47+
plt.subplot(1, 2, 1)
48+
grid[node] = 6
49+
plt.cla()
50+
plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None)
51+
theta1 = 2 * pi * node[0] / M - pi
52+
theta2 = 2 * pi * node[1] / M - pi
53+
arm.update_joints([theta1, theta2])
54+
plt.subplot(1, 2, 2)
55+
arm.plot(plt, obstacles=obstacles)
56+
plt.show()
57+
# Uncomment here to save the sequence of frames
58+
#plt.savefig('frame{:04d}.png'.format(i))
59+
plt.pause(0.1)
60+
61+
62+
def detect_collision(line_seg, circle):
63+
"""
64+
Determines whether a line segment (arm link) is in contact
65+
with a circle (obstacle).
66+
Credit to: http://doswa.com/2009/07/13/circle-segment-intersectioncollision.html
67+
Args:
68+
line_seg: List of coordinates of line segment endpoints e.g. [[1, 1], [2, 2]]
69+
circle: List of circle coordinates and radius e.g. [0, 0, 0.5] is a circle centered
70+
at the origin with radius 0.5
71+
72+
Returns:
73+
True if the line segment is in contact with the circle
74+
False otherwise
75+
"""
76+
a_vec = np.array([line_seg[0][0], line_seg[0][1]])
77+
b_vec = np.array([line_seg[1][0], line_seg[1][1]])
78+
c_vec = np.array([circle[0], circle[1]])
79+
radius = circle[2]
80+
line_vec = b_vec - a_vec
81+
line_mag = np.linalg.norm(line_vec)
82+
circle_vec = c_vec - a_vec
83+
proj = circle_vec.dot(line_vec / line_mag)
84+
if proj <= 0:
85+
closest_point = a_vec
86+
elif proj >= line_mag:
87+
closest_point = b_vec
88+
else:
89+
closest_point = a_vec + line_vec * proj / line_mag
90+
if np.linalg.norm(closest_point - c_vec) > radius:
91+
return False
92+
else:
93+
return True
94+
95+
96+
def get_occupancy_grid(arm, obstacles):
97+
"""
98+
Discretizes joint space into M values from -pi to +pi
99+
and determines whether a given coordinate in joint space
100+
would result in a collision between a robot arm and obstacles
101+
in its environment.
102+
103+
Args:
104+
arm: An instance of NLinkArm
105+
obstacles: A list of obstacles, with each obstacle defined as a list
106+
of xy coordinates and a radius.
107+
108+
Returns:
109+
Occupancy grid in joint space
110+
"""
111+
grid = [[0 for _ in range(M)] for _ in range(M)]
112+
theta_list = [2 * i * pi / M for i in range(-M // 2, M // 2 + 1)]
113+
for i in range(M):
114+
for j in range(M):
115+
arm.update_joints([theta_list[i], theta_list[j]])
116+
points = arm.points
117+
collision_detected = False
118+
for k in range(len(points) - 1):
119+
for obstacle in obstacles:
120+
line_seg = [points[k], points[k + 1]]
121+
collision_detected = detect_collision(line_seg, obstacle)
122+
if collision_detected:
123+
break
124+
if collision_detected:
125+
break
126+
grid[i][j] = int(collision_detected)
127+
return np.array(grid)
128+
129+
130+
def astar_torus(grid, start_node, goal_node):
131+
"""
132+
Finds a path between an initial and goal joint configuration using
133+
the A* Algorithm on a tororiadal grid.
134+
135+
Args:
136+
grid: An occupancy grid (ndarray)
137+
start_node: Initial joint configuation (tuple)
138+
goal_node: Goal joint configuration (tuple)
139+
140+
Returns:
141+
Obstacle-free route in joint space from start_node to goal_node
142+
"""
143+
grid[start_node] = 4
144+
grid[goal_node] = 5
145+
146+
parent_map = [[() for _ in range(M)] for _ in range(M)]
147+
148+
X, Y = np.meshgrid([i for i in range(M)], [i for i in range(M)])
149+
heuristic_map = np.abs(X - goal_node[1]) + np.abs(Y - goal_node[0])
150+
for i in range(heuristic_map.shape[0]):
151+
for j in range(heuristic_map.shape[1]):
152+
heuristic_map[i, j] = min(heuristic_map[i, j],
153+
i + 1 + heuristic_map[M - 1, j],
154+
M - i + heuristic_map[0, j],
155+
j + 1 + heuristic_map[i, M - 1],
156+
M - j + heuristic_map[i, 0]
157+
)
158+
159+
explored_heuristic_map = np.full((M, M), np.inf)
160+
distance_map = np.full((M, M), np.inf)
161+
explored_heuristic_map[start_node] = heuristic_map[start_node]
162+
distance_map[start_node] = 0
163+
while True:
164+
grid[start_node] = 4
165+
grid[goal_node] = 5
166+
167+
current_node = np.unravel_index(
168+
np.argmin(explored_heuristic_map, axis=None), explored_heuristic_map.shape)
169+
min_distance = np.min(explored_heuristic_map)
170+
if (current_node == goal_node) or np.isinf(min_distance):
171+
break
172+
173+
grid[current_node] = 2
174+
explored_heuristic_map[current_node] = np.inf
175+
176+
i, j = current_node[0], current_node[1]
177+
178+
neighbors = []
179+
if i - 1 >= 0:
180+
neighbors.append((i - 1, j))
181+
else:
182+
neighbors.append((M - 1, j))
183+
184+
if i + 1 < M:
185+
neighbors.append((i + 1, j))
186+
else:
187+
neighbors.append((0, j))
188+
189+
if j - 1 >= 0:
190+
neighbors.append((i, j - 1))
191+
else:
192+
neighbors.append((i, M - 1))
193+
194+
if j + 1 < M:
195+
neighbors.append((i, j + 1))
196+
else:
197+
neighbors.append((i, 0))
198+
199+
for neighbor in neighbors:
200+
if grid[neighbor] == 0 or grid[neighbor] == 5:
201+
distance_map[neighbor] = distance_map[current_node] + 1
202+
explored_heuristic_map[neighbor] = heuristic_map[neighbor]
203+
parent_map[neighbor[0]][neighbor[1]] = current_node
204+
grid[neighbor] = 3
205+
'''
206+
plt.cla()
207+
plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None)
208+
plt.show()
209+
plt.pause(1e-5)
210+
'''
211+
212+
if np.isinf(explored_heuristic_map[goal_node]):
213+
route = []
214+
print("No route found.")
215+
else:
216+
route = [goal_node]
217+
while parent_map[route[0][0]][route[0][1]] is not ():
218+
route.insert(0, parent_map[route[0][0]][route[0][1]])
219+
220+
print("The route found covers %d grid cells." % len(route))
221+
return route
222+
223+
224+
class NLinkArm(object):
225+
"""
226+
Class for controlling and plotting a planar arm with an arbitrary number of links.
227+
"""
228+
229+
def __init__(self, link_lengths, joint_angles):
230+
self.n_links = len(link_lengths)
231+
if self.n_links != len(joint_angles):
232+
raise ValueError()
233+
234+
self.link_lengths = np.array(link_lengths)
235+
self.joint_angles = np.array(joint_angles)
236+
self.points = [[0, 0] for _ in range(self.n_links + 1)]
237+
238+
self.lim = sum(link_lengths)
239+
self.update_points()
240+
241+
def update_joints(self, joint_angles):
242+
self.joint_angles = joint_angles
243+
self.update_points()
244+
245+
def update_points(self):
246+
for i in range(1, self.n_links + 1):
247+
self.points[i][0] = self.points[i - 1][0] + \
248+
self.link_lengths[i - 1] * \
249+
np.cos(np.sum(self.joint_angles[:i]))
250+
self.points[i][1] = self.points[i - 1][1] + \
251+
self.link_lengths[i - 1] * \
252+
np.sin(np.sum(self.joint_angles[:i]))
253+
254+
self.end_effector = np.array(self.points[self.n_links]).T
255+
256+
def plot(self, myplt, obstacles=[]):
257+
myplt.cla()
258+
259+
for obstacle in obstacles:
260+
circle = myplt.Circle(
261+
(obstacle[0], obstacle[1]), radius=0.5 * obstacle[2], fc='k')
262+
myplt.gca().add_patch(circle)
263+
264+
for i in range(self.n_links + 1):
265+
if i is not self.n_links:
266+
myplt.plot([self.points[i][0], self.points[i + 1][0]],
267+
[self.points[i][1], self.points[i + 1][1]], 'r-')
268+
myplt.plot(self.points[i][0], self.points[i][1], 'k.')
269+
270+
myplt.xlim([-self.lim, self.lim])
271+
myplt.ylim([-self.lim, self.lim])
272+
myplt.draw()
273+
#myplt.pause(1e-5)
274+
275+
276+
if __name__ == '__main__':
277+
main()

0 commit comments

Comments
 (0)