Create the set of classes typically needed to solve a geometric problem. More...
#include <SimpleSetup.h>
Public Member Functions | |
void | addStartState (const base::ScopedState<> &state) |
Add a starting state for planning. This call is not needed if setStartAndGoalStates() has been called. | |
virtual void | clear (void) |
Clear all planning data. This only includes data generated by motion plan computation. Planner settings, start & goal states are not affected. | |
void | clearStartStates (void) |
Clear the currently set starting states. | |
const base::GoalPtr & | getGoal (void) const |
Get the current goal definition. | |
double | getLastPlanComputationTime (void) const |
Get the amount of time (in seconds) spent during the last planning step. | |
double | getLastSimplificationTime (void) const |
Get the amount of time (in seconds) spend during the last path simplification step. | |
PathSimplifierPtr & | getPathSimplifier (void) |
Get the path simplifier. | |
const PathSimplifierPtr & | getPathSimplifier (void) const |
Get the path simplifier. | |
const base::PlannerPtr & | getPlanner (void) const |
Get the current planner. | |
base::PlannerData | getPlannerData (void) const |
Get information about the exploration data structure the motion planner used. | |
const base::ProblemDefinitionPtr & | getProblemDefinition (void) const |
Get the current instance of the problem definition. | |
PathGeometric & | getSolutionPath (void) const |
Get the solution path. Throw an exception if no solution is available. | |
const base::SpaceInformationPtr & | getSpaceInformation (void) const |
Get the current instance of the space information. | |
const base::StateSpacePtr & | getStateSpace (void) const |
Get the current instance of the state space. | |
const base::StateValidityCheckerPtr & | getStateValidityChecker (void) const |
Get the current instance of the state validity checker. | |
bool | haveExactSolutionPath (void) const |
Return true if a solution path is available (previous call to solve() was successful) and the solution is exact (not approximate). | |
bool | haveSolutionPath (void) const |
Return true if a solution path is available (previous call to solve() was successful). The solution may be approximate. | |
virtual void | print (std::ostream &out=std::cout) const |
Print information about the current setup. | |
void | setGoal (const base::GoalPtr &goal) |
Set the goal for planning. This call is not needed if setStartAndGoalStates() has been called. | |
void | setGoalState (const base::ScopedState<> &goal, const double threshold=std::numeric_limits< double >::epsilon()) |
A simple form of setGoal(). The goal will be an instance of ompl::base::GoalState. | |
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. | |
void | setStartAndGoalStates (const base::ScopedState<> &start, const base::ScopedState<> &goal, const double threshold=std::numeric_limits< double >::epsilon()) |
Set the start and goal states to use. | |
void | setStartState (const base::ScopedState<> &state) |
Clear the currently set starting states and add state as the starting state. | |
void | setStateValidityChecker (const base::StateValidityCheckerFn &svc) |
Set the state validity checker to use. | |
void | setStateValidityChecker (const base::StateValidityCheckerPtr &svc) |
Set the state validity checker to use. | |
virtual void | setup (void) |
This method will create the necessary classes for planning. The solve() method will call this function automatically. | |
SimpleSetup (const base::StateSpacePtr &space) | |
Constructor needs the state space used for planning. | |
void | simplifySolution (void) |
Attempt to simplify the current solution path. | |
virtual bool | solve (double time=1.0) |
Run the planner for a specified amount of time (default is 1 second). | |
void | updateProjectionCellSizes (void) |
Use the exploration data structure of the planner to compute the cell sizes of the projection evaluator. | |
virtual | ~SimpleSetup (void) |
Protected Attributes | |
bool | configured_ |
Flag indicating whether the classes needed for planning are set up. | |
msg::Interface | msg_ |
Interface for console output. | |
base::PlannerAllocator | pa_ |
The optional planner allocator. | |
base::ProblemDefinitionPtr | pdef_ |
The created problem definition. | |
base::PlannerPtr | planner_ |
The maintained planner instance. | |
double | planTime_ |
The amount of time the last planning step took. | |
PathSimplifierPtr | psk_ |
The instance of the path simplifier. | |
base::SpaceInformationPtr | si_ |
The created space information. | |
double | simplifyTime_ |
The amount of time the last path simplification step took. |
Create the set of classes typically needed to solve a geometric problem.
Definition at line 56 of file geometric/SimpleSetup.h.
ompl::geometric::SimpleSetup::SimpleSetup | ( | const base::StateSpacePtr & | space | ) | [inline, explicit] |
Constructor needs the state space used for planning.
Definition at line 62 of file geometric/SimpleSetup.h.
virtual ompl::geometric::SimpleSetup::~SimpleSetup | ( | void | ) | [inline, virtual] |
Definition at line 69 of file geometric/SimpleSetup.h.
void ompl::geometric::SimpleSetup::addStartState | ( | const base::ScopedState<> & | state | ) | [inline] |
Add a starting state for planning. This call is not needed if setStartAndGoalStates() has been called.
Definition at line 160 of file geometric/SimpleSetup.h.
virtual void ompl::geometric::SimpleSetup::clear | ( | void | ) | [virtual] |
Clear all planning data. This only includes data generated by motion plan computation. Planner settings, start & goal states are not affected.
void ompl::geometric::SimpleSetup::clearStartStates | ( | void | ) | [inline] |
Clear the currently set starting states.
Definition at line 166 of file geometric/SimpleSetup.h.
const base::GoalPtr& ompl::geometric::SimpleSetup::getGoal | ( | void | ) | const [inline] |
Get the current goal definition.
Definition at line 98 of file geometric/SimpleSetup.h.
double ompl::geometric::SimpleSetup::getLastPlanComputationTime | ( | void | ) | const [inline] |
Get the amount of time (in seconds) spent during the last planning step.
Definition at line 222 of file geometric/SimpleSetup.h.
double ompl::geometric::SimpleSetup::getLastSimplificationTime | ( | void | ) | const [inline] |
Get the amount of time (in seconds) spend during the last path simplification step.
Definition at line 228 of file geometric/SimpleSetup.h.
PathSimplifierPtr& ompl::geometric::SimpleSetup::getPathSimplifier | ( | void | ) | [inline] |
Get the path simplifier.
Definition at line 116 of file geometric/SimpleSetup.h.
const PathSimplifierPtr& ompl::geometric::SimpleSetup::getPathSimplifier | ( | void | ) | const [inline] |
Get the path simplifier.
Definition at line 110 of file geometric/SimpleSetup.h.
const base::PlannerPtr& ompl::geometric::SimpleSetup::getPlanner | ( | void | ) | const [inline] |
Get the current planner.
Definition at line 104 of file geometric/SimpleSetup.h.
base::PlannerData ompl::geometric::SimpleSetup::getPlannerData | ( | void | ) | const |
Get information about the exploration data structure the motion planner used.
const base::ProblemDefinitionPtr& ompl::geometric::SimpleSetup::getProblemDefinition | ( | void | ) | const [inline] |
Get the current instance of the problem definition.
Definition at line 80 of file geometric/SimpleSetup.h.
PathGeometric& ompl::geometric::SimpleSetup::getSolutionPath | ( | void | ) | const |
Get the solution path. Throw an exception if no solution is available.
const base::SpaceInformationPtr& ompl::geometric::SimpleSetup::getSpaceInformation | ( | void | ) | const [inline] |
Get the current instance of the space information.
Definition at line 74 of file geometric/SimpleSetup.h.
const base::StateSpacePtr& ompl::geometric::SimpleSetup::getStateSpace | ( | void | ) | const [inline] |
Get the current instance of the state space.
Definition at line 86 of file geometric/SimpleSetup.h.
const base::StateValidityCheckerPtr& ompl::geometric::SimpleSetup::getStateValidityChecker | ( | void | ) | const [inline] |
Get the current instance of the state validity checker.
Definition at line 92 of file geometric/SimpleSetup.h.
bool ompl::geometric::SimpleSetup::haveExactSolutionPath | ( | void | ) | const [inline] |
Return true if a solution path is available (previous call to solve() was successful) and the solution is exact (not approximate).
Definition at line 122 of file geometric/SimpleSetup.h.
bool ompl::geometric::SimpleSetup::haveSolutionPath | ( | void | ) | const [inline] |
Return true if a solution path is available (previous call to solve() was successful). The solution may be approximate.
Definition at line 128 of file geometric/SimpleSetup.h.
virtual void ompl::geometric::SimpleSetup::print | ( | std::ostream & | out = std::cout |
) | const [inline, virtual] |
Print information about the current setup.
Definition at line 242 of file geometric/SimpleSetup.h.
void ompl::geometric::SimpleSetup::setGoal | ( | const base::GoalPtr & | goal | ) | [inline] |
Set the goal for planning. This call is not needed if setStartAndGoalStates() has been called.
Definition at line 186 of file geometric/SimpleSetup.h.
void ompl::geometric::SimpleSetup::setGoalState | ( | const base::ScopedState<> & | goal, | |
const double | threshold = std::numeric_limits<double>::epsilon() | |||
) | [inline] |
A simple form of setGoal(). The goal will be an instance of ompl::base::GoalState.
Definition at line 179 of file geometric/SimpleSetup.h.
void ompl::geometric::SimpleSetup::setPlanner | ( | const base::PlannerPtr & | planner | ) | [inline] |
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.
Definition at line 195 of file geometric/SimpleSetup.h.
void ompl::geometric::SimpleSetup::setPlannerAllocator | ( | const base::PlannerAllocator & | pa | ) | [inline] |
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.
Definition at line 206 of file geometric/SimpleSetup.h.
void ompl::geometric::SimpleSetup::setStartAndGoalStates | ( | const base::ScopedState<> & | start, | |
const base::ScopedState<> & | goal, | |||
const double | threshold = std::numeric_limits<double>::epsilon() | |||
) | [inline] |
Set the start and goal states to use.
Definition at line 152 of file geometric/SimpleSetup.h.
void ompl::geometric::SimpleSetup::setStartState | ( | const base::ScopedState<> & | state | ) | [inline] |
Clear the currently set starting states and add state as the starting state.
Definition at line 172 of file geometric/SimpleSetup.h.
void ompl::geometric::SimpleSetup::setStateValidityChecker | ( | const base::StateValidityCheckerFn & | svc | ) | [inline] |
Set the state validity checker to use.
Definition at line 146 of file geometric/SimpleSetup.h.
void ompl::geometric::SimpleSetup::setStateValidityChecker | ( | const base::StateValidityCheckerPtr & | svc | ) | [inline] |
Set the state validity checker to use.
Definition at line 140 of file geometric/SimpleSetup.h.
virtual void ompl::geometric::SimpleSetup::setup | ( | void | ) | [virtual] |
This method will create the necessary classes for planning. The solve() method will call this function automatically.
void ompl::geometric::SimpleSetup::simplifySolution | ( | void | ) |
Attempt to simplify the current solution path.
virtual bool ompl::geometric::SimpleSetup::solve | ( | double | time = 1.0 |
) | [virtual] |
Run the planner for a specified amount of time (default is 1 second).
void ompl::geometric::SimpleSetup::updateProjectionCellSizes | ( | void | ) |
Use the exploration data structure of the planner to compute the cell sizes of the projection evaluator.
bool ompl::geometric::SimpleSetup::configured_ [protected] |
Flag indicating whether the classes needed for planning are set up.
Definition at line 273 of file geometric/SimpleSetup.h.
msg::Interface ompl::geometric::SimpleSetup::msg_ [protected] |
Interface for console output.
Definition at line 282 of file geometric/SimpleSetup.h.
The optional planner allocator.
Definition at line 267 of file geometric/SimpleSetup.h.
The created problem definition.
Definition at line 261 of file geometric/SimpleSetup.h.
The maintained planner instance.
Definition at line 264 of file geometric/SimpleSetup.h.
double ompl::geometric::SimpleSetup::planTime_ [protected] |
The amount of time the last planning step took.
Definition at line 276 of file geometric/SimpleSetup.h.
PathSimplifierPtr ompl::geometric::SimpleSetup::psk_ [protected] |
The instance of the path simplifier.
Definition at line 270 of file geometric/SimpleSetup.h.
The created space information.
Definition at line 258 of file geometric/SimpleSetup.h.
double ompl::geometric::SimpleSetup::simplifyTime_ [protected] |
The amount of time the last path simplification step took.
Definition at line 279 of file geometric/SimpleSetup.h.