39 from __future__
import print_function
41 from ompl
import util
as ou
42 from ompl
import base
as ob
43 from ompl
import geometric
as og
44 from ompl
import tools
as ot
48 from os.path
import abspath, dirname, join
51 0, join(dirname(dirname(dirname(abspath(__file__)))),
'py-bindings'))
52 from ompl
import util
as ou
53 from ompl
import base
as ob
54 from ompl
import geometric
as og
55 from ompl
import tools
as ot
59 def addSpaceOption(parser):
60 parser.add_argument(
"-s",
"--space", default=
"PJ",
61 choices=[
"PJ",
"AT",
"TB"],
62 help=
"""Choose which constraint handling methodology to use. One of:
63 PJ - Projection (Default)
65 TB - Tangent Bundle.""")
68 def addPlannerOption(parser):
69 parser.add_argument(
"-p",
"--planner", default=
"RRT",
70 help=
"Comma-separated list of which motion planner to use (multiple if "
71 "benchmarking, one if planning).\n Choose from, e.g.:\n"
72 "RRT (Default), RRTConnect, RRTstar, "
73 "EST, BiEST, ProjEST, "
79 def addConstrainedOptions(parser):
80 group = parser.add_argument_group(
"Constrained planning options")
81 group.add_argument(
"-d",
"--delta", type=float, default=ob.CONSTRAINED_STATE_SPACE_DELTA,
82 help=
"Step-size for discrete geodesic on manifold.")
83 group.add_argument(
"--lambda", type=float, dest=
"lambda_", metavar=
"LAMBDA",
84 default=ob.CONSTRAINED_STATE_SPACE_LAMBDA,
85 help=
"Maximum `wandering` allowed during atlas traversal. Must be greater "
87 group.add_argument(
"--tolerance", type=float, default=ob.CONSTRAINT_PROJECTION_TOLERANCE,
88 help=
"Constraint satisfaction tolerance.")
89 group.add_argument(
"--time", type=float, default=5.,
90 help=
"Planning time allowed.")
91 group.add_argument(
"--tries", type=int, default=ob.CONSTRAINT_PROJECTION_MAX_ITERATIONS,
92 help=
"Maximum number sample tries per sample.")
93 group.add_argument(
"-r",
"--range", type=float, default=0.,
94 help=
"Planner `range` value for planners that support this parameter. "
95 "Automatically determined otherwise (when 0).")
98 ret = ou.vectorDouble()
103 def clearSpaceAndPlanner(planner):
104 planner.getSpaceInformation().getStateSpace().clear()
108 def addAtlasOptions(parser):
109 group = parser.add_argument_group(
"Atlas options")
110 group.add_argument(
"--epsilon", type=float, default=ob.ATLAS_STATE_SPACE_EPSILON,
111 help=
"Maximum distance from an atlas chart to the manifold. Must be "
113 group.add_argument(
"--rho", type=float, default=ob.CONSTRAINED_STATE_SPACE_DELTA *
114 ob.ATLAS_STATE_SPACE_RHO_MULTIPLIER,
115 help=
"Maximum radius for an atlas chart. Must be positive.")
116 group.add_argument(
"--exploration", type=float, default=ob.ATLAS_STATE_SPACE_EXPLORATION,
117 help=
"Value in [0, 1] which tunes balance of refinement and exploration in "
119 group.add_argument(
"--alpha", type=float, default=ob.ATLAS_STATE_SPACE_ALPHA,
120 help=
"Maximum angle between an atlas chart and the manifold. Must be in "
122 group.add_argument(
"--bias", action=
"store_true",
123 help=
"Sets whether the atlas should use frontier-biased chart sampling "
124 "rather than uniform.")
125 group.add_argument(
"--no-separate", action=
"store_true",
126 help=
"Sets that the atlas should not compute chart separating halfspaces.")
127 group.add_argument(
"--charts", type=int, default=ob.ATLAS_STATE_SPACE_MAX_CHARTS_PER_EXTENSION,
128 help=
"Maximum number of atlas charts that can be generated during one "
129 "manifold traversal.")
134 def __init__(self, spaceType, space, constraint, options):
138 self.
constraint.setTolerance(options.tolerance)
139 self.
constraint.setMaxIterations(options.tries)
145 if spaceType ==
"PJ":
146 ou.OMPL_INFORM(
"Using Projection-Based State Space!")
149 elif spaceType ==
"AT":
150 ou.OMPL_INFORM(
"Using Atlas-Based State Space!")
153 elif spaceType ==
"TB":
154 ou.OMPL_INFORM(
"Using Tangent Bundle-Based State Space!")
159 self.
css.setDelta(options.delta)
160 self.
css.setLambda(options.lambda_)
161 if not spaceType ==
"PJ":
162 self.
css.setExploration(options.exploration)
163 self.
css.setEpsilon(options.epsilon)
164 self.
css.setRho(options.rho)
165 self.
css.setAlpha(options.alpha)
166 self.
css.setMaxChartsPerExtension(options.charts)
168 self.
css.setBiasFunction(
lambda c, atlas=self.
css:
169 atlas.getChartCount() - c.getNeighborCount() + 1.)
170 if spaceType ==
"AT":
171 self.
css.setSeparated(
not options.no_separate)
175 def setStartAndGoalStates(self, start, goal):
178 self.
css.anchorChart(start())
179 self.
css.anchorChart(goal())
182 self.
ss.setStartAndGoalStates(start, goal)
184 def getPlanner(self, plannerName, projectionName=None):
185 planner = eval(
'og.%s(self.csi)' % plannerName)
189 planner.setRange(self.
css.getRho_s())
191 planner.setRange(self.
options.range)
196 planner.setProjectionEvaluator(projectionName)
201 def setPlanner(self, plannerName, projectionName=None):
203 self.
ss.setPlanner(self.
pp)
205 def solveOnce(self, output=False, name="ompl"):
211 path = self.
ss.getSolutionPath()
213 ou.OMPL_WARN(
"Path fails check!")
215 if stat == ob.PlannerStatus.APPROXIMATE_SOLUTION:
216 ou.OMPL_WARN(
"Solution is approximate.")
219 ou.OMPL_INFORM(
"Simplifying solution...")
220 self.
ss.simplifySolution(5.)
222 simplePath = self.
ss.getSolutionPath()
223 ou.OMPL_INFORM(
"Simplified Path Length: %.3f -> %.3f" %
224 (path.length(), simplePath.length()))
226 if not simplePath.check():
227 ou.OMPL_WARN(
"Simplified path fails check!")
230 ou.OMPL_INFORM(
"Interpolating path...")
234 ou.OMPL_WARN(
"Interpolated simplified path fails check!")
236 ou.OMPL_INFORM(
"Interpolating simplified path...")
237 simplePath.interpolate()
239 if not simplePath.check():
240 ou.OMPL_WARN(
"Interpolated simplified path fails check!")
243 ou.OMPL_INFORM(
"Dumping path to `%s_path.txt`." % name)
244 with open(
'%s_path.txt' % name,
'w')
as pathfile:
245 print(path.printAsMatrix, file=pathfile)
248 "Dumping simplified path to `%s_simplepath.txt`." % name)
249 with open(
"%s_simplepath.txt" % name,
'w')
as simplepathfile:
250 print(simplePath.printAsMatrix(), file=simplepathfile)
252 ou.OMPL_WARN(
"No solution found.")
256 def setupBenchmark(self, planners, problem):
259 self.
bench.addExperimentParameter(
260 "n",
"INTEGER", str(self.
constraint.getAmbientDimension()))
261 self.
bench.addExperimentParameter(
262 "k",
"INTEGER", str(self.
constraint.getManifoldDimension()))
263 self.
bench.addExperimentParameter(
264 "n - k",
"INTEGER", str(self.
constraint.getCoDimension()))
265 self.
bench.addExperimentParameter(
"space",
"INTEGER", self.
spaceType)
267 self.
request = ot.Benchmark.Request()
271 self.
request.timeBetweenUpdates = 0.1
272 self.
request.saveConsoleOutput =
False
273 for planner
in planners:
276 self.
bench.setPreRunEvent(ot.PreSetupEvent(clearSpaceAndPlanner))
278 def runBenchmark(self):
280 filename = str(datetime.datetime.now()) +
'_' + \
282 self.
bench.saveResultsToFile(filename)
284 def atlasStats(self):
288 ou.OMPL_INFORM(
"Atlas has %d charts" % self.
css.getChartCount())
290 ou.OMPL_INFORM(
"Atlas is approximately %.3f%% open" %
291 self.
css.estimateFrontierPercent())
293 def dumpGraph(self, name):
294 ou.OMPL_INFORM(
"Dumping planner graph to `%s_graph.graphml`." % name)
296 self.
pp.getPlannerData(data)
298 with open(
"%s_graph.graphml" % name,
"w")
as graphfile:
299 print(data.printGraphML(), file=graphfile)
302 ou.OMPL_INFORM(
"Dumping atlas to `%s_atlas.ply`." % name)
303 with open(
"%s_atlas.ply" % name,
"w")
as atlasfile:
304 print(self.
css.printPLY(), file=atlasfile)