1
1
import math
2
2
from collections import namedtuple
3
3
from roboticstoolbox .mobile .OccGrid import PolygonMap
4
- import rvcprint
4
+
5
+ # import rvcprint
5
6
from roboticstoolbox import *
6
7
import numpy as np
7
8
import matplotlib .pyplot as plt
8
9
9
10
from spatialmath import Polygon2 , SE2 , base
10
11
from roboticstoolbox .mobile .PlannerBase import PlannerBase
11
12
from roboticstoolbox .mobile .DubinsPlanner import DubinsPlanner
13
+
12
14
# from roboticstoolbox.mobile.OccupancyGrid import OccupancyGrid
13
15
from pgraph import DGraph
14
16
15
- class RRTPlanner (PlannerBase ):
16 17
17
- def __init__ (self ,
18
- map = None ,
19
- vehicle = None ,
20
- curvature = None ,
21
- expand_dis = 3.0 ,
22
- path_resolution = 0.5 ,
23
- stepsize = 0.2 ,
24
- showsamples = False ,
25
- npoints = 50 , ** kwargs ):
18
+ class RRTPlanner (PlannerBase ):
19
+ def __init__ (
20
+ self ,
21
+ map = None ,
22
+ vehicle = None ,
23
+ curvature = None ,
24
+ expand_dis = 3.0 ,
25
+ path_resolution = 0.5 ,
26
+ stepsize = 0.2 ,
27
+ showsamples = False ,
28
+ npoints = 50 ,
29
+ ** kwargs
30
+ ):
26
31
27
32
super ().__init__ (ndims = 2 , ** kwargs )
28
33
@@ -32,7 +37,7 @@ def __init__(self,
32
37
self .map = map
33
38
self .showsamples = showsamples
34
39
35
- self .g = DGraph (metric = ' SE2' )
40
+ self .g = DGraph (metric = " SE2" )
36
41
37
42
self .vehicle = vehicle
38
43
if curvature is None :
@@ -41,7 +46,7 @@ def __init__(self,
41
46
else :
42
47
curvature = 1
43
48
44
- print (' curvature' , curvature )
49
+ print (" curvature" , curvature )
45
50
self .dubins = DubinsPlanner (curvature = curvature , stepsize = stepsize )
46
51
47
52
# self.goal_yaw_th = np.deg2rad(1.0)
@@ -68,7 +73,7 @@ def plan(self, goal, animation=True, search_until_npoints=True):
68
73
random_point = self .qrandom_free ()
69
74
70
75
if self .showsamples :
71
- plt .plot (random_point [0 ], random_point [1 ], 'ok' , markersize = 2 )
76
+ plt .plot (random_point [0 ], random_point [1 ], "ok" , markersize = 2 )
72
77
73
78
vnearest , d = self .g .closest (random_point )
74
79
@@ -100,8 +105,7 @@ def plan(self, goal, animation=True, search_until_npoints=True):
100
105
self .g .add_edge (vnew , vnearest , cost = pstatus .length )
101
106
vnew .path = path
102
107
103
-
104
- self .vehicle .polygon (random_point ).plot (color = 'b' , alpha = 0.1 )
108
+ self .vehicle .polygon (random_point ).plot (color = "b" , alpha = 0.1 )
105
109
plt .show ()
106
110
107
111
self .progress_end ()
@@ -119,7 +123,9 @@ def query(self, start):
119
123
if vertex .path is not None :
120
124
path = np .vstack ((path , vertex .path ))
121
125
122
- status = namedtuple ('RRTStatus' , ['length' , 'initial_d' , 'vertices' ])(cost , d , vpath )
126
+ status = namedtuple ("RRTStatus" , ["length" , "initial_d" , "vertices" ])(
127
+ cost , d , vpath
128
+ )
123
129
124
130
return path , status
125
131
@@ -142,7 +148,8 @@ def calc_dist_to_goal(self, x, y):
142
148
def qrandom (self ):
143
149
return self .random .uniform (
144
150
low = (self .map .workspace [0 ], self .map .workspace [2 ], - np .pi ),
145
- high = (self .map .workspace [1 ], self .map .workspace [3 ], np .pi ))
151
+ high = (self .map .workspace [1 ], self .map .workspace [3 ], np .pi ),
152
+ )
146
153
147
154
def qrandom_free (self ):
148
155
@@ -155,23 +162,24 @@ def qrandom_free(self):
155
162
def iscollision (self , q ):
156
163
return self .map .iscollision (self .vehicle .polygon (q ))
157
164
165
+
158
166
if __name__ == "__main__" :
159
167
160
168
from roboticstoolbox .mobile .Vehicle import Bicycle
161
169
162
170
# start and goal configuration
163
- qs = (2 , 8 , - np .pi / 2 )
164
- qg = (8 , 2 , - np .pi / 2 )
171
+ qs = (2 , 8 , - np .pi / 2 )
172
+ qg = (8 , 2 , - np .pi / 2 )
165
173
166
174
# obstacle map
167
175
map = PolygonMap (workspace = [0 , 10 ])
168
176
map .add ([(5 , 50 ), (5 , 6 ), (6 , 6 ), (6 , 50 )])
169
177
# map.add([(5, 0), (6, 0), (6, 4), (5, 4)])
170
178
map .add ([(5 , 4 ), (5 , - 50 ), (6 , - 50 ), (6 , 4 )])
171
179
172
- l = 3
173
- w = 1.5
174
- v0 = Polygon2 ([(- l / 2 , w / 2 ), (- l / 2 , - w / 2 ), (l / 2 , - w / 2 ), (l / 2 , w / 2 )])
180
+ l = 3
181
+ w = 1.5
182
+ v0 = Polygon2 ([(- l / 2 , w / 2 ), (- l / 2 , - w / 2 ), (l / 2 , - w / 2 ), (l / 2 , w / 2 )])
175
183
176
184
vehicle = Bicycle (steer_max = 0.4 , l = 2 , polygon = v0 )
177
185
@@ -181,5 +189,4 @@ def iscollision(self, q):
181
189
path , status = rrt .query (start = qs )
182
190
rrt .plot (path )
183
191
184
-
185
- plt .show (block = True )
192
+ plt .show (block = True )
0 commit comments