Planner that generates a trajectory that moves the end-effector to a given pose.  
 More...
#include <aikido/planner/vectorfield/VectorFieldConfigurationToEndEffectorPosePlanner.hpp>
 | 
|   | VectorFieldConfigurationToEndEffectorPosePlanner (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton, double goalTolerance, double anglePoseRatio, double positionTolerance, double angularTolerance, double initialStepSize, double jointLimitTolerance, double constraintCheckResolution, std::chrono::duration< double > timelimit) | 
|   | Constructor.  More...
  | 
|   | 
| trajectory::TrajectoryPtr  | plan (const SolvableProblem &problem, Result *result=nullptr) override | 
|   | Plan to a trajectory that moves the end-effector to a given pose.  More...
  | 
|   | 
|   | ConfigurationToEndEffectorPosePlanner (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton) | 
|   | Constructor.  More...
  | 
|   | 
| virtual trajectory::TrajectoryPtr  | plan (const SolvableProblem &problem, Result *result=nullptr)=0 | 
|   | Solves problem returning the result to result.  More...
  | 
|   | 
|   | SingleProblemPlanner (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton) | 
|   | Constructor.  More...
  | 
|   | 
| statespace::dart::ConstMetaSkeletonStateSpacePtr  | getMetaSkeletonStateSpace () const | 
|   | Return this planner's MetaSkeletonStateSpace.  More...
  | 
|   | 
| ::dart::dynamics::MetaSkeletonPtr  | getMetaSkeleton () | 
|   | Return this planner's MetaSkeleton.  More...
  | 
|   | 
|   | 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...
  | 
|   | 
Planner that generates a trajectory that moves the end-effector to a given pose. 
 
◆ VectorFieldConfigurationToEndEffectorPosePlanner()
      
        
          | aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::VectorFieldConfigurationToEndEffectorPosePlanner  | 
          ( | 
          statespace::dart::ConstMetaSkeletonStateSpacePtr  | 
          stateSpace,  | 
        
        
           | 
           | 
          ::dart::dynamics::MetaSkeletonPtr  | 
          metaSkeleton,  | 
        
        
           | 
           | 
          double  | 
          goalTolerance,  | 
        
        
           | 
           | 
          double  | 
          anglePoseRatio,  | 
        
        
           | 
           | 
          double  | 
          positionTolerance,  | 
        
        
           | 
           | 
          double  | 
          angularTolerance,  | 
        
        
           | 
           | 
          double  | 
          initialStepSize,  | 
        
        
           | 
           | 
          double  | 
          jointLimitTolerance,  | 
        
        
           | 
           | 
          double  | 
          constraintCheckResolution,  | 
        
        
           | 
           | 
          std::chrono::duration< double >  | 
          timelimit  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Constructor. 
- Parameters
 - 
  
    | [in] | stateSpace | State space that this planner is associated with.  | 
    | [in] | metaSkeleton | MetaSkeleton to plan with.  | 
    | [in] | goalTolerance | Distance from goal to stop planning.  | 
    | [in] | anglePoseRatio | Conversion ratio from radian to meter in computing the goal tolerance.  | 
    | [in] | positionTolerance | How a planned trajectory is allowed to deviated from a straight line segment defined by the direction and the distance.  | 
    | [in] | angularTolerance | How a planned trajectory is allowed to deviate from a given direction.  | 
    | [in] | initialStepSize | Initial step size.  | 
    | [in] | jointLimitTolerance | If less then this distance to joint limit, velocity is bounded in that direction to 0.  | 
    | [in] | constraintCheckResolution | Resolution used in constraint checking.  | 
    | [in] | timelimit | timeout in seconds.  | 
  
   
 
 
◆ plan()
Plan to a trajectory that moves the end-effector to a given pose. 
The planner returns success if the resulting trajectory satisfies constraint at some resolution and failure (returning nullptr) otherwise. The reason for the failure is stored in the result output parameter.
- Parameters
 - 
  
    | [in] | problem | Planning problem.  | 
    | [out] | result | Information about success or failure.  | 
  
   
- Returns
 - Trajectory or 
nullptr if planning failed.  
 
 
◆ mAnglePoseRatio
  
  
      
        
          | double aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mAnglePoseRatio | 
         
       
   | 
  
protected   | 
  
 
Conversion ratio from radian to meter in computing the combined geodesic error. 
 
 
◆ mAngularTolerance
  
  
      
        
          | double aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mAngularTolerance | 
         
       
   | 
  
protected   | 
  
 
How a planned trajectory is allowed to deviate from a given direction. 
 
 
◆ mConstraintCheckResolution
  
  
      
        
          | double aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mConstraintCheckResolution | 
         
       
   | 
  
protected   | 
  
 
Resolution used in constraint checking. 
 
 
◆ mGoalTolerance
  
  
      
        
          | double aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mGoalTolerance | 
         
       
   | 
  
protected   | 
  
 
Tolerated geodesic distance from goal. 
 
 
◆ mInitialStepSize
  
  
      
        
          | double aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mInitialStepSize | 
         
       
   | 
  
protected   | 
  
 
 
◆ mJointLimitTolerance
  
  
      
        
          | double aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mJointLimitTolerance | 
         
       
   | 
  
protected   | 
  
 
If less then this distance to joint limit, velocity is bounded in that direction to 0. 
 
 
◆ mPositionTolerance
  
  
      
        
          | double aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mPositionTolerance | 
         
       
   | 
  
protected   | 
  
 
How a planned trajectory is allowed to deviated from a straight line segment defined by the direction and the distance. 
 
 
◆ mTimelimit
  
  
      
        
          | std::chrono::duration<double> aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mTimelimit | 
         
       
   | 
  
protected   |