37 #include <ompl/geometric/SimpleSetup.h>
38 #include <ompl/tools/benchmark/Benchmark.h>
39 #include <ompl/base/spaces/RealVectorStateSpace.h>
40 #include <ompl/geometric/planners/rrt/RRTstar.h>
42 namespace ob = ompl::base;
43 namespace og = ompl::geometric;
61 int main(
int argc,
char** argv)
80 ss.setStartAndGoalStates(start, goal, 0.05);
110 b.saveResultsToFile();
Optimal Rapidly-exploring Random Trees.
Definition of a scoped state.
A boost shared pointer wrapper for ompl::base::StateSpace.
State StateType
Define the type of state allocated by this space.
void setName(const std::string &name)
Set the name of the planner.
const T * as(void) const
Cast this instance to a desired type.
Create the set of classes typically needed to solve a geometric problem.
A boost shared pointer wrapper for ompl::base::Planner.
A state space representing Rn. The distance function is the L2 norm.
void setGoalBias(double goalBias)
Set the goal bias.