Skip to content

Commit 474ffef

Browse files
committed
first release grid based_sweep_planner.py
1 parent 6314c40 commit 474ffef

File tree

3 files changed

+278
-3
lines changed

3 files changed

+278
-3
lines changed

Mapping/grid_map_lib/__init__.py

Whitespace-only changes.

Mapping/grid_map_lib/grid_map_lib.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -185,13 +185,14 @@ def check_inside_polygon(iox, ioy, x, y):
185185

186186
return inside
187187

188-
def plot_grid_map(self):
188+
def plot_grid_map(self, ax=None):
189189

190190
grid_data = np.reshape(np.array(self.data), (self.height, self.width))
191-
fig, ax = plt.subplots()
191+
if not ax:
192+
fig, ax = plt.subplots()
192193
heat_map = ax.pcolor(grid_data, cmap="Blues", vmin=0.0, vmax=1.0)
193194
plt.axis("equal")
194-
plt.show()
195+
# plt.show()
195196

196197
return heat_map
197198

Lines changed: 274 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,274 @@
1+
"""
2+
Grid based sweep planner
3+
4+
author: Atsushi Sakai
5+
"""
6+
7+
import math
8+
import os
9+
import sys
10+
11+
import matplotlib.pyplot as plt
12+
import numpy as np
13+
14+
sys.path.append(os.path.relpath("../../Mapping/grid_map_lib/"))
15+
from grid_map_lib import GridMap
16+
17+
18+
class SweepSearcher:
19+
20+
def __init__(self, mdirection, sdirection, xinds_miny, miny):
21+
self.moving_direction = mdirection # +1 or -1
22+
self.sweep_direction = sdirection # +1 or -1
23+
self.turing_window = []
24+
self.update_turning_window()
25+
self.xinds_miny = xinds_miny
26+
self.miny = miny
27+
28+
def move_target_grid(self, cxind, cyind, gmap):
29+
30+
nxind = self.moving_direction + cxind
31+
nyind = cyind
32+
33+
# found safe grid
34+
if not gmap.check_occupied_from_xy_index(nxind, nyind, occupied_val=0.5):
35+
return nxind, nyind
36+
else: # occupided
37+
ncxind, ncyind = self.find_safe_turning_grid(cxind, cyind, gmap)
38+
if not ncxind and not ncyind:
39+
# moving backward
40+
ncxind = -self.moving_direction + cxind
41+
ncyind = cyind
42+
if gmap.check_occupied_from_xy_index(ncxind, ncyind):
43+
# moved backward, but the grid is occupied by obstacle
44+
return None, None
45+
else:
46+
self.swap_moving_direction()
47+
return ncxind, ncyind
48+
49+
def find_safe_turning_grid(self, cxind, cyind, gmap):
50+
51+
for (dxind, dyind) in self.turing_window:
52+
53+
nxind = dxind + cxind
54+
nyind = dyind + cyind
55+
56+
# found safe grid
57+
if not gmap.check_occupied_from_xy_index(nxind, nyind, occupied_val=0.5):
58+
print(dxind, dyind)
59+
return nxind, nyind
60+
61+
return None, None
62+
63+
def is_search_done(self, gmap):
64+
for ix in self.xinds_miny:
65+
if not gmap.check_occupied_from_xy_index(ix, self.miny, occupied_val=0.5):
66+
return False
67+
68+
# all lower grid is occupied
69+
return True
70+
71+
def update_turning_window(self):
72+
self.turing_window = [
73+
(self.moving_direction, 0.0),
74+
(self.moving_direction, self.sweep_direction),
75+
(0, self.sweep_direction),
76+
(-self.moving_direction, self.sweep_direction),
77+
]
78+
79+
def swap_moving_direction(self):
80+
self.moving_direction *= -1
81+
self.update_turning_window()
82+
83+
84+
def find_sweep_direction_and_start_posi(ox, oy, start_posi):
85+
# find sweep_direction
86+
maxd_id = None
87+
maxd = 0.0
88+
vec = [0.0, 0.0]
89+
for i in range(len(ox) - 1):
90+
dx = ox[i + 1] - ox[i]
91+
dy = oy[i + 1] - oy[i]
92+
d = np.sqrt(dx ** 2 + dy ** 2)
93+
94+
if d > maxd:
95+
maxd_id = i
96+
maxd = d
97+
vec = [dx, dy]
98+
99+
# find sweep start posi
100+
d1 = np.sqrt((ox[maxd_id] - start_posi[0]) ** 2 +
101+
(oy[maxd_id] - start_posi[1]) ** 2)
102+
d2 = np.sqrt((ox[maxd_id + 1] - start_posi[0]) ** 2 +
103+
(oy[maxd_id + 1] - start_posi[1]) ** 2)
104+
105+
if d2 >= d1: # first point is near
106+
sweep_start_posi = [ox[maxd_id], oy[maxd_id]]
107+
else:
108+
sweep_start_posi = [ox[maxd_id + 1], oy[maxd_id + 1]]
109+
vec = [-1.0 * iv for iv in vec] # reverse direction
110+
111+
return vec, sweep_start_posi
112+
113+
114+
def convert_grid_coordinate(ox, oy, sweep_vec, sweep_start_posi):
115+
tx = [ix - sweep_start_posi[0] for ix in ox]
116+
ty = [iy - sweep_start_posi[1] for iy in oy]
117+
118+
th = math.atan2(sweep_vec[1], sweep_vec[0])
119+
120+
c = np.cos(-th)
121+
s = np.sin(-th)
122+
123+
rx = [ix * c - iy * s for (ix, iy) in zip(tx, ty)]
124+
ry = [ix * s + iy * c for (ix, iy) in zip(tx, ty)]
125+
126+
return rx, ry
127+
128+
129+
def convert_global_coordinate(x, y, sweep_vec, sweep_start_posi):
130+
th = math.atan2(sweep_vec[1], sweep_vec[0])
131+
c = np.cos(th)
132+
s = np.sin(th)
133+
134+
tx = [ix * c - iy * s for (ix, iy) in zip(x, y)]
135+
ty = [ix * s + iy * c for (ix, iy) in zip(x, y)]
136+
137+
rx = [ix + sweep_start_posi[0] for ix in tx]
138+
ry = [iy + sweep_start_posi[1] for iy in ty]
139+
140+
return rx, ry
141+
142+
143+
def search_free_lower_y_grid_index(grid_map):
144+
miny = None
145+
xinds = []
146+
147+
for iy in range(grid_map.height):
148+
for ix in range(grid_map.width):
149+
if not grid_map.check_occupied_from_xy_index(ix, iy):
150+
miny = iy
151+
xinds.append(ix)
152+
if miny:
153+
break
154+
155+
return xinds, miny
156+
157+
158+
def setup_grid_map(ox, oy, reso):
159+
offset_grid = 10
160+
161+
width = math.ceil((max(ox) - min(ox)) / reso) + offset_grid
162+
height = math.ceil((max(oy) - min(oy)) / reso) + offset_grid
163+
center_x = np.mean(ox)
164+
center_y = np.mean(oy)
165+
166+
grid_map = GridMap(width, height, reso, center_x, center_y)
167+
168+
grid_map.set_value_from_polygon(ox, oy, 1.0, inside=False)
169+
170+
# fill grid
171+
# for i in range(len(ox) - 1):
172+
# grid_map.set_value_from_xy_pos(ox[i], oy[i], 1.0)
173+
#
174+
# x, y = ox[i], oy[i]
175+
# th = math.atan2(oy[i + 1] - oy[i], ox[i + 1] - ox[i])
176+
# d = np.sqrt((x - ox[i + 1])**2 + (y - oy[i + 1])**2)
177+
#
178+
# while d > reso:
179+
# x += np.cos(th) * reso
180+
# y += np.sin(th) * reso
181+
# d = np.sqrt((x - ox[i + 1])**2 + (y - oy[i + 1])**2)
182+
#
183+
# grid_map.set_value_from_xy_pos(x, y, 1.0)
184+
185+
xinds, miny = search_free_lower_y_grid_index(grid_map)
186+
187+
# grid_map.plot_gridmap()
188+
189+
return grid_map, xinds, miny
190+
191+
192+
def sweep_path_search(sweep_searcher, gmap, start_posi):
193+
sx, sy = start_posi[0], start_posi[1]
194+
# print(sx, sy)
195+
196+
# search start grid
197+
cxind, cyind = gmap.get_xy_index_from_xy_pos(sx, sy)
198+
if gmap.check_occupied_from_xy_index(cxind, cyind):
199+
cxind, cyind = sweep_searcher.find_safe_turning_grid(cxind, cyind, gmap)
200+
gmap.set_value_from_xy_index(cxind, cyind, 0.5)
201+
202+
px, py = [], []
203+
204+
# fig, ax = plt.subplots()
205+
206+
while True:
207+
208+
cxind, cyind = sweep_searcher.move_target_grid(cxind, cyind, gmap)
209+
210+
if sweep_searcher.is_search_done(gmap) or (not cxind and not cyind):
211+
print("Done")
212+
break
213+
214+
x, y = gmap.calc_grid_central_xy_position_from_xy_index(
215+
cxind, cyind)
216+
217+
px.append(x)
218+
py.append(y)
219+
220+
gmap.set_value_from_xy_index(cxind, cyind, 0.5)
221+
222+
# gmap.plot_grid_map(ax=ax)
223+
# plt.pause(0.1)
224+
225+
gmap.plot_grid_map()
226+
227+
return px, py
228+
229+
230+
def planning(ox, oy, reso, start_posi):
231+
sweep_vec, sweep_start_posi = find_sweep_direction_and_start_posi(
232+
ox, oy, start_posi)
233+
234+
rox, roy = convert_grid_coordinate(ox, oy, sweep_vec, sweep_start_posi)
235+
236+
moving_direction = 1
237+
sweeping_direction = -1
238+
239+
gmap, xinds_miny, miny = setup_grid_map(rox, roy, reso)
240+
241+
sweep_searcher = SweepSearcher(moving_direction, sweeping_direction, xinds_miny, miny)
242+
243+
px, py = sweep_path_search(sweep_searcher, gmap, start_posi)
244+
245+
rx, ry = convert_global_coordinate(px, py, sweep_vec, sweep_start_posi)
246+
247+
return rx, ry
248+
249+
250+
def main():
251+
print("start!!")
252+
253+
start_posi = [0.0, 0.0]
254+
255+
ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0, 0.0]
256+
oy = [0.0, -20.0, 0.0, 30.0, 60.0, 80.0, 0.0]
257+
reso = 5.0
258+
259+
px, py = planning(ox, oy, reso, start_posi)
260+
261+
plt.subplots()
262+
263+
plt.plot(start_posi[0], start_posi[1], "or")
264+
plt.plot(ox, oy, "-xb")
265+
plt.plot(px, py, "-r")
266+
plt.axis("equal")
267+
plt.grid(True)
268+
plt.show()
269+
270+
print("done!!")
271+
272+
273+
if __name__ == '__main__':
274+
main()

0 commit comments

Comments
 (0)