HypercubeBenchmark.cpp
110 addPlanner(b, ompl::base::PlannerPtr(new ompl::geometric::STRIDE(ss.getSpaceInformation())), range);
111 addPlanner(b, ompl::base::PlannerPtr(new ompl::geometric::EST(ss.getSpaceInformation())), range);
112 addPlanner(b, ompl::base::PlannerPtr(new ompl::geometric::KPIECE1(ss.getSpaceInformation())), range);
113 addPlanner(b, ompl::base::PlannerPtr(new ompl::geometric::RRT(ss.getSpaceInformation())), range);
114 addPlanner(b, ompl::base::PlannerPtr(new ompl::geometric::PRM(ss.getSpaceInformation())), range);
Search Tree with Resolution Independent Density Estimation.
Definition: STRIDE.h:80
bool hasParam(const std::string &key) const
Check whether this set of parameters includes the parameter named key.
Definition: GenericParam.cpp:123
A boost shared pointer wrapper for ompl::base::StateSpace.
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.
bool setParam(const std::string &key, const std::string &value)
Algorithms in OMPL often have parameters that can be set externally. While each algorithm will have t...
Definition: GenericParam.cpp:48
Kinematic Planning by Interior-Exterior Cell Exploration.
Definition: KPIECE1.h:74
A state space representing Rn. The distance function is the L2 norm.
Definition: RealVectorStateSpace.h:75
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:48
The definition of a state in Rn
Definition: RealVectorStateSpace.h:80