2525
2626
2727class RRTPlanner (PlannerBase ):
28- """
28+ r """
2929 Rapidly exploring tree planner
3030
3131 :param map: occupancy grid
@@ -36,8 +36,6 @@ class RRTPlanner(PlannerBase):
3636 :type curvature: float, optional
3737 :param stepsize: spacing between points on the path, defaults to 0.2
3838 :type stepsize: float, optional
39- :param showsamples: shows vehicle polygons for all random samples, defaults to False
40- :type showsamples: bool, optional
4139 :param npoints: number of vertices in random tree, defaults to 50
4240 :type npoints: int, optional
4341
@@ -102,16 +100,13 @@ def __init__(
102100 vehicle ,
103101 curvature = 1.0 ,
104102 stepsize = 0.2 ,
105- showsamples = False ,
106103 npoints = 50 ,
107104 ** kwargs ,
108105 ):
109-
110106 super ().__init__ (ndims = 2 , ** kwargs )
111107
112108 self .npoints = npoints
113109 self .map = map
114- self .showsamples = showsamples
115110
116111 self .g = DGraph (metric = "SE2" )
117112
@@ -128,12 +123,18 @@ def __init__(
128123 # self.goal_yaw_th = np.deg2rad(1.0)
129124 # self.goal_xy_th = 0.5
130125
131- def plan (self , goal , animate = True , search_until_npoints = True ):
126+ def plan (self , goal , showsamples = True , showvalid = True , animate = False ):
132127 r"""
133128 Plan paths to goal using RRT
134129
135130 :param goal: goal pose :math:`(x, y, \theta)`, defaults to previously set value
136131 :type goal: array_like(3), optional
132+ :param showsamples: display position part of configurations overlaid on the map, defaults to True
133+ :type showsamples: bool, optional
134+ :param showvalid: display valid configurations as vehicle polygons overlaid on the map, defaults to False
135+ :type showvalid: bool, optional
136+ :param animate: update the display as configurations are tested, defaults to False
137+ :type animate: bool, optional
137138
138139 Compute a rapidly exploring random tree with its root at the ``goal``.
139140 The tree will have ``npoints`` vertices spread uniformly randomly over
@@ -143,6 +144,11 @@ def plan(self, goal, animate=True, search_until_npoints=True):
143144 vertex already in the graph. Each configuration on that path, with
144145 spacing of ``stepsize``, is tested for obstacle intersection.
145146
147+ The configurations tested are displayed (translation only) if ``showsamples`` is
148+ True. The valid configurations are displayed as vehicle polygones if ``showvalid``
149+ is True. If ``animate`` is True these points are displayed during the search
150+ process, otherwise a single figure is displayed at the end.
151+
146152 :seealso: :meth:`query`
147153 """
148154 # TODO use validate
@@ -153,14 +159,18 @@ def plan(self, goal, animate=True, search_until_npoints=True):
153159 v = self .g .add_vertex (coord = goal )
154160 v .path = None
155161
162+ if showsamples or showvalid :
163+ self .map .plot ()
164+
156165 self .progress_start (self .npoints )
157166 count = 0
158167 while count < self .npoints :
159-
160168 random_point = self .qrandom_free ()
161169
162- if self . showsamples :
170+ if showsamples :
163171 plt .plot (random_point [0 ], random_point [1 ], "ok" , markersize = 2 )
172+ if animate :
173+ plt .pause (0.02 )
164174
165175 vnearest , d = self .g .closest (random_point )
166176
@@ -192,8 +202,13 @@ def plan(self, goal, animate=True, search_until_npoints=True):
192202 self .g .add_edge (vnew , vnearest , cost = pstatus .length )
193203 vnew .path = path
194204
195- self .vehicle .polygon (random_point ).plot (color = "b" , alpha = 0.1 )
196- plt .show ()
205+ if showvalid :
206+ self .vehicle .polygon (random_point ).plot (color = "b" , alpha = 0.1 )
207+ if animate :
208+ plt .pause (0.02 )
209+
210+ if (showvalid or showsamples ) and not animate :
211+ plt .show (block = False )
197212
198213 self .progress_end ()
199214
@@ -307,7 +322,6 @@ def iscollision(self, q):
307322
308323
309324if __name__ == "__main__" :
310-
311325 from roboticstoolbox .mobile .Vehicle import Bicycle
312326
313327 # start and goal configuration
0 commit comments