CForestCircleGridBenchmark.cpp
51 ompl::base::OptimizationObjectivePtr getPathLengthObjective(const ompl::base::SpaceInformationPtr& si)
53 return ompl::base::OptimizationObjectivePtr(new ompl::base::PathLengthOptimizationObjective(si));
81 ("distance", po::value<int>(&distance)->default_value(3), "integer grid distance between start and goal")
82 ("obstacle-radius", po::value<double>(&obstacleRadius)->default_value(.25), "radius of obstacles")
83 ("turning-radius", po::value<double>(&turningRadius)->default_value(.5), "turning radius of robot (ignored for default point robot)")
85 ("runtime-limit", po::value<double>(&runtimeLimit)->default_value(2), "time limit for every test")
86 ("run-count", po::value<int>(&runCount)->default_value(100), "number of times to run each planner")
128 ss.getProblemDefinition()->setOptimizationObjective(getPathLengthObjective(ss.getSpaceInformation()));
A boost shared pointer wrapper for ompl::base::StateSpace.
An SE(2) state space where distance is measured by the length of Dubins curves.
Definition: DubinsStateSpace.h:65
CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:549
Includes various tools such as self config, benchmarking, etc.
Definition: Benchmark.h:45
Create the set of classes typically needed to solve a geometric problem.
Definition: SimpleSetup.h:65
A boost shared pointer wrapper for ompl::base::Planner.
A boost shared pointer wrapper for ompl::base::SpaceInformation.
An optimization objective which corresponds to optimizing path length.
Definition: PathLengthOptimizationObjective.h:47
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition: Cost.h:44
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves.
Definition: ReedsSheppStateSpace.h:64
A boost shared pointer wrapper for ompl::base::OptimizationObjective.
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:48
This namespace contains code that is specific to planning under geometric constraints.
Definition: GeneticSearch.h:48