python-motion-planning 1.0__py3-none-any.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- curve_generation/__init__.py +9 -0
- curve_generation/bezier_curve.py +131 -0
- curve_generation/bspline_curve.py +271 -0
- curve_generation/cubic_spline.py +128 -0
- curve_generation/curve.py +64 -0
- curve_generation/dubins_curve.py +348 -0
- curve_generation/fem_pos_smooth.py +114 -0
- curve_generation/polynomial_curve.py +226 -0
- curve_generation/reeds_shepp.py +736 -0
- global_planner/__init__.py +3 -0
- global_planner/evolutionary_search/__init__.py +4 -0
- global_planner/evolutionary_search/aco.py +186 -0
- global_planner/evolutionary_search/evolutionary_search.py +87 -0
- global_planner/evolutionary_search/pso.py +356 -0
- global_planner/graph_search/__init__.py +28 -0
- global_planner/graph_search/a_star.py +124 -0
- global_planner/graph_search/d_star.py +291 -0
- global_planner/graph_search/d_star_lite.py +188 -0
- global_planner/graph_search/dijkstra.py +77 -0
- global_planner/graph_search/gbfs.py +78 -0
- global_planner/graph_search/graph_search.py +87 -0
- global_planner/graph_search/jps.py +165 -0
- global_planner/graph_search/lazy_theta_star.py +114 -0
- global_planner/graph_search/lpa_star.py +230 -0
- global_planner/graph_search/s_theta_star.py +133 -0
- global_planner/graph_search/theta_star.py +171 -0
- global_planner/graph_search/voronoi.py +200 -0
- global_planner/sample_search/__init__.py +6 -0
- global_planner/sample_search/informed_rrt.py +152 -0
- global_planner/sample_search/rrt.py +151 -0
- global_planner/sample_search/rrt_connect.py +147 -0
- global_planner/sample_search/rrt_star.py +77 -0
- global_planner/sample_search/sample_search.py +135 -0
- local_planner/__init__.py +19 -0
- local_planner/apf.py +144 -0
- local_planner/ddpg.py +630 -0
- local_planner/dqn.py +687 -0
- local_planner/dwa.py +212 -0
- local_planner/local_planner.py +262 -0
- local_planner/lqr.py +146 -0
- local_planner/mpc.py +214 -0
- local_planner/pid.py +158 -0
- local_planner/rpp.py +147 -0
- python_motion_planning-1.0.dist-info/LICENSE +674 -0
- python_motion_planning-1.0.dist-info/METADATA +873 -0
- python_motion_planning-1.0.dist-info/RECORD +65 -0
- python_motion_planning-1.0.dist-info/WHEEL +5 -0
- python_motion_planning-1.0.dist-info/top_level.txt +4 -0
- utils/__init__.py +19 -0
- utils/agent/__init__.py +0 -0
- utils/agent/agent.py +135 -0
- utils/environment/__init__.py +0 -0
- utils/environment/env.py +134 -0
- utils/environment/node.py +85 -0
- utils/environment/point2d.py +96 -0
- utils/environment/pose2d.py +91 -0
- utils/helper/__init__.py +3 -0
- utils/helper/math_helper.py +65 -0
- utils/planner/__init__.py +0 -0
- utils/planner/control_factory.py +31 -0
- utils/planner/curve_factory.py +29 -0
- utils/planner/planner.py +40 -0
- utils/planner/search_factory.py +51 -0
- utils/plot/__init__.py +0 -0
- utils/plot/plot.py +274 -0
|
@@ -0,0 +1,151 @@
|
|
|
1
|
+
"""
|
|
2
|
+
@file: rrt.py
|
|
3
|
+
@breif: RRT motion planning
|
|
4
|
+
@author: Yang Haodong, Wu Maojia
|
|
5
|
+
@update: 2024.6.23
|
|
6
|
+
"""
|
|
7
|
+
import math
|
|
8
|
+
import numpy as np
|
|
9
|
+
|
|
10
|
+
from .sample_search import SampleSearcher
|
|
11
|
+
from python_motion_planning.utils import Env, Node
|
|
12
|
+
|
|
13
|
+
|
|
14
|
+
class RRT(SampleSearcher):
|
|
15
|
+
"""
|
|
16
|
+
Class for RRT motion planning.
|
|
17
|
+
|
|
18
|
+
Parameters:
|
|
19
|
+
start (tuple): start point coordinate
|
|
20
|
+
goal (tuple): goal point coordinate
|
|
21
|
+
env (Env): environment
|
|
22
|
+
max_dist (float): Maximum expansion distance one step
|
|
23
|
+
sample_num (int): Maximum number of sample points
|
|
24
|
+
goal_sample_rate (float): heuristic sample
|
|
25
|
+
|
|
26
|
+
Examples:
|
|
27
|
+
>>> import python_motion_planning as pmp
|
|
28
|
+
>>> planner = pmp.RRT((5, 5), (45, 25), pmp.Map(51, 31))
|
|
29
|
+
>>> cost, path, expand = planner.plan() # planning results only
|
|
30
|
+
>>> planner.plot.animation(path, str(planner), cost, expand) # animation
|
|
31
|
+
>>> planner.run() # run both planning and animation
|
|
32
|
+
|
|
33
|
+
References:
|
|
34
|
+
[1] Rapidly-Exploring Random Trees: A New Tool for Path Planning
|
|
35
|
+
"""
|
|
36
|
+
def __init__(self, start: tuple, goal: tuple, env: Env, max_dist: float = 0.5,
|
|
37
|
+
sample_num: int = 10000, goal_sample_rate: float = 0.05) -> None:
|
|
38
|
+
super().__init__(start, goal, env)
|
|
39
|
+
# Maximum expansion distance one step
|
|
40
|
+
self.max_dist = max_dist
|
|
41
|
+
# Maximum number of sample points
|
|
42
|
+
self.sample_num = sample_num
|
|
43
|
+
# heuristic sample
|
|
44
|
+
self.goal_sample_rate = goal_sample_rate
|
|
45
|
+
|
|
46
|
+
def __str__(self) -> str:
|
|
47
|
+
return "Rapidly-exploring Random Tree(RRT)"
|
|
48
|
+
|
|
49
|
+
def plan(self) -> tuple:
|
|
50
|
+
"""
|
|
51
|
+
RRT motion plan function.
|
|
52
|
+
|
|
53
|
+
Returns:
|
|
54
|
+
cost (float): path cost
|
|
55
|
+
path (list): planning path
|
|
56
|
+
expand (list): expanded (sampled) nodes list
|
|
57
|
+
"""
|
|
58
|
+
# Sampled list
|
|
59
|
+
sample_list = {self.start.current: self.start}
|
|
60
|
+
|
|
61
|
+
# main loop
|
|
62
|
+
for _ in range(self.sample_num):
|
|
63
|
+
# generate a random node in the map
|
|
64
|
+
node_rand = self.generateRandomNode()
|
|
65
|
+
|
|
66
|
+
# visited
|
|
67
|
+
if node_rand.current in sample_list:
|
|
68
|
+
continue
|
|
69
|
+
|
|
70
|
+
# generate new node
|
|
71
|
+
node_new = self.getNearest(list(sample_list.values()), node_rand)
|
|
72
|
+
if node_new:
|
|
73
|
+
sample_list[node_new.current] = node_new
|
|
74
|
+
dist = self.dist(node_new, self.goal)
|
|
75
|
+
# goal found
|
|
76
|
+
if dist <= self.max_dist and not self.isCollision(node_new, self.goal):
|
|
77
|
+
self.goal.parent = node_new.current
|
|
78
|
+
self.goal.g = node_new.g + self.dist(self.goal, node_new)
|
|
79
|
+
sample_list[self.goal.current] = self.goal
|
|
80
|
+
cost, path = self.extractPath(sample_list)
|
|
81
|
+
return cost, path, list(sample_list.values())
|
|
82
|
+
|
|
83
|
+
return 0, None, list(sample_list.values())
|
|
84
|
+
|
|
85
|
+
def run(self) -> None:
|
|
86
|
+
"""
|
|
87
|
+
Running both plannig and animation.
|
|
88
|
+
"""
|
|
89
|
+
cost, path, expand = self.plan()
|
|
90
|
+
self.plot.animation(path, str(self), cost, expand)
|
|
91
|
+
|
|
92
|
+
def generateRandomNode(self) -> Node:
|
|
93
|
+
"""
|
|
94
|
+
Generate a random node to extend exploring tree.
|
|
95
|
+
|
|
96
|
+
Returns:
|
|
97
|
+
node (Node): a random node based on sampling
|
|
98
|
+
"""
|
|
99
|
+
if np.random.random() > self.goal_sample_rate:
|
|
100
|
+
current = (np.random.uniform(self.delta, self.env.x_range - self.delta),
|
|
101
|
+
np.random.uniform(self.delta, self.env.y_range - self.delta))
|
|
102
|
+
return Node(current, None, 0, 0)
|
|
103
|
+
return self.goal
|
|
104
|
+
|
|
105
|
+
def getNearest(self, node_list: list, node: Node) -> Node:
|
|
106
|
+
"""
|
|
107
|
+
Get the node from `node_list` that is nearest to `node`.
|
|
108
|
+
|
|
109
|
+
Parameters:
|
|
110
|
+
node_list (list): exploring list
|
|
111
|
+
node (Node): currently generated node
|
|
112
|
+
|
|
113
|
+
Returns:
|
|
114
|
+
node (Node): nearest node
|
|
115
|
+
"""
|
|
116
|
+
# find nearest neighbor
|
|
117
|
+
dist = [self.dist(node, nd) for nd in node_list]
|
|
118
|
+
node_near = node_list[int(np.argmin(dist))]
|
|
119
|
+
|
|
120
|
+
# regular and generate new node
|
|
121
|
+
dist, theta = self.dist(node_near, node), self.angle(node_near, node)
|
|
122
|
+
dist = min(self.max_dist, dist)
|
|
123
|
+
node_new = Node((node_near.x + dist * math.cos(theta),
|
|
124
|
+
(node_near.y + dist * math.sin(theta))),
|
|
125
|
+
node_near.current, node_near.g + dist, 0)
|
|
126
|
+
|
|
127
|
+
# obstacle check
|
|
128
|
+
if self.isCollision(node_new, node_near):
|
|
129
|
+
return None
|
|
130
|
+
return node_new
|
|
131
|
+
|
|
132
|
+
def extractPath(self, closed_list: dict) -> tuple:
|
|
133
|
+
"""
|
|
134
|
+
Extract the path based on the CLOSED list.
|
|
135
|
+
|
|
136
|
+
Parameters:
|
|
137
|
+
closed_list (dict): CLOSED list
|
|
138
|
+
|
|
139
|
+
Returns
|
|
140
|
+
cost (float): the cost of planning path
|
|
141
|
+
path (list): the planning path
|
|
142
|
+
"""
|
|
143
|
+
node = closed_list[self.goal.current]
|
|
144
|
+
path = [node.current]
|
|
145
|
+
cost = node.g
|
|
146
|
+
while node != self.start:
|
|
147
|
+
node_parent = closed_list[node.parent]
|
|
148
|
+
node = node_parent
|
|
149
|
+
path.append(node.current)
|
|
150
|
+
|
|
151
|
+
return cost, path
|
|
@@ -0,0 +1,147 @@
|
|
|
1
|
+
"""
|
|
2
|
+
@file: rrt_connected.py
|
|
3
|
+
@breif: RRT-Connected motion planning
|
|
4
|
+
@author: Yang Haodong, Wu Maojia
|
|
5
|
+
@update: 2024.6.23
|
|
6
|
+
"""
|
|
7
|
+
import math
|
|
8
|
+
|
|
9
|
+
from .rrt import RRT
|
|
10
|
+
from python_motion_planning.utils import Env, Node
|
|
11
|
+
|
|
12
|
+
|
|
13
|
+
class RRTConnect(RRT):
|
|
14
|
+
"""
|
|
15
|
+
Class for RRT-Connect motion planning.
|
|
16
|
+
|
|
17
|
+
Parameters:
|
|
18
|
+
start (tuple): start point coordinate
|
|
19
|
+
goal (tuple): goal point coordinate
|
|
20
|
+
env (Env): environment
|
|
21
|
+
max_dist (float): Maximum expansion distance one step
|
|
22
|
+
sample_num (int): Maximum number of sample points
|
|
23
|
+
goal_sample_rate (float): heuristic sample
|
|
24
|
+
|
|
25
|
+
Examples:
|
|
26
|
+
>>> import python_motion_planning as pmp
|
|
27
|
+
>>> planner = pmp.RRTConnect((5, 5), (45, 25), pmp.Map(51, 31))
|
|
28
|
+
>>> cost, path, expand = planner.plan() # planning results only
|
|
29
|
+
>>> planner.plot.animation(path, str(planner), cost, expand) # animation
|
|
30
|
+
>>> planner.run() # run both planning and animation
|
|
31
|
+
|
|
32
|
+
References:
|
|
33
|
+
[1] RRT-Connect: An Efficient Approach to Single-Query Path Planning
|
|
34
|
+
"""
|
|
35
|
+
def __init__(self, start: tuple, goal: tuple, env: Env, max_dist: float = 0.5,
|
|
36
|
+
sample_num: int = 10000, goal_sample_rate: float = 0.05) -> None:
|
|
37
|
+
super().__init__(start, goal, env, max_dist, sample_num, goal_sample_rate)
|
|
38
|
+
|
|
39
|
+
def __str__(self) -> str:
|
|
40
|
+
return "RRT-Connect"
|
|
41
|
+
|
|
42
|
+
def plan(self) -> tuple:
|
|
43
|
+
"""
|
|
44
|
+
RRT-Connected motion plan function.
|
|
45
|
+
|
|
46
|
+
Returns:
|
|
47
|
+
cost (float): path cost
|
|
48
|
+
path (list): planning path
|
|
49
|
+
expand (list): expanded (sampled) nodes list
|
|
50
|
+
"""
|
|
51
|
+
# Sampled list forward
|
|
52
|
+
sample_list_f = {self.start.current: self.start}
|
|
53
|
+
# Sampled list backward
|
|
54
|
+
sample_list_b = {self.goal.current: self.goal}
|
|
55
|
+
|
|
56
|
+
for _ in range(self.sample_num):
|
|
57
|
+
# generate a random node in the map
|
|
58
|
+
node_rand = self.generateRandomNode()
|
|
59
|
+
# generate new node
|
|
60
|
+
node_new = self.getNearest(list(sample_list_f.values()), node_rand)
|
|
61
|
+
if node_new:
|
|
62
|
+
sample_list_f[node_new.current] = node_new
|
|
63
|
+
# backward exploring
|
|
64
|
+
node_new_b = self.getNearest(list(sample_list_b.values()), node_new)
|
|
65
|
+
if node_new_b:
|
|
66
|
+
sample_list_b[node_new_b.current] = node_new_b
|
|
67
|
+
|
|
68
|
+
# greedy extending
|
|
69
|
+
while True:
|
|
70
|
+
if node_new_b == node_new:
|
|
71
|
+
cost, path = self.extractPath(node_new, sample_list_b, sample_list_f)
|
|
72
|
+
expand = self.getExpand(list(sample_list_b.values()), list(sample_list_f.values()))
|
|
73
|
+
return cost, path, expand
|
|
74
|
+
|
|
75
|
+
dist = min(self.max_dist, self.dist(node_new, node_new_b))
|
|
76
|
+
theta = self.angle(node_new_b, node_new)
|
|
77
|
+
node_new_b2 = Node((node_new_b.x + dist * math.cos(theta),
|
|
78
|
+
(node_new_b.y + dist * math.sin(theta))),
|
|
79
|
+
node_new_b.current, node_new_b.g + dist, 0)
|
|
80
|
+
|
|
81
|
+
if not self.isCollision(node_new_b2, node_new_b):
|
|
82
|
+
sample_list_b[node_new_b2.current] = node_new_b2
|
|
83
|
+
node_new_b = node_new_b2
|
|
84
|
+
else:
|
|
85
|
+
break
|
|
86
|
+
|
|
87
|
+
if len(sample_list_b) < len(sample_list_f):
|
|
88
|
+
sample_list_f, sample_list_b = sample_list_b, sample_list_f
|
|
89
|
+
|
|
90
|
+
return 0, None, None
|
|
91
|
+
|
|
92
|
+
def extractPath(self, boundary: Node, sample_list_b: dict, sample_list_f: dict) -> tuple:
|
|
93
|
+
"""
|
|
94
|
+
Extract the path based on the CLOSED set.
|
|
95
|
+
|
|
96
|
+
Parameters:
|
|
97
|
+
boundary (Node): the boundary node
|
|
98
|
+
sample_list_b (dict): Sample list backward
|
|
99
|
+
sample_list_f (dict): Sample list forward
|
|
100
|
+
|
|
101
|
+
Returns:
|
|
102
|
+
cost (float): the cost of planning path
|
|
103
|
+
path (list): the planning path
|
|
104
|
+
"""
|
|
105
|
+
if self.start.current in sample_list_b:
|
|
106
|
+
sample_list_f, sample_list_b = sample_list_b, sample_list_f
|
|
107
|
+
|
|
108
|
+
# forward
|
|
109
|
+
node = sample_list_f[boundary.current]
|
|
110
|
+
path_f = [node.current]
|
|
111
|
+
cost = node.g
|
|
112
|
+
while node != self.start:
|
|
113
|
+
node_parent = sample_list_f[node.parent]
|
|
114
|
+
node = node_parent
|
|
115
|
+
path_f.append(node.current)
|
|
116
|
+
|
|
117
|
+
# backward
|
|
118
|
+
node = sample_list_b[boundary.current]
|
|
119
|
+
path_b = []
|
|
120
|
+
cost += node.g
|
|
121
|
+
while node != self.goal:
|
|
122
|
+
node_parent = sample_list_b[node.parent]
|
|
123
|
+
node = node_parent
|
|
124
|
+
path_b.append(node.current)
|
|
125
|
+
|
|
126
|
+
return cost, list(reversed(path_f)) + path_b
|
|
127
|
+
|
|
128
|
+
def getExpand(self, sample_list_b: list, sample_list_f: list) -> list:
|
|
129
|
+
"""
|
|
130
|
+
Get the expand list from sample list.
|
|
131
|
+
|
|
132
|
+
Parameters:
|
|
133
|
+
sample_list_b (list): Sample list backward
|
|
134
|
+
sample_list_f (list): Sample list forward
|
|
135
|
+
|
|
136
|
+
Returns:
|
|
137
|
+
expand (list): expand list
|
|
138
|
+
"""
|
|
139
|
+
expand = []
|
|
140
|
+
tree_size = max(len(sample_list_f), len(sample_list_b))
|
|
141
|
+
for k in range(tree_size):
|
|
142
|
+
if k < len(sample_list_f):
|
|
143
|
+
expand.append(sample_list_f[k])
|
|
144
|
+
if k < len(sample_list_b):
|
|
145
|
+
expand.append(sample_list_b[k])
|
|
146
|
+
|
|
147
|
+
return expand
|
|
@@ -0,0 +1,77 @@
|
|
|
1
|
+
"""
|
|
2
|
+
@file: rrt_star.py
|
|
3
|
+
@breif: RRT-Star motion planning
|
|
4
|
+
@author: Yang Haodong, Wu Maojia
|
|
5
|
+
@update: 2024.6.23
|
|
6
|
+
"""
|
|
7
|
+
from .rrt import RRT
|
|
8
|
+
from python_motion_planning.utils import Env, Node
|
|
9
|
+
|
|
10
|
+
|
|
11
|
+
class RRTStar(RRT):
|
|
12
|
+
"""
|
|
13
|
+
Class for RRT-Star motion planning.
|
|
14
|
+
|
|
15
|
+
Parameters:
|
|
16
|
+
start (tuple): start point coordinate
|
|
17
|
+
goal (tuple): goal point coordinate
|
|
18
|
+
env (Env): environment
|
|
19
|
+
max_dist (float): Maximum expansion distance one step
|
|
20
|
+
sample_num (int): Maximum number of sample points
|
|
21
|
+
r (float): optimization radius
|
|
22
|
+
goal_sample_rate (float): heuristic sample
|
|
23
|
+
|
|
24
|
+
Examples:
|
|
25
|
+
>>> import python_motion_planning as pmp
|
|
26
|
+
>>> planner = pmp.RRTStar((5, 5), (45, 25), pmp.Map(51, 31))
|
|
27
|
+
>>> cost, path, expand = planner.plan() # planning results only
|
|
28
|
+
>>> planner.plot.animation(path, str(planner), cost, expand) # animation
|
|
29
|
+
>>> planner.run() # run both planning and animation
|
|
30
|
+
|
|
31
|
+
References:
|
|
32
|
+
[1] Sampling-based algorithms for optimal motion planning
|
|
33
|
+
"""
|
|
34
|
+
def __init__(self, start: tuple, goal: tuple, env: Env, max_dist: float = 0.5,
|
|
35
|
+
sample_num: int = 10000, r: float = 10.0, goal_sample_rate: float = 0.05) -> None:
|
|
36
|
+
super().__init__(start, goal, env, max_dist, sample_num, goal_sample_rate)
|
|
37
|
+
# optimization radius
|
|
38
|
+
self.r = r
|
|
39
|
+
|
|
40
|
+
def __str__(self) -> str:
|
|
41
|
+
return "RRT*"
|
|
42
|
+
|
|
43
|
+
def getNearest(self, node_list: list, node: Node) -> Node:
|
|
44
|
+
"""
|
|
45
|
+
Get the node from `node_list` that is nearest to `node` with optimization.
|
|
46
|
+
|
|
47
|
+
Parameters:
|
|
48
|
+
node_list (list): exploring list
|
|
49
|
+
node (Node): currently generated node
|
|
50
|
+
|
|
51
|
+
Returns:
|
|
52
|
+
node (Node): nearest node
|
|
53
|
+
"""
|
|
54
|
+
node_new = super().getNearest(node_list, node)
|
|
55
|
+
if node_new:
|
|
56
|
+
# rewire optimization
|
|
57
|
+
for node_n in node_list:
|
|
58
|
+
# inside the optimization circle
|
|
59
|
+
new_dist = self.dist(node_n, node_new)
|
|
60
|
+
if new_dist < self.r:
|
|
61
|
+
cost = node_n.g + new_dist
|
|
62
|
+
# update new sample node's cost and parent
|
|
63
|
+
if node_new.g > cost and not self.isCollision(node_n, node_new):
|
|
64
|
+
node_new.parent = node_n.current
|
|
65
|
+
node_new.g = cost
|
|
66
|
+
else:
|
|
67
|
+
# update nodes' cost inside the radius
|
|
68
|
+
cost = node_new.g + new_dist
|
|
69
|
+
if node_n.g > cost and not self.isCollision(node_n, node_new):
|
|
70
|
+
node_n.parent = node_new.current
|
|
71
|
+
node_n.g = cost
|
|
72
|
+
else:
|
|
73
|
+
continue
|
|
74
|
+
return node_new
|
|
75
|
+
else:
|
|
76
|
+
return None
|
|
77
|
+
|
|
@@ -0,0 +1,135 @@
|
|
|
1
|
+
"""
|
|
2
|
+
@file: graph_search.py
|
|
3
|
+
@breif: Base class for planner based on graph searching
|
|
4
|
+
@author: Winter
|
|
5
|
+
@update: 2023.1.17
|
|
6
|
+
"""
|
|
7
|
+
import numpy as np
|
|
8
|
+
from itertools import combinations
|
|
9
|
+
import math
|
|
10
|
+
|
|
11
|
+
from python_motion_planning.utils import Env, Node, Planner
|
|
12
|
+
|
|
13
|
+
class SampleSearcher(Planner):
|
|
14
|
+
"""
|
|
15
|
+
Base class for planner based on sample searching.
|
|
16
|
+
|
|
17
|
+
Parameters:
|
|
18
|
+
start (tuple): start point coordinate
|
|
19
|
+
goal (tuple): goal point coordinate
|
|
20
|
+
env (Env): environment
|
|
21
|
+
"""
|
|
22
|
+
def __init__(self, start: tuple, goal: tuple, env: Env, delta: float=0.5) -> None:
|
|
23
|
+
super().__init__(start, goal, env)
|
|
24
|
+
# inflation bias
|
|
25
|
+
self.delta = delta
|
|
26
|
+
|
|
27
|
+
def isCollision(self, node1: Node, node2: Node) -> bool:
|
|
28
|
+
"""
|
|
29
|
+
Judge collision when moving from node1 to node2.
|
|
30
|
+
|
|
31
|
+
Parameters:
|
|
32
|
+
node1 (Node): node 1
|
|
33
|
+
node2 (Node): node 2
|
|
34
|
+
|
|
35
|
+
Returns:
|
|
36
|
+
collision (bool): True if collision exists else False
|
|
37
|
+
"""
|
|
38
|
+
if self.isInsideObs(node1) or self.isInsideObs(node2):
|
|
39
|
+
return True
|
|
40
|
+
|
|
41
|
+
for rect in self.env.obs_rect:
|
|
42
|
+
if self.isInterRect(node1, node2, rect):
|
|
43
|
+
return True
|
|
44
|
+
|
|
45
|
+
for circle in self.env.obs_circ:
|
|
46
|
+
if self.isInterCircle(node1, node2, circle):
|
|
47
|
+
return True
|
|
48
|
+
|
|
49
|
+
return False
|
|
50
|
+
|
|
51
|
+
def isInsideObs(self, node: Node) -> bool:
|
|
52
|
+
"""
|
|
53
|
+
Judge whether a node inside tht obstacles or not.
|
|
54
|
+
|
|
55
|
+
Parameters:
|
|
56
|
+
node (Node): node
|
|
57
|
+
|
|
58
|
+
Returns:
|
|
59
|
+
inside (bool): True if inside the obstacles else False
|
|
60
|
+
"""
|
|
61
|
+
x, y = node.current
|
|
62
|
+
|
|
63
|
+
for (ox, oy, r) in self.env.obs_circ:
|
|
64
|
+
if math.hypot(x - ox, y - oy) <= r + self.delta:
|
|
65
|
+
return True
|
|
66
|
+
|
|
67
|
+
for (ox, oy, w, h) in self.env.obs_rect:
|
|
68
|
+
if 0 <= x - (ox - self.delta) <= w + 2 * self.delta \
|
|
69
|
+
and 0 <= y - (oy - self.delta) <= h + 2 * self.delta:
|
|
70
|
+
return True
|
|
71
|
+
|
|
72
|
+
for (ox, oy, w, h) in self.env.boundary:
|
|
73
|
+
if 0 <= x - (ox - self.delta) <= w + 2 * self.delta \
|
|
74
|
+
and 0 <= y - (oy - self.delta) <= h + 2 * self.delta:
|
|
75
|
+
return True
|
|
76
|
+
|
|
77
|
+
return False
|
|
78
|
+
|
|
79
|
+
def isInterRect(self, node1: Node, node2: Node, rect: list) -> bool:
|
|
80
|
+
# obstacle and it's vertex
|
|
81
|
+
ox, oy, w, h = rect
|
|
82
|
+
vertex = [[ox - self.delta, oy - self.delta],
|
|
83
|
+
[ox + w + self.delta, oy - self.delta],
|
|
84
|
+
[ox + w + self.delta, oy + h + self.delta],
|
|
85
|
+
[ox - self.delta, oy + h + self.delta]]
|
|
86
|
+
|
|
87
|
+
# node
|
|
88
|
+
x1, y1 = node1.current
|
|
89
|
+
x2, y2 = node2.current
|
|
90
|
+
|
|
91
|
+
def cross(p1, p2, p3):
|
|
92
|
+
x1 = p2[0] - p1[0]
|
|
93
|
+
y1 = p2[1] - p1[1]
|
|
94
|
+
x2 = p3[0] - p1[0]
|
|
95
|
+
y2 = p3[1] - p1[1]
|
|
96
|
+
return x1 * y2 - x2 * y1
|
|
97
|
+
|
|
98
|
+
for v1, v2 in combinations(vertex, 2):
|
|
99
|
+
# rapid repulsion
|
|
100
|
+
if max(x1, x2) >= min(v1[0], v2[0]) and \
|
|
101
|
+
min(x1, x2) <= max(v1[0], v2[0]) and \
|
|
102
|
+
max(y1, y2) >= min(v1[1], v2[1]) and \
|
|
103
|
+
min(y1, y2) <= max(v1[1], v2[1]):
|
|
104
|
+
# cross
|
|
105
|
+
if cross(v1, v2, node1.current) * cross(v1, v2, node2.current) <= 0 and \
|
|
106
|
+
cross(node1.current, node2.current, v1) * cross(node1.current, node2.current, v2) <= 0:
|
|
107
|
+
return True
|
|
108
|
+
|
|
109
|
+
return False
|
|
110
|
+
|
|
111
|
+
def isInterCircle(self, node1: Node, node2: Node, circle: list) -> bool:
|
|
112
|
+
# obstacle
|
|
113
|
+
ox, oy, r = circle
|
|
114
|
+
|
|
115
|
+
# origin
|
|
116
|
+
x, y = node1.current
|
|
117
|
+
|
|
118
|
+
# direction
|
|
119
|
+
dx = node2.x - node1.x
|
|
120
|
+
dy = node2.y - node1.y
|
|
121
|
+
d = [dx, dy]
|
|
122
|
+
d2 = np.dot(d, d)
|
|
123
|
+
|
|
124
|
+
if d2 == 0:
|
|
125
|
+
return False
|
|
126
|
+
|
|
127
|
+
# projection
|
|
128
|
+
t = np.dot([ox - x, oy - y], d) / d2
|
|
129
|
+
if 0 <= t <= 1:
|
|
130
|
+
shot = Node((x + t * dx, y + t * dy), None, None, None)
|
|
131
|
+
center = Node((ox, oy), None, None, None)
|
|
132
|
+
if self.dist(shot, center) <= r + self.delta:
|
|
133
|
+
return True
|
|
134
|
+
|
|
135
|
+
return False
|
|
@@ -0,0 +1,19 @@
|
|
|
1
|
+
from .dwa import DWA
|
|
2
|
+
from .pid import PID
|
|
3
|
+
from .apf import APF
|
|
4
|
+
from .rpp import RPP
|
|
5
|
+
from .lqr import LQR
|
|
6
|
+
from .mpc import MPC
|
|
7
|
+
from .ddpg import DDPG
|
|
8
|
+
from .dqn import DQNPlanner
|
|
9
|
+
|
|
10
|
+
__all__ = [
|
|
11
|
+
"DWA",
|
|
12
|
+
"PID",
|
|
13
|
+
"APF",
|
|
14
|
+
"RPP",
|
|
15
|
+
"LQR",
|
|
16
|
+
"MPC",
|
|
17
|
+
"DDPG",
|
|
18
|
+
"DQNPlanner"
|
|
19
|
+
]
|
local_planner/apf.py
ADDED
|
@@ -0,0 +1,144 @@
|
|
|
1
|
+
"""
|
|
2
|
+
@file: apf.py
|
|
3
|
+
@breif: Artificial Potential Field(APF) motion planning
|
|
4
|
+
@author: Yang Haodong, Wu Maojia
|
|
5
|
+
@update: 2024.5.21
|
|
6
|
+
"""
|
|
7
|
+
import math
|
|
8
|
+
import numpy as np
|
|
9
|
+
from scipy.spatial.distance import cdist
|
|
10
|
+
|
|
11
|
+
from .local_planner import LocalPlanner
|
|
12
|
+
from python_motion_planning.utils import Env
|
|
13
|
+
|
|
14
|
+
class APF(LocalPlanner):
|
|
15
|
+
"""
|
|
16
|
+
Class for Artificial Potential Field(APF) motion planning.
|
|
17
|
+
|
|
18
|
+
Parameters:
|
|
19
|
+
start (tuple): start point coordinate
|
|
20
|
+
goal (tuple): goal point coordinate
|
|
21
|
+
env (Env): environment
|
|
22
|
+
heuristic_type (str): heuristic function type
|
|
23
|
+
**params: other parameters can be found in the parent class LocalPlanner
|
|
24
|
+
|
|
25
|
+
Examples:
|
|
26
|
+
>>> from python_motion_planning.utils import Grid
|
|
27
|
+
>>> from python_motion_planning.local_planner import APF
|
|
28
|
+
>>> start = (5, 5, 0)
|
|
29
|
+
>>> goal = (45, 25, 0)
|
|
30
|
+
>>> env = Grid(51, 31)
|
|
31
|
+
>>> planner = APF(start, goal, env)
|
|
32
|
+
>>> planner.run()
|
|
33
|
+
"""
|
|
34
|
+
def __init__(self, start: tuple, goal: tuple, env: Env, heuristic_type: str = "euclidean", **params) -> None:
|
|
35
|
+
super().__init__(start, goal, env, heuristic_type, **params)
|
|
36
|
+
# APF parameters
|
|
37
|
+
self.zeta = 1.0
|
|
38
|
+
self.eta = 1.0
|
|
39
|
+
self.d_0 = 1.0
|
|
40
|
+
|
|
41
|
+
# global planner
|
|
42
|
+
g_start = (start[0], start[1])
|
|
43
|
+
g_goal = (goal[0], goal[1])
|
|
44
|
+
self.g_planner = {"planner_name": "a_star", "start": g_start, "goal": g_goal, "env": env}
|
|
45
|
+
self.path = self.g_path[::-1]
|
|
46
|
+
|
|
47
|
+
def __str__(self) -> str:
|
|
48
|
+
return "Artificial Potential Field(APF)"
|
|
49
|
+
|
|
50
|
+
def plan(self):
|
|
51
|
+
"""
|
|
52
|
+
APF motion plan function.
|
|
53
|
+
|
|
54
|
+
Returns:
|
|
55
|
+
flag (bool): planning successful if true else failed
|
|
56
|
+
pose_list (list): history poses of robot
|
|
57
|
+
"""
|
|
58
|
+
dt = self.params["TIME_STEP"]
|
|
59
|
+
for _ in range(self.params["MAX_ITERATION"]):
|
|
60
|
+
# break until goal reached
|
|
61
|
+
if self.reachGoal(tuple(self.robot.state.squeeze(axis=1)[0:3]), self.goal):
|
|
62
|
+
return True, self.robot.history_pose
|
|
63
|
+
|
|
64
|
+
# compute the tatget pose and force at the current step
|
|
65
|
+
lookahead_pt, _, _ = self.getLookaheadPoint()
|
|
66
|
+
rep_force = self.getRepulsiveForce()
|
|
67
|
+
attr_force = self.getAttractiveForce(np.array(self.robot.position), np.array(lookahead_pt))
|
|
68
|
+
net_force = self.zeta * attr_force + self.eta * rep_force
|
|
69
|
+
|
|
70
|
+
# compute desired velocity
|
|
71
|
+
v, theta = self.robot.v, self.robot.theta
|
|
72
|
+
new_v = np.array([v * math.cos(theta), v * math.sin(theta)]) + net_force
|
|
73
|
+
new_v /= np.linalg.norm(new_v)
|
|
74
|
+
new_v *= self.params["MAX_V"]
|
|
75
|
+
theta_d = math.atan2(new_v[1], new_v[0])
|
|
76
|
+
|
|
77
|
+
# calculate velocity command
|
|
78
|
+
e_theta = self.regularizeAngle(self.robot.theta - self.goal[2])
|
|
79
|
+
if not self.shouldMoveToGoal(self.robot.position, self.goal):
|
|
80
|
+
if not self.shouldRotateToPath(abs(e_theta)):
|
|
81
|
+
u = np.array([[0], [0]])
|
|
82
|
+
else:
|
|
83
|
+
u = np.array([[0], [self.angularRegularization(e_theta / dt)]])
|
|
84
|
+
else:
|
|
85
|
+
e_theta = self.regularizeAngle(theta_d - self.robot.theta)
|
|
86
|
+
if self.shouldRotateToPath(abs(e_theta)):
|
|
87
|
+
u = np.array([[0], [self.angularRegularization(e_theta / dt)]])
|
|
88
|
+
else:
|
|
89
|
+
v_d = np.linalg.norm(new_v)
|
|
90
|
+
u = np.array([[self.linearRegularization(v_d)], [self.angularRegularization(e_theta / dt)]])
|
|
91
|
+
|
|
92
|
+
# feed into robotic kinematic
|
|
93
|
+
self.robot.kinematic(u, dt)
|
|
94
|
+
|
|
95
|
+
return False, None
|
|
96
|
+
|
|
97
|
+
def run(self):
|
|
98
|
+
"""
|
|
99
|
+
Running both plannig and animation.
|
|
100
|
+
"""
|
|
101
|
+
_, history_pose = self.plan()
|
|
102
|
+
if not history_pose:
|
|
103
|
+
raise ValueError("Path not found and planning failed!")
|
|
104
|
+
|
|
105
|
+
path = np.array(history_pose)[:, 0:2]
|
|
106
|
+
cost = np.sum(np.sqrt(np.sum(np.diff(path, axis=0)**2, axis=1, keepdims=True)))
|
|
107
|
+
self.plot.plotPath(self.path, path_color="r", path_style="--")
|
|
108
|
+
self.plot.animation(path, str(self), cost, history_pose=history_pose)
|
|
109
|
+
|
|
110
|
+
def getRepulsiveForce(self) -> np.ndarray:
|
|
111
|
+
"""
|
|
112
|
+
Get the repulsive force of APF.
|
|
113
|
+
|
|
114
|
+
Returns:
|
|
115
|
+
rep_force (np.ndarray): repulsive force of APF
|
|
116
|
+
"""
|
|
117
|
+
obstacles = np.array(list(self.obstacles))
|
|
118
|
+
cur_pos = np.array([[self.robot.px, self.robot.py]])
|
|
119
|
+
D = cdist(obstacles, cur_pos)
|
|
120
|
+
rep_force = (1 / D - 1 / self.d_0) * (1 / D) ** 2 * (cur_pos - obstacles)
|
|
121
|
+
valid_mask = np.argwhere((1 / D - 1 / self.d_0) > 0)[:, 0]
|
|
122
|
+
rep_force = np.sum(rep_force[valid_mask, :], axis=0)
|
|
123
|
+
|
|
124
|
+
if not np.all(rep_force == 0):
|
|
125
|
+
rep_force = rep_force / np.linalg.norm(rep_force)
|
|
126
|
+
|
|
127
|
+
return rep_force
|
|
128
|
+
|
|
129
|
+
def getAttractiveForce(self, cur_pos: np.ndarray, tgt_pos: np.ndarray) -> np.ndarray:
|
|
130
|
+
"""
|
|
131
|
+
Get the attractive force of APF.
|
|
132
|
+
|
|
133
|
+
Parameters:
|
|
134
|
+
cur_pos (np.ndarray): current position of robot
|
|
135
|
+
tgt_pos (np.ndarray): target position of robot
|
|
136
|
+
|
|
137
|
+
Returns
|
|
138
|
+
attr_force (np.ndarray): attractive force
|
|
139
|
+
"""
|
|
140
|
+
attr_force = tgt_pos - cur_pos
|
|
141
|
+
if not np.all(attr_force == 0):
|
|
142
|
+
attr_force = attr_force / np.linalg.norm(attr_force)
|
|
143
|
+
|
|
144
|
+
return attr_force
|