Creates an OMPL Planner.  
 More...
#include <aikido/planner/ompl/OMPLConfigurationToConfigurationPlanner.hpp>
 | 
|   | OMPLConfigurationToConfigurationPlanner (statespace::ConstStateSpacePtr stateSpace, common::RNG *rng=nullptr, statespace::ConstInterpolatorPtr interpolator=nullptr, distance::DistanceMetricPtr dmetric=nullptr, constraint::SampleablePtr sampler=nullptr, constraint::ConstTestablePtr boundsConstraint=nullptr, constraint::ProjectablePtr boundsProjector=nullptr, double maxDistanceBtwValidityChecks=0.1) | 
|   | Constructor.  More...
  | 
|   | 
| trajectory::TrajectoryPtr  | plan (const SolvableProblem &problem, Result *result=nullptr) override | 
|   | Plans a trajectory from start state to goal state by using an interpolator to interpolate between them.  More...
  | 
|   | 
| ::ompl::base::PlannerPtr  | getOMPLPlanner () | 
|   | Returns the underlying OMPL planner used.  More...
  | 
|   | 
|   | ConfigurationToConfigurationPlanner (statespace::ConstStateSpacePtr stateSpace, common::RNG *rng=nullptr) | 
|   | Constructs from a state space.  More...
  | 
|   | 
| virtual trajectory::TrajectoryPtr  | plan (const SolvableProblem &problem, Result *result=nullptr)=0 | 
|   | Solves problem returning the result to result.  More...
  | 
|   | 
| trajectory::TrajectoryPtr  | plan (const Problem &problem, Result *result=nullptr) final override | 
|   | 
|   | SingleProblemPlanner (statespace::ConstStateSpacePtr stateSpace, common::RNG *rng=nullptr) | 
|   | 
| bool  | canSolve (const Problem &problem) const final override | 
|   | Returns true if this planner can solve problem.  More...
  | 
|   | 
| trajectory::TrajectoryPtr  | plan (const Problem &problem, Result *result=nullptr) final override | 
|   | Solves problem returning the result to result.  More...
  | 
|   | 
|   | Planner (statespace::ConstStateSpacePtr stateSpace, common::RNG *rng=nullptr) | 
|   | Constructs from a state space.  More...
  | 
|   | 
| virtual  | ~Planner ()=default | 
|   | Default destructor.  More...
  | 
|   | 
| statespace::ConstStateSpacePtr  | getStateSpace () const | 
|   | Returns const state space.  More...
  | 
|   | 
| common::RNG *  | getRng () | 
|   | Returns RNG.  More...
  | 
|   | 
template<class PlannerType>
class aikido::planner::ompl::OMPLConfigurationToConfigurationPlanner< PlannerType >
Creates an OMPL Planner. 
- Template Parameters
 - 
  
    | PlannerType | The OMPL Planner to use.  | 
  
   
 
◆ OMPLConfigurationToConfigurationPlanner()
template<class PlannerType > 
      
 
Constructor. 
- Parameters
 - 
  
    | [in] | stateSpace | State space that this planner associated with.  | 
    | [in] | rng | Random number generator to create the state sampler.  | 
    | [in] | interpolator | Interpolator used to interpolate between two states. GeodesicInterpolator is used by default.  | 
    | [in] | dmetric | A valid distance metric defined on the StateSpace. Distance metric relevant to the statespace is used by default.  | 
    | [in] | sampler | A Sampleable to sample states from StateSpace.  | 
  
   
- Note
 - OMPL planners assume this sampler samples from the statespace uniformly. Care must be taken when using a non-uniform sampler. 
 
- Parameters
 - 
  
    | [in] | boundsConstraint | A constraint used to determine whether states encountered during planning fall within any bounds specified on the StateSpace. In addition to the validityConstraint, this must also be satisfied for a state to be considered valid.  | 
    | [in] | boundsProjector | A Projectable that projects a state back within valid bounds defined on the StateSpace.  | 
    | [in] | maxDistanceBtwValidityChecks | The maximum distance (under dmetric) between validity checking two successive points on a tree extension or an edge in a graph.  | 
  
   
 
 
◆ getOMPLPlanner()
template<class PlannerType > 
      
 
Returns the underlying OMPL planner used. 
 
 
◆ plan()
template<class PlannerType > 
 
Plans a trajectory from start state to goal state by using an interpolator to interpolate between them. 
If successful, the planner returns a trajectory that satisfies the constraint. If not, it returns a nullptr. The corresponding message is stored in result.
- Parameters
 - 
  
    | [in] | problem | Planning problem.  | 
    | [out] | result | Information about success or failure.  | 
  
   
- Returns
 - Trajectory or 
nullptr if planning failed.  
- Exceptions
 - 
  
  
 
 
 
◆ mPlanner
template<class PlannerType > 
 
Pointer to the underlying OMPL Planner.