-
Notifications
You must be signed in to change notification settings - Fork 0
/
path_planning.py
405 lines (343 loc) · 17.6 KB
/
path_planning.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
from std_msgs.msg import Int32MultiArray, MultiArrayDimension, MultiArrayLayout
import math
# a star
class PathPlanning(Node):
def __init__(self):
"""
ox: x position list of Obstacles
oy: y position list of Obstacles
resolution: grid resolution
rr: robot radiums
"""
super().__init__("path_planning")
self.pos_list_pub = self.create_publisher(Int32MultiArray, '/pos_test', 10)
self.resolution = 1
self.rr = 100
# 3----2
# | |
# 0----1
#之后确定边界的顶点坐标后,应设定这个值, 按逆时针, 必须为长方形且与Gazebo中的经纬度平行
# self.fly_boundary_position = [[-26717208, 514234260], [-26701340, 514212462],
# [-26656878, 514224401], [-26670602, 514246918]]
# self.no_fly_zone = [[-26711717, 514226717], [-26673723, 514235482],
# [-26670013, 514228490], [-26706367, 514219368]]
self.fly_boundary_position = [[-267172, 5142342], [-267013, 5142124],
[-266568, 5142244], [-266706, 5142469]]
self.no_fly_zone = [[-267117, 5142267], [-266737, 5142354],
[-266700, 5142284], [-267063, 5142193]]
# A[-2.6711717, 51.4226717], D[-2.6706367, 51.4219368]
self.ox = []
self.oy = []
self.min_x, self.min_y = 0, 0
self.max_x, self.max_y = 0, 0
self.obstacle_map = None
self.x_width, self.y_width = 0, 0
self.motion = None
self.message = "AStar init"
self.pos_t = [[1, 1], [2, 2]]
self.path_planning_controller_pub = self.create_publisher(String, '/path_planning_controller', 10)
self.path_planning_controller_msg = String()
class PathNode:
def __init__(self, x, y, cost, parent_index):
self.x = x
self.y = y
self.cost = cost
self.parent_index = parent_index
def calc_heuristic(self, node1, node2):
w = 1.0 # weight of heuristic
d = w * math.hypot(node1.x - node2.x, node1.y - node2.y)
return d
def tf_xy_global_position(self, index, min_position):
# tf xy glocal position
pos = index * self.resolution + min_position
return pos
def tf_xy_local_position(self, position, min_pos):
# tf xy local position, e.g. index
return (position - min_pos) / self.resolution
def tf_dict_index(self, node):
# dict index: tf 2-D to 1-D dict
return (int)(node.y - self.min_y) * self.x_width + (node.x - self.min_x)
def verify_node(self, node):
px = self.tf_xy_global_position(node.x, self.min_x)
py = self.tf_xy_global_position(node.y, self.min_y)
if px < self.min_x:
return False
elif py < self.min_y:
return False
elif px >= self.max_x:
return False
elif py >= self.max_y:
return False
if self.obstacle_map[(int)(node.x)][(int)(node.y)]:
return False
return True
def calc_final_path(self, goal_node, closed_set):
rx = [self.tf_xy_global_position(goal_node.x, self.min_x)]
ry = [self.tf_xy_global_position(goal_node.y, self.min_y)]
parent_index = goal_node.parent_index
while parent_index != -1:
n = closed_set[parent_index]
rx.append(self.tf_xy_global_position(n.x, self.min_x))
ry.append(self.tf_xy_global_position(n.y, self.min_y))
parent_index = n.parent_index
return rx, ry
def planning(self, sx, sy, gx, gy):
"""
input:
sx: start x position
sy: start y position
gx: goal x position
gy: goal y position
output:
rx: x position list of the fianl path
ry: y position list of the final path
"""
start_node = self.PathNode(self.tf_xy_local_position(sx, self.min_x),
self.tf_xy_local_position(sy, self.min_y), 0.0, -1)
goal_node = self.PathNode(self.tf_xy_local_position(gx, self.min_x),
self.tf_xy_local_position(gy, self.min_y), 0.0, -1)
open_set, closed_set = dict(), dict()
open_set[self.tf_dict_index(start_node)] = start_node
while True:
if len(open_set) == 0:
self.message = "Open set is empty."
break
# get the min value's index in open_set
c_id = min(open_set,
key=lambda o: open_set[o].cost + self.calc_heuristic(goal_node, open_set[o]))
current = open_set[c_id]
if current.x == goal_node.x and current.y == goal_node.y:
self.message = "Find goal"
goal_node.parent_index = current.parent_index
goal_node.cost = current.cost
break
del open_set[c_id]
closed_set[c_id] = current
if current.x > -266737:
self.motion = self.get_motion_model(2)
else:
self.motion = self.get_motion_model(1)
# expend the grid search based on motion model
for i, _ in enumerate(self.motion):
node = self.PathNode(current.x + self.motion[i][0], current.y + self.motion[i][1],
current.cost + self.motion[i][2], c_id)
n_id = self.tf_dict_index(node)
# if the node is not safe, do nothing
if not self.verify_node(node):
continue
if n_id in closed_set:
continue
if n_id not in open_set:
open_set[n_id] = node
else:
if open_set[n_id].cost > node.cost:
open_set[n_id] = node
rx, ry = self.calc_final_path(goal_node, closed_set)
return rx, ry
def calc_obstacle_map(self):
self.min_x = self.fly_boundary_position[0][0]
self.min_y = self.fly_boundary_position[1][1]
self.max_x = self.fly_boundary_position[2][0]
self.max_y = self.fly_boundary_position[3][1]
self.x_width = self.max_x - self.min_x
self.y_width = self.max_y - self.min_y
self.obstacle_map = [[True for _ in range(self.y_width)] for _ in range(self.x_width)]
obstacle_para = 1 # 1 = 1 m 1*1.414 = 1.41
for ix in range(self.x_width):
x = self.tf_xy_global_position(ix, self.min_x)
flight_ab = round((-137107 * x + 477603048596) / 100000) + obstacle_para
flight_bc = round(( 26966 * x + 521412672558) / 100000) + obstacle_para
flight_cd = round((-163043 * x + 470762353576) / 100000) - obstacle_para
flight_da = round(( 27253 * x + 521515438516) / 100000) - obstacle_para
no_fly_ab = round(( 16667 * x + 518681105735) / 100000) + obstacle_para
no_fly_bc = round((-189189 * x + 463771693707) / 100000) + obstacle_para
no_fly_cd = round(( 25000 * x + 520895900000) / 100000) - obstacle_para
for iy in range(self.y_width):
y = self.tf_xy_global_position(iy, self.min_y)
if x < self.no_fly_zone[0][0]:
if y > flight_ab and y < flight_da:
self.obstacle_map[ix][iy] = False
elif x < self.no_fly_zone[3][0]:
if y > no_fly_ab and y < flight_da:
self.obstacle_map[ix][iy] = False
elif x < self.fly_boundary_position[1][0]:
if y > flight_ab and y < no_fly_cd:
self.obstacle_map[ix][iy] = False
elif y > no_fly_ab and y < flight_da:
self.obstacle_map[ix][iy] = False
elif x < self.no_fly_zone[1][0]:
if y > flight_bc and y < no_fly_cd:
self.obstacle_map[ix][iy] = False
elif y > no_fly_ab and y < flight_da:
self.obstacle_map[ix][iy] = False
# elif x < self.no_fly_zone[2][0]:
# if y > flight_bc and y < no_fly_cd:
# self.obstacle_map[ix][iy] = False
# elif y > no_fly_bc and y < flight_da:
# self.obstacle_map[ix][iy] = False
elif x < self.no_fly_zone[2][0] + 20:
if y > flight_bc and y < (self.no_fly_zone[2][1] - 10):
self.obstacle_map[ix][iy] = False
elif y > (self.no_fly_zone[1][1] + 10) and y < flight_da:
self.obstacle_map[ix][iy] = False
elif x < self.fly_boundary_position[3][0]:
if y > flight_bc and y < flight_da:
self.obstacle_map[ix][iy] = False
elif x < self.fly_boundary_position[2][0]:
if y > flight_bc and y < flight_cd:
self.obstacle_map[ix][iy] = False
# self.min_x = (int)(min(ox))
# self.min_y = (int)(min(oy))
# self.max_x = (int)(max(ox))
# self.max_y = (int)(max(oy))
# self.x_width = (self.max_x - self.min_x) / self.resolution
# self.y_width = (self.max_y - self.min_y) / self.resolution
# self.obstacle_map = [[False for _ in range(self.y_width)] for _ in range(self.x_width)]
# for ix in range(self.x_width):
# x = self.tf_xy_global_position(ix, self.min_x)
# for iy in range(self.y_width):
# y = self.tf_xy_global_position(iy, self.min_y)
# for iox, ioy in zip(ox, oy):
# d = math.hypot(iox - x, ioy - y)
# if d <= self.rr:
# self.obstacle_map[ix][iy] = True
# break
def get_motion_model(self, state):
# x, y, cost
# motion = [[1, 0, 1], [0, 1, 1], [-1, 0, 1], [0, -1, 1],
# [-1, -1, math.sqrt(2)], [-1, 1, math.sqrt(2)],
# [1, -1, math.sqrt(2)], [1, 1, math.sqrt(2)]]
# motion = [[1, 0, 2], [0, 1, 1], [-1, 0, 2], [0, -1, 1],
# [-1, -1, math.sqrt(5)], [-1, 1, math.sqrt(5)],
# [1, -1, math.sqrt(5)], [1, 1, math.sqrt(5)]]
if state == 1:
motion = [[1, 0, 4], [0, 1, 3], [-1, 0, 4], [0, -1, 3],
[-1, -1, 5], [-1, 1, 5],
[1, -1, 5], [1, 1, 5]]
else:
motion = [[1, 0, 1], [0, 1, 1], [-1, 0, 1], [0, -1, 1],
[-1, -1, math.sqrt(2)], [-1, 1, math.sqrt(2)],
[1, -1, math.sqrt(2)], [1, 1, math.sqrt(2)]]
return motion
# 假设禁飞区的顶点坐标为no_fly_zone, 逆时针
# 设定飞行边界fly_boundary为顶点坐标
def obstacle_map_init(self, fly_boundary, no_fly_zone):
ox, oy = [], []
# set fly boundary
#fly boundary bc
for i in range(fly_boundary[1][0], fly_boundary[0][0]+1):
ox.append(i)
oy.append(round((-26852 * i * 100000 + 52138230581680) / 1000000000000, 7))
#fly boundary cd
for i in range(fly_boundary[1][0], fly_boundary[2][0]+1):
ox.append(i)
oy.append(round((164070 * i * 100000 + 47048846126540) / 1000000000000, 7))
#fly boundary da
for i in range(fly_boundary[2][0], fly_boundary[3][0]+1):
ox.append(i)
oy.append(round((-27160 * i * 100000 + 52149065369280) / 1000000000000, 7))
#fly boundary ab
for i in range(fly_boundary[0][0], fly_boundary[3][0]+1):
ox.append(i)
oy.append(round((137371 * i * 100000 + 47753256419832) / 1000000000000, 7))
# set no fly zone
#no fly zone dc
for i in range(no_fly_zone[1][0], no_fly_zone[0][0]+1):
ox.append(i)
oy.append(round((-25089 * i * 100000 + 52091972956157) / 1000000000000, 7))
#no fly zone bc
for i in range(no_fly_zone[1][0], no_fly_zone[2][0]+1):
ox.append(i)
oy.append(round((188464 * i * 100000 + 46396511668528) / 1000000000000, 7))
#no fly zone ab
for i in range(no_fly_zone[2][0], no_fly_zone[3][0]+1):
ox.append(i)
oy.append(round((-23068 * i * 100000 + 52038857631596) / 1000000000000, 7))
return ox, oy
def start(self):
pos = Int32MultiArray()
pos_layout = MultiArrayLayout()
pos_dim = MultiArrayDimension()
pos.data = [v for nested in self.pos_t for v in nested]
pos_dim.label = 'pos'
pos_dim.size = len(self.pos_t)
pos_dim.stride = len(pos.data)
pos_layout.dim = [pos_dim]
pos_layout.data_offset = 0
pos.layout = pos_layout
controller_path_planning_sub = self.create_subscription(String, '/controller_path_planning', self.controller_path_planning_msg_callback,10)
# self.ox, self.oy = self.obstacle_map_init(self.fly_boundary_position, self.no_fly_zone)
self.calc_obstacle_map()
rx, ry = self.planning(-267155, 5142341, -266877, 5142192)
if len(rx) == len(ry):
current_pos = [-2.67155, 51.42341]
for i in range(len(rx) - 1 , -1, -1):
position_x = rx[i] / 100000
position_y = ry[i] / 100000
# d_x_no_fly_b = position_x - (-2.66737)
# d_y_no_fly_b = position_y - 51.42355
# d_x_no_fly_c = position_x - (-2.667)
# d_y_no_fly_c = position_y - 51.42285
# if (abs(d_x_no_fly_b) < 0.0001) and (abs(d_y_no_fly_b) < 0.0001):
# current_pos = [position_x, position_y]
# # position_xy = str(position_x) + "," + str(position_y)
# position_xy = '{},{}'.format(position_x, position_y)
# self.path_planning_controller_msg.data = position_xy
# self.get_logger().info('x={}, y={}'.format(position_x, position_y))
# self.path_planning_controller_pub.publish(self.path_planning_controller_msg)
# continue
# if (abs(d_x_no_fly_c) < 0.0001) and (abs(d_y_no_fly_c) < 0.0001):
# current_pos = [position_x, position_y]
# # position_xy = str(position_x) + "," + str(position_y)
# position_xy = '{},{}'.format(position_x, position_y)
# self.path_planning_controller_msg.data = position_xy
# self.get_logger().info('x={}, y={}'.format(position_x, position_y))
# self.path_planning_controller_pub.publish(self.path_planning_controller_msg)
# continue
if math.sqrt((current_pos[0] - position_x)**2 + (current_pos[1] - position_y)**2) > 0.0006:
current_pos = [position_x, position_y]
# position_xy = str(position_x) + "," + str(position_y)
position_xy = '{},{}'.format(position_x, position_y)
self.path_planning_controller_msg.data = position_xy
self.get_logger().info('x={}, y={}'.format(position_x, position_y))
self.path_planning_controller_pub.publish(self.path_planning_controller_msg)
# self.pos_list_pub.publish(pos)
# self.path_planning_controller_msg.data = 'pos list finished'
# self.path_planning_controller_pub.publish(self.path_planning_controller_msg)
def controller_path_planning_msg_callback(self, msg):
controller_path_planning_msg = msg.data.split(",")
if controller_path_planning_msg[0] == 'return_home':
cur_lon = round(float(controller_path_planning_msg[2]) * 100000)
cur_lat = round(float(controller_path_planning_msg[1]) * 100000)
self.path_planning_home(cur_lon, cur_lat)
self.path_planning_controller_msg.data = 'return home path planning finished'
self.path_planning_controller_pub.publish(self.path_planning_controller_msg)
def path_planning_home(self, cur_lon, cur_lat):
rx, ry = self.planning(cur_lon, cur_lat, -267155, 5142341)
if len(rx) == len(ry):
cur_lon = cur_lon / 100000
cur_lat = cur_lat / 100000
current_pos = [cur_lon, cur_lat]
for i in range(len(rx) - 1 , -1, -1):
position_x = rx[i] / 100000
position_y = ry[i] / 100000
if math.sqrt((current_pos[0] - position_x)**2 + (current_pos[1] - position_y)**2) > 0.0006:
current_pos = [position_x, position_y]
# position_xy = str(position_x) + "," + str(position_y)
position_xy = '{},{}'.format(position_x, position_y)
self.path_planning_controller_msg.data = position_xy
self.get_logger().info('x={}, y={}'.format(position_x, position_y))
self.path_planning_controller_pub.publish(self.path_planning_controller_msg)
def main(args=None):
rclpy.init(args=args)
pathplanning_node = PathPlanning()
pathplanning_node.start()
rclpy.spin(pathplanning_node)
if __name__ == '__main__':
main()
# 用法
# a_star = AStar(ox, oy, resolution, rr)
# rx, ry = a_star.planning(sx, sy, gx, gy)