Loading...
Searching...
No Matches
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. More...
 
 SimpleSetup (const base::StateSpacePtr &space)
 Constructor needs the state space used for planning. More...
 
const base::SpaceInformationPtr & getSpaceInformation () const
 Get the current instance of the space information. More...
 
const base::ProblemDefinitionPtr & getProblemDefinition () const
 Get the current instance of the problem definition. More...
 
base::ProblemDefinitionPtr & getProblemDefinition ()
 Get the current instance of the problem definition. More...
 
const base::StateSpacePtr & getStateSpace () const
 Get the current instance of the state space. More...
 
const base::StateValidityCheckerPtr & getStateValidityChecker () const
 Get the current instance of the state validity checker. More...
 
const base::GoalPtr & getGoal () const
 Get the current goal definition. More...
 
const base::PlannerPtr & getPlanner () const
 Get the current planner. More...
 
const base::PlannerAllocatorgetPlannerAllocator () const
 Get the planner allocator. More...
 
const PathSimplifierPtrgetPathSimplifier () const
 Get the path simplifier. More...
 
PathSimplifierPtrgetPathSimplifier ()
 Get the path simplifier. More...
 
const base::OptimizationObjectivePtr & getOptimizationObjective () const
 Get the optimization objective to use. More...
 
bool haveExactSolutionPath () const
 Return true if a solution path is available (previous call to solve() was successful) and the solution is exact (not approximate) More...
 
bool haveSolutionPath () const
 Return true if a solution path is available (previous call to solve() was successful). The solution may be approximate. More...
 
const std::string getSolutionPlannerName () const
 Get the best solution's planer name. Throw an exception if no solution is available. More...
 
PathGeometricgetSolutionPath () const
 Get the solution path. Throw an exception if no solution is available. More...
 
void getPlannerData (base::PlannerData &pd) const
 Get information about the exploration data structure the motion planner used. More...
 
void setStateValidityChecker (const base::StateValidityCheckerPtr &svc)
 Set the state validity checker to use. More...
 
void setStateValidityChecker (const base::StateValidityCheckerFn &svc)
 Set the state validity checker to use. More...
 
void setOptimizationObjective (const base::OptimizationObjectivePtr &optimizationObjective)
 Set the optimization objective to use. More...
 
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. More...
 
void addStartState (const base::ScopedState<> &state)
 Add a starting state for planning. This call is not needed if setStartAndGoalStates() has been called. More...
 
void clearStartStates ()
 Clear the currently set starting states. More...
 
void setStartState (const base::ScopedState<> &state)
 Clear the currently set starting states and add state as the starting state. More...
 
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. More...
 
void setGoal (const base::GoalPtr &goal)
 Set the goal for planning. This call is not needed if setStartAndGoalStates() has been called. More...
 
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. More...
 
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. More...
 
virtual base::PlannerStatus solve (double time=1.0)
 Run the planner for up to a specified amount of time (default is 1 second) More...
 
virtual base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc)
 Run the planner until ptc becomes true (at most) More...
 
base::PlannerStatus getLastPlannerStatus () const
 Return the status of the last planning attempt. More...
 
double getLastPlanComputationTime () const
 Get the amount of time (in seconds) spent during the last planning step. More...
 
double getLastSimplificationTime () const
 Get the amount of time (in seconds) spend during the last path simplification step. More...
 
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. More...
 
void simplifySolution (const base::PlannerTerminationCondition &ptc)
 Attempt to simplify the current solution path. Stop computation when ptc becomes true at the latest. More...
 
virtual void clear ()
 Clear all planning data. This only includes data generated by motion plan computation. Planner settings, start & goal states are not affected. More...
 
virtual void print (std::ostream &out=std::cout) const
 Print information about the current setup. More...
 
virtual void setup ()
 This method will create the necessary classes for planning. The solve() method will call this function automatically. More...
 

Protected Attributes

base::SpaceInformationPtr si_
 The created space information. More...
 
base::ProblemDefinitionPtr pdef_
 The created problem definition. More...
 
base::PlannerPtr planner_
 The maintained planner instance. More...
 
base::PlannerAllocator pa_
 The optional planner allocator. More...
 
PathSimplifierPtr psk_
 The instance of the path simplifier. More...
 
bool configured_
 Flag indicating whether the classes needed for planning are set up. More...
 
double planTime_
 The amount of time the last planning step took. More...
 
double simplifyTime_
 The amount of time the last path simplification step took. More...
 
base::PlannerStatus lastStatus_
 The status of the last planning request. More...
 

Detailed Description

Create the set of classes typically needed to solve a geometric problem.

Definition at line 62 of file SimpleSetup.h.

Constructor & Destructor Documentation

◆ SimpleSetup() [1/2]

ompl::geometric::SimpleSetup::SimpleSetup ( const base::SpaceInformationPtr &  si)
explicit

Constructor needs the state space used for planning.

Definition at line 40 of file SimpleSetup.cpp.

◆ SimpleSetup() [2/2]

ompl::geometric::SimpleSetup::SimpleSetup ( const base::StateSpacePtr &  space)
explicit

Constructor needs the state space used for planning.

Definition at line 47 of file SimpleSetup.cpp.

Member Function Documentation

◆ addStartState()

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 186 of file SimpleSetup.h.

◆ clear()

void ompl::geometric::SimpleSetup::clear ( )
virtual

Clear all planning data. This only includes data generated by motion plan computation. Planner settings, start & goal states are not affected.

Reimplemented in ompl::tools::Lightning, and ompl::tools::Thunder.

Definition at line 77 of file SimpleSetup.cpp.

◆ clearStartStates()

void ompl::geometric::SimpleSetup::clearStartStates ( )
inline

Clear the currently set starting states.

Definition at line 192 of file SimpleSetup.h.

◆ getGoal()

const base::GoalPtr & ompl::geometric::SimpleSetup::getGoal ( ) const
inline

Get the current goal definition.

Definition at line 104 of file SimpleSetup.h.

◆ getLastPlanComputationTime()

double ompl::geometric::SimpleSetup::getLastPlanComputationTime ( ) const
inline

Get the amount of time (in seconds) spent during the last planning step.

Definition at line 247 of file SimpleSetup.h.

◆ getLastPlannerStatus()

base::PlannerStatus ompl::geometric::SimpleSetup::getLastPlannerStatus ( ) const
inline

Return the status of the last planning attempt.

Definition at line 241 of file SimpleSetup.h.

◆ getLastSimplificationTime()

double ompl::geometric::SimpleSetup::getLastSimplificationTime ( ) const
inline

Get the amount of time (in seconds) spend during the last path simplification step.

Definition at line 253 of file SimpleSetup.h.

◆ getOptimizationObjective()

const base::OptimizationObjectivePtr & ompl::geometric::SimpleSetup::getOptimizationObjective ( ) const
inline

Get the optimization objective to use.

Definition at line 134 of file SimpleSetup.h.

◆ getPathSimplifier() [1/2]

PathSimplifierPtr & ompl::geometric::SimpleSetup::getPathSimplifier ( )
inline

Get the path simplifier.

Definition at line 128 of file SimpleSetup.h.

◆ getPathSimplifier() [2/2]

const PathSimplifierPtr & ompl::geometric::SimpleSetup::getPathSimplifier ( ) const
inline

Get the path simplifier.

Definition at line 122 of file SimpleSetup.h.

◆ getPlanner()

const base::PlannerPtr & ompl::geometric::SimpleSetup::getPlanner ( ) const
inline

Get the current planner.

Definition at line 110 of file SimpleSetup.h.

◆ getPlannerAllocator()

const base::PlannerAllocator & ompl::geometric::SimpleSetup::getPlannerAllocator ( ) const
inline

Get the planner allocator.

Definition at line 116 of file SimpleSetup.h.

◆ getPlannerData()

void ompl::geometric::SimpleSetup::getPlannerData ( base::PlannerData pd) const

Get information about the exploration data structure the motion planner used.

Definition at line 212 of file SimpleSetup.cpp.

◆ getProblemDefinition() [1/2]

base::ProblemDefinitionPtr & ompl::geometric::SimpleSetup::getProblemDefinition ( )
inline

Get the current instance of the problem definition.

Definition at line 86 of file SimpleSetup.h.

◆ getProblemDefinition() [2/2]

const base::ProblemDefinitionPtr & ompl::geometric::SimpleSetup::getProblemDefinition ( ) const
inline

Get the current instance of the problem definition.

Definition at line 80 of file SimpleSetup.h.

◆ getSolutionPath()

ompl::geometric::PathGeometric & ompl::geometric::SimpleSetup::getSolutionPath ( ) const

Get the solution path. Throw an exception if no solution is available.

Definition at line 201 of file SimpleSetup.cpp.

◆ getSolutionPlannerName()

const std::string ompl::geometric::SimpleSetup::getSolutionPlannerName ( ) const

Get the best solution's planer name. Throw an exception if no solution is available.

Definition at line 187 of file SimpleSetup.cpp.

◆ getSpaceInformation()

const base::SpaceInformationPtr & ompl::geometric::SimpleSetup::getSpaceInformation ( ) const
inline

Get the current instance of the space information.

Definition at line 74 of file SimpleSetup.h.

◆ getStateSpace()

const base::StateSpacePtr & ompl::geometric::SimpleSetup::getStateSpace ( ) const
inline

Get the current instance of the state space.

Definition at line 92 of file SimpleSetup.h.

◆ getStateValidityChecker()

const base::StateValidityCheckerPtr & ompl::geometric::SimpleSetup::getStateValidityChecker ( ) const
inline

Get the current instance of the state validity checker.

Definition at line 98 of file SimpleSetup.h.

◆ haveExactSolutionPath()

bool ompl::geometric::SimpleSetup::haveExactSolutionPath ( ) 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 141 of file SimpleSetup.h.

◆ haveSolutionPath()

bool ompl::geometric::SimpleSetup::haveSolutionPath ( ) const
inline

Return true if a solution path is available (previous call to solve() was successful). The solution may be approximate.

Definition at line 148 of file SimpleSetup.h.

◆ print()

void ompl::geometric::SimpleSetup::print ( std::ostream &  out = std::cout) const
virtual

Print information about the current setup.

Reimplemented in ompl::tools::Lightning, and ompl::tools::Thunder.

Definition at line 219 of file SimpleSetup.cpp.

◆ setGoal()

void ompl::geometric::SimpleSetup::setGoal ( const base::GoalPtr &  goal)

Set the goal for planning. This call is not needed if setStartAndGoalStates() has been called.

Definition at line 104 of file SimpleSetup.cpp.

◆ setGoalState()

void ompl::geometric::SimpleSetup::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.

Definition at line 96 of file SimpleSetup.cpp.

◆ setOptimizationObjective()

void ompl::geometric::SimpleSetup::setOptimizationObjective ( const base::OptimizationObjectivePtr &  optimizationObjective)
inline

Set the optimization objective to use.

Definition at line 175 of file SimpleSetup.h.

◆ setPlanner()

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 216 of file SimpleSetup.h.

◆ setPlannerAllocator()

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 227 of file SimpleSetup.h.

◆ setStartAndGoalStates()

void ompl::geometric::SimpleSetup::setStartAndGoalStates ( const base::ScopedState<> &  start,
const base::ScopedState<> &  goal,
double  threshold = std::numeric_limits<double>::epsilon() 
)

Set the start and goal states to use.

Definition at line 85 of file SimpleSetup.cpp.

◆ setStartState()

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 198 of file SimpleSetup.h.

◆ setStateValidityChecker() [1/2]

void ompl::geometric::SimpleSetup::setStateValidityChecker ( const base::StateValidityCheckerFn svc)
inline

Set the state validity checker to use.

Definition at line 169 of file SimpleSetup.h.

◆ setStateValidityChecker() [2/2]

void ompl::geometric::SimpleSetup::setStateValidityChecker ( const base::StateValidityCheckerPtr &  svc)
inline

Set the state validity checker to use.

Definition at line 163 of file SimpleSetup.h.

◆ setup()

void ompl::geometric::SimpleSetup::setup ( )
virtual

This method will create the necessary classes for planning. The solve() method will call this function automatically.

Reimplemented in ompl::tools::Lightning, and ompl::tools::Thunder.

Definition at line 54 of file SimpleSetup.cpp.

◆ simplifySolution() [1/2]

void ompl::geometric::SimpleSetup::simplifySolution ( const base::PlannerTerminationCondition ptc)

Attempt to simplify the current solution path. Stop computation when ptc becomes true at the latest.

Definition at line 144 of file SimpleSetup.cpp.

◆ simplifySolution() [2/2]

void ompl::geometric::SimpleSetup::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.

Definition at line 164 of file SimpleSetup.cpp.

◆ solve() [1/2]

ompl::base::PlannerStatus ompl::geometric::SimpleSetup::solve ( const base::PlannerTerminationCondition ptc)
virtual

Run the planner until ptc becomes true (at most)

Reimplemented in ompl::tools::Lightning, and ompl::tools::Thunder.

Definition at line 130 of file SimpleSetup.cpp.

◆ solve() [2/2]

ompl::base::PlannerStatus ompl::geometric::SimpleSetup::solve ( double  time = 1.0)
virtual

Run the planner for up to a specified amount of time (default is 1 second)

Reimplemented in ompl::tools::Lightning, and ompl::tools::Thunder.

Definition at line 116 of file SimpleSetup.cpp.

Member Data Documentation

◆ configured_

bool ompl::geometric::SimpleSetup::configured_
protected

Flag indicating whether the classes needed for planning are set up.

Definition at line 297 of file SimpleSetup.h.

◆ lastStatus_

base::PlannerStatus ompl::geometric::SimpleSetup::lastStatus_
protected

The status of the last planning request.

Definition at line 306 of file SimpleSetup.h.

◆ pa_

base::PlannerAllocator ompl::geometric::SimpleSetup::pa_
protected

The optional planner allocator.

Definition at line 291 of file SimpleSetup.h.

◆ pdef_

base::ProblemDefinitionPtr ompl::geometric::SimpleSetup::pdef_
protected

The created problem definition.

Definition at line 285 of file SimpleSetup.h.

◆ planner_

base::PlannerPtr ompl::geometric::SimpleSetup::planner_
protected

The maintained planner instance.

Definition at line 288 of file SimpleSetup.h.

◆ planTime_

double ompl::geometric::SimpleSetup::planTime_
protected

The amount of time the last planning step took.

Definition at line 300 of file SimpleSetup.h.

◆ psk_

PathSimplifierPtr ompl::geometric::SimpleSetup::psk_
protected

The instance of the path simplifier.

Definition at line 294 of file SimpleSetup.h.

◆ si_

base::SpaceInformationPtr ompl::geometric::SimpleSetup::si_
protected

The created space information.

Definition at line 282 of file SimpleSetup.h.

◆ simplifyTime_

double ompl::geometric::SimpleSetup::simplifyTime_
protected

The amount of time the last path simplification step took.

Definition at line 303 of file SimpleSetup.h.


The documentation for this class was generated from the following files: