| 
    Aikido
    
   | 
 
Planning problem to plan to a given single Task Space Region (TSR). More...
#include <aikido/planner/dart/ConfigurationToTSR.hpp>
  
Public Member Functions | |
| ConfigurationToTSR (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, std::size_t maxSamplingTries, std::size_t batchSize, std::size_t maxBatches, std::size_t numMaxIterations, constraint::dart::ConstTSRPtr goalTSR, constraint::ConstTestablePtr constraint=nullptr) | |
| Constructor.  More... | |
| ConfigurationToTSR (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, const statespace::dart::MetaSkeletonStateSpace::State *startState, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, std::size_t maxSamplingTries, std::size_t batchSize, std::size_t maxBatches, std::size_t numMaxIterations, constraint::dart::ConstTSRPtr goalTSR, constraint::ConstTestablePtr constraint=nullptr) | |
| Constructor.  More... | |
| const std::string & | getType () const override | 
| Returns type of this planning problem.  More... | |
| ::dart::dynamics::ConstBodyNodePtr | getEndEffectorBodyNode () const | 
| Returns the end-effector BodyNode to be planned to move to a desired TSR.  More... | |
| std::size_t | getMaxSamplingTries () const | 
| Returns the maximum number of times to try when sampling from the TSR.  More... | |
| std::size_t | getBatchSize () const | 
| Returns the number of samples from the TSR to include per batch.  More... | |
| std::size_t | getMaxBatches () const | 
| Returns the maximum number of batches to run when planning to TSR samples.  More... | |
| std::size_t | getNumMaxIterations () const | 
| Returns the maximum number of iterations for the IK Solver.  More... | |
| const statespace::dart::MetaSkeletonStateSpace::State * | getStartState () const | 
| Returns the start state to plan from, either set on construction or taken from the current state of the MetaSkeleton.  More... | |
| constraint::dart::ConstTSRPtr | getGoalTSR () const | 
| Returns the goal TSR.  More... | |
  Public Member Functions inherited from aikido::planner::Problem | |
| Problem (statespace::ConstStateSpacePtr stateSpace, constraint::ConstTestablePtr constraint=nullptr) | |
| Constructor.  More... | |
| virtual | ~Problem ()=default | 
| Destructor.  More... | |
| statespace::ConstStateSpacePtr | getStateSpace () const | 
| Returns const state space.  More... | |
| constraint::ConstTestablePtr | getConstraint () const | 
| Returns the constraint that must be satisfied throughout the trajectory.  More... | |
Static Public Member Functions | |
| static const std::string & | getStaticType () | 
| Returns the type of the planning problem.  More... | |
Protected Attributes | |
| statespace::dart::ConstMetaSkeletonStateSpacePtr | mMetaSkeletonStateSpace | 
| MetaSkeletonStateSpace.  More... | |
| ::dart::dynamics::ConstMetaSkeletonPtr | mMetaSkeleton | 
| MetaSkeleton, if given.  More... | |
| statespace::dart::MetaSkeletonStateSpace::ScopedState | mStartState | 
| Start state, if set on construction.  More... | |
| const ::dart::dynamics::ConstBodyNodePtr | mEndEffectorBodyNode | 
| End-effector body node.  More... | |
| std::size_t | mMaxSamplingTries | 
| Maximum number of times to try when sampling from the TSR.  More... | |
| std::size_t | mBatchSize | 
| Number of TSR samples to include per batch.  More... | |
| std::size_t | mMaxBatches | 
| Maximum number of batches to run when planning to TSR samples.  More... | |
| std::size_t | mNumMaxIterations | 
| Maximum number of iterations for the IK Solver.  More... | |
| const constraint::dart::ConstTSRPtr | mGoalTSR | 
| Goal TSR.  More... | |
  Protected Attributes inherited from aikido::planner::Problem | |
| statespace::ConstStateSpacePtr | mStateSpace | 
| State space associated with this problem.  More... | |
| constraint::ConstTestablePtr | mConstraint | 
| Trajectory-wide constraint that must be satisfied.  More... | |
Planning problem to plan to a given single Task Space Region (TSR).
| aikido::planner::dart::ConfigurationToTSR::ConfigurationToTSR | ( | statespace::dart::ConstMetaSkeletonStateSpacePtr | stateSpace, | 
| ::dart::dynamics::ConstMetaSkeletonPtr | metaSkeleton, | ||
| ::dart::dynamics::ConstBodyNodePtr | endEffectorBodyNode, | ||
| std::size_t | maxSamplingTries, | ||
| std::size_t | batchSize, | ||
| std::size_t | maxBatches, | ||
| std::size_t | numMaxIterations, | ||
| constraint::dart::ConstTSRPtr | goalTSR, | ||
| constraint::ConstTestablePtr | constraint = nullptr  | 
        ||
| ) | 
Constructor.
Note that this constructor takes the start state from the current state of the passed MetaSkeleton.
| [in] | stateSpace | State space. | 
| [in] | metaSkeleton | MetaSkeleton that getStartState will return the current state of when called. | 
| [in] | endEffectorBodyNode | BodyNode to be planned to move to a desired TSR. | 
| [in] | maxSamplingTries | Maximum number of times for the sample generator to retry sampling from the TSR. | 
| [in] | batchSize | Number of TSR samples to include per ranked batch. | 
| [in] | maxBatches | Maximum number of ranked batches to run when planning to TSR samples. | 
| [in] | numMaxIterations | Maximum number of iterations for the IK Solver | 
| [in] | goalTSR | Goal TSR. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| If | stateSpace is not compatible with constraint's state space.  | 
| aikido::planner::dart::ConfigurationToTSR::ConfigurationToTSR | ( | statespace::dart::ConstMetaSkeletonStateSpacePtr | stateSpace, | 
| const statespace::dart::MetaSkeletonStateSpace::State * | startState, | ||
| ::dart::dynamics::ConstBodyNodePtr | endEffectorBodyNode, | ||
| std::size_t | maxSamplingTries, | ||
| std::size_t | batchSize, | ||
| std::size_t | maxBatches, | ||
| std::size_t | numMaxIterations, | ||
| constraint::dart::ConstTSRPtr | goalTSR, | ||
| constraint::ConstTestablePtr | constraint = nullptr  | 
        ||
| ) | 
Constructor.
Note that this constructor sets the start state on construction.
| [in] | stateSpace | State space. | 
| [in] | startState | Start state to plan from. | 
| [in] | endEffectorBodyNode | BodyNode to be planned to move to a desired TSR. | 
| [in] | maxSamplingTries | Maximum number of times for the sample generator to retry sampling from the TSR | 
| [in] | batchSize | Number of TSR samples to include per ranked batch. | 
| [in] | maxBatches | Maximum number of ranked batches to run when planning to TSR samples. | 
| [in] | numMaxIterations | Maximum number of iterations for the IK Solver | 
| [in] | goalTSR | Goal TSR. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| If | stateSpace is not compatible with constraint's state space.  | 
| std::size_t aikido::planner::dart::ConfigurationToTSR::getBatchSize | ( | ) | const | 
Returns the number of samples from the TSR to include per batch.
| ::dart::dynamics::ConstBodyNodePtr aikido::planner::dart::ConfigurationToTSR::getEndEffectorBodyNode | ( | ) | const | 
Returns the end-effector BodyNode to be planned to move to a desired TSR.
| constraint::dart::ConstTSRPtr aikido::planner::dart::ConfigurationToTSR::getGoalTSR | ( | ) | const | 
Returns the goal TSR.
| std::size_t aikido::planner::dart::ConfigurationToTSR::getMaxBatches | ( | ) | const | 
Returns the maximum number of batches to run when planning to TSR samples.
| std::size_t aikido::planner::dart::ConfigurationToTSR::getMaxSamplingTries | ( | ) | const | 
Returns the maximum number of times to try when sampling from the TSR.
| std::size_t aikido::planner::dart::ConfigurationToTSR::getNumMaxIterations | ( | ) | const | 
Returns the maximum number of iterations for the IK Solver.
| const statespace::dart::MetaSkeletonStateSpace::State* aikido::planner::dart::ConfigurationToTSR::getStartState | ( | ) | const | 
Returns the start state to plan from, either set on construction or taken from the current state of the MetaSkeleton.
      
  | 
  static | 
Returns the type of the planning problem.
      
  | 
  overridevirtual | 
Returns type of this planning problem.
Implements aikido::planner::Problem.
      
  | 
  protected | 
Number of TSR samples to include per batch.
      
  | 
  protected | 
End-effector body node.
      
  | 
  protected | 
Goal TSR.
      
  | 
  protected | 
Maximum number of batches to run when planning to TSR samples.
      
  | 
  protected | 
Maximum number of times to try when sampling from the TSR.
      
  | 
  protected | 
MetaSkeleton, if given.
      
  | 
  protected | 
MetaSkeletonStateSpace.
Prevents use of expensive dynamic cast on mStateSpace.
      
  | 
  protected | 
Maximum number of iterations for the IK Solver.
      
  | 
  protected | 
Start state, if set on construction.