OptimalPlanning.py
254 print("{0} found solution of path length {1:.4f} with an optimization objective value of {2:.4f}".format(optimizingPlanner.getName(), pdef.getSolutionPath().length(), pdef.getSolutionPath().cost(pdef.getOptimizationObjective()).value()))
269 parser.add_argument('-t', '--runtime', type=float, default=1.0, help='(Optional) Specify the runtime in seconds. Defaults to 1 and must be greater than 0.')
270 parser.add_argument('-p', '--planner', default='RRTstar', choices=['BFMTstar', 'BITstar', 'FMTstar', 'InformedRRTstar', 'PRMstar', 'RRTstar', 'SORRTstar'], help='(Optional) Specify the optimal planner to use, defaults to RRTstar if not given.') # Alphabetical order
271 parser.add_argument('-o', '--objective', default='PathLength', choices=['PathClearance', 'PathLength', 'ThresholdPathLength', 'WeightedLengthAndClearanceCombo'], help='(Optional) Specify the optimization objective, defaults to PathLength if not given.') # Alphabetical order
272 parser.add_argument('-f', '--file', default=None, help='(Optional) Specify an output path for the found solution path.')
273 parser.add_argument('-i', '--info', type=int, default=0, choices=[0, 1, 2], help='(Optional) Set the OMPL log level. 0 for WARN, 1 for INFO, 2 for DEBUG. Defaults to WARN.')
280 raise argparse.ArgumentTypeError("argument -t/--runtime: invalid choice: %r (choose a positive number greater than 0)"%(args.runtime,))
This class allows for the definition of multiobjective optimal planning problems. Objectives are adde...
Definition: OptimizationObjective.h:207
Asymptotically Optimal Fast Marching Tree algorithm developed by L. Janson and M. Pavone...
Definition: FMT.h:90
std::function< Cost(const State *, const Goal *)> CostToGoHeuristic
The definition of a function which returns an admissible estimate of the optimal path cost from a giv...
Definition: OptimizationObjective.h:53
Bidirectional Asymptotically Optimal Fast Marching Tree algorithm developed by J. Starek...
Definition: BFMT.h:82
Defines optimization objectives where path cost can be represented as a path integral over a cost fun...
Definition: StateCostIntegralObjective.h:50
Abstract definition for a class checking the validity of states. The implementation of this class mus...
Definition: StateValidityChecker.h:90
A state space representing Rn. The distance function is the L2 norm.
Definition: RealVectorStateSpace.h:73
The base class for space information. This contains all the information about the space planning is d...
Definition: SpaceInformation.h:81
An optimization objective which corresponds to optimizing path length.
Definition: PathLengthOptimizationObjective.h:47
Definition of a problem to be solved. This includes the start state(s) for the system and a goal spec...
Definition: ProblemDefinition.h:152
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:47