| 
    Aikido
    
   | 
 
Planning problem to plan to multiple goal configurations. More...
#include <aikido/planner/dart/ConfigurationToConfigurations.hpp>
  
Public Types | |
| using | GoalStates = std::vector< const statespace::dart::MetaSkeletonStateSpace::State * > | 
Public Member Functions | |
| ConfigurationToConfigurations (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, const GoalStates &goalStates, constraint::ConstTestablePtr constraint=nullptr) | |
| Constructor.  More... | |
| ConfigurationToConfigurations (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, const statespace::dart::MetaSkeletonStateSpace::State *startState, const GoalStates &goalStates, constraint::ConstTestablePtr constraint=nullptr) | |
| Constructor.  More... | |
| const std::string & | getType () const override | 
| Returns type of this planning problem.  More... | |
| const statespace::dart::MetaSkeletonStateSpace::State * | getStartState () const | 
| Returns the start state.  More... | |
| std::size_t | getNumGoalStates () const | 
| Returns the number of the goal states.  More... | |
| GoalStates | getGoalStates () const | 
| Returns goal states.  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.  More... | |
| std::vector< statespace::dart::MetaSkeletonStateSpace::ScopedState > | mGoalStates | 
| Goal States.  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 multiple goal configurations.
| using aikido::planner::dart::ConfigurationToConfigurations::GoalStates = std::vector<const statespace::dart::MetaSkeletonStateSpace::State*> | 
| aikido::planner::dart::ConfigurationToConfigurations::ConfigurationToConfigurations | ( | statespace::dart::ConstMetaSkeletonStateSpacePtr | stateSpace, | 
| ::dart::dynamics::ConstMetaSkeletonPtr | metaSkeleton, | ||
| const GoalStates & | goalStates, | ||
| 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] | goalStates | Goal states. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| aikido::planner::dart::ConfigurationToConfigurations::ConfigurationToConfigurations | ( | statespace::dart::ConstMetaSkeletonStateSpacePtr | stateSpace, | 
| const statespace::dart::MetaSkeletonStateSpace::State * | startState, | ||
| const GoalStates & | goalStates, | ||
| 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] | goalStates | Goal states. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| GoalStates aikido::planner::dart::ConfigurationToConfigurations::getGoalStates | ( | ) | const | 
Returns goal states.
| std::size_t aikido::planner::dart::ConfigurationToConfigurations::getNumGoalStates | ( | ) | const | 
Returns the number of the goal states.
| const statespace::dart::MetaSkeletonStateSpace::State* aikido::planner::dart::ConfigurationToConfigurations::getStartState | ( | ) | const | 
Returns the start state.
      
  | 
  static | 
Returns the type of the planning problem.
      
  | 
  overridevirtual | 
Returns type of this planning problem.
Implements aikido::planner::Problem.
      
  | 
  protected | 
Goal States.
      
  | 
  protected | 
MetaSkeleton, if given.
      
  | 
  protected | 
MetaSkeletonStateSpace.
Prevents use of expensive dynamic cast on mStateSpace.
      
  | 
  protected | 
Start state.