| 
    Aikido
    
   | 
 
Planning problem to plan to a single goal configuration. More...
#include <aikido/planner/ConfigurationToConfiguration.hpp>
  
Public Member Functions | |
| ConfigurationToConfiguration (statespace::ConstStateSpacePtr stateSpace, const statespace::StateSpace::State *startState, const statespace::StateSpace::State *goalState, constraint::ConstTestablePtr constraint) | |
| Constructor.  More... | |
| const std::string & | getType () const override | 
| Returns type of this planning problem.  More... | |
| const statespace::StateSpace::State * | getStartState () const | 
| Returns the start state.  More... | |
| const statespace::StateSpace::State * | getGoalState () const | 
| Returns the goal state.  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::StateSpace::ScopedState | mStartState | 
| Start state.  More... | |
| statespace::StateSpace::ScopedState | mGoalState | 
| Goal state.  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 single goal configuration.
| aikido::planner::ConfigurationToConfiguration::ConfigurationToConfiguration | ( | statespace::ConstStateSpacePtr | stateSpace, | 
| const statespace::StateSpace::State * | startState, | ||
| const statespace::StateSpace::State * | goalState, | ||
| constraint::ConstTestablePtr | constraint | ||
| ) | 
Constructor.
| [in] | stateSpace | State space that this problem associated with. | 
| [in] | startState | Start state. | 
| [in] | goalState | Goal state. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| If | stateSpace is not compatible with constraint's state space.  | 
| const statespace::StateSpace::State* aikido::planner::ConfigurationToConfiguration::getGoalState | ( | ) | const | 
Returns the goal state.
| const statespace::StateSpace::State* aikido::planner::ConfigurationToConfiguration::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 state.
      
  | 
  protected | 
Start state.