ompl::geometric::SimpleSetup Class Reference
Create the set of classes typically needed to solve a geometric problem. More...
#include <ompl/geometric/SimpleSetup.h>
Inheritance diagram for ompl::geometric::SimpleSetup:
Public Member Functions | |
SimpleSetup (const base::SpaceInformationPtr &si) | |
Constructor needs the state space used for planning. | |
SimpleSetup (const base::StateSpacePtr &space) | |
Constructor needs the state space used for planning. | |
const base::SpaceInformationPtr & | getSpaceInformation () const |
Get the current instance of the space information. | |
const base::ProblemDefinitionPtr & | getProblemDefinition () const |
Get the current instance of the problem definition. | |
base::ProblemDefinitionPtr & | getProblemDefinition () |
Get the current instance of the problem definition. | |
const base::StateSpacePtr & | getStateSpace () const |
Get the current instance of the state space. | |
const base::StateValidityCheckerPtr & | getStateValidityChecker () const |
Get the current instance of the state validity checker. | |
const base::GoalPtr & | getGoal () const |
Get the current goal definition. | |
const base::PlannerPtr & | getPlanner () const |
Get the current planner. | |
const base::PlannerAllocator & | getPlannerAllocator () const |
Get the planner allocator. | |
const PathSimplifierPtr & | getPathSimplifier () const |
Get the path simplifier. | |
PathSimplifierPtr & | getPathSimplifier () |
Get the path simplifier. | |
const base::OptimizationObjectivePtr & | getOptimizationObjective () const |
Get the optimization objective to use. | |
bool | haveExactSolutionPath () const |
Return true if a solution path is available (previous call to solve() was successful) and the solution is exact (not approximate) | |
bool | haveSolutionPath () const |
Return true if a solution path is available (previous call to solve() was successful). The solution may be approximate. | |
const std::string | getSolutionPlannerName () const |
Get the best solution's planer name. Throw an exception if no solution is available. | |
PathGeometric & | getSolutionPath () const |
Get the solution path. Throw an exception if no solution is available. | |
void | getPlannerData (base::PlannerData &pd) const |
Get information about the exploration data structure the motion planner used. | |
void | setStateValidityChecker (const base::StateValidityCheckerPtr &svc) |
Set the state validity checker to use. | |
void | setStateValidityChecker (const base::StateValidityCheckerFn &svc) |
Set the state validity checker to use. | |
void | setOptimizationObjective (const base::OptimizationObjectivePtr &optimizationObjective) |
Set the optimization objective to use. | |
void | setStartAndGoalStates (const base::ScopedState<> &start, const base::ScopedState<> &goal, double threshold=std::numeric_limits< double >::epsilon()) |
Set the start and goal states to use. | |
void | addStartState (const base::ScopedState<> &state) |
Add a starting state for planning. This call is not needed if setStartAndGoalStates() has been called. | |
void | clearStartStates () |
Clear the currently set starting states. | |
void | setStartState (const base::ScopedState<> &state) |
Clear the currently set starting states and add state as the starting state. | |
void | setGoalState (const base::ScopedState<> &goal, double threshold=std::numeric_limits< double >::epsilon()) |
A simple form of setGoal(). The goal will be an instance of ompl::base::GoalState. | |
void | setGoal (const base::GoalPtr &goal) |
Set the goal for planning. This call is not needed if setStartAndGoalStates() has been called. | |
void | setPlanner (const base::PlannerPtr &planner) |
Set the planner to use. If the planner is not set, an attempt is made to use the planner allocator. If no planner allocator is available either, a default planner is set. | |
void | setPlannerAllocator (const base::PlannerAllocator &pa) |
Set the planner allocator to use. This is only used if no planner has been set. This is optional – a default planner will be used if no planner is otherwise specified. | |
virtual base::PlannerStatus | solve (double time=1.0) |
Run the planner for up to a specified amount of time (default is 1 second) | |
virtual base::PlannerStatus | solve (const base::PlannerTerminationCondition &ptc) |
Run the planner until ptc becomes true (at most) | |
base::PlannerStatus | getLastPlannerStatus () const |
Return the status of the last planning attempt. | |
double | getLastPlanComputationTime () const |
Get the amount of time (in seconds) spent during the last planning step. | |
double | getLastSimplificationTime () const |
Get the amount of time (in seconds) spend during the last path simplification step. | |
void | simplifySolution (double duration=0.0) |
Attempt to simplify the current solution path. Spent at most duration seconds in the simplification process. If duration is 0 (the default), a default simplification procedure is executed. | |
void | simplifySolution (const base::PlannerTerminationCondition &ptc) |
Attempt to simplify the current solution path. Stop computation when ptc becomes true at the latest. | |
virtual void | clear () |
Clear all planning data. This only includes data generated by motion plan computation. Planner settings, start & goal states are not affected. | |
virtual void | print (std::ostream &out=std::cout) const |
Print information about the current setup. | |
virtual void | setup () |
This method will create the necessary classes for planning. The solve() method will call this function automatically. | |
Protected Attributes | |
base::SpaceInformationPtr | si_ |
The created space information. | |
base::ProblemDefinitionPtr | pdef_ |
The created problem definition. | |
base::PlannerPtr | planner_ |
The maintained planner instance. | |
base::PlannerAllocator | pa_ |
The optional planner allocator. | |
PathSimplifierPtr | psk_ |
The instance of the path simplifier. | |
bool | configured_ |
Flag indicating whether the classes needed for planning are set up. | |
double | planTime_ |
The amount of time the last planning step took. | |
double | simplifyTime_ |
The amount of time the last path simplification step took. | |
base::PlannerStatus | lastStatus_ |
The status of the last planning request. | |
Detailed Description
Create the set of classes typically needed to solve a geometric problem.
Definition at line 126 of file SimpleSetup.h.
The documentation for this class was generated from the following files:
- ompl/geometric/SimpleSetup.h
- ompl/geometric/src/SimpleSetup.cpp