Aikido
aikido::planner::dart::ConfigurationToConfiguration Class Reference

Planning problem to plan to a single goal configuration. More...

#include <aikido/planner/dart/ConfigurationToConfiguration.hpp>

Inheritance diagram for aikido::planner::dart::ConfigurationToConfiguration:
aikido::planner::Problem

Public Member Functions

 ConfigurationToConfiguration (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, const statespace::dart::MetaSkeletonStateSpace::State *goalState, constraint::ConstTestablePtr constraint=nullptr)
 Constructor. More...
 
 ConfigurationToConfiguration (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, const statespace::dart::MetaSkeletonStateSpace::State *startState, const statespace::dart::MetaSkeletonStateSpace::State *goalState, constraint::ConstTestablePtr constraint=nullptr)
 Constructor. More...
 
const std::string & getType () const override
 Returns type of this planning problem. More...
 
const statespace::dart::MetaSkeletonStateSpace::StategetStartState () const
 Returns the start state. More...
 
const statespace::dart::MetaSkeletonStateSpace::StategetGoalState () 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::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
 MetaSkeletonStateSpace. More...
 
::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton
 MetaSkeleton, if given. More...
 
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
 Start state. More...
 
statespace::dart::MetaSkeletonStateSpace::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...
 

Detailed Description

Planning problem to plan to a single goal configuration.

Constructor & Destructor Documentation

◆ ConfigurationToConfiguration() [1/2]

aikido::planner::dart::ConfigurationToConfiguration::ConfigurationToConfiguration ( statespace::dart::ConstMetaSkeletonStateSpacePtr  stateSpace,
::dart::dynamics::ConstMetaSkeletonPtr  metaSkeleton,
const statespace::dart::MetaSkeletonStateSpace::State goalState,
constraint::ConstTestablePtr  constraint = nullptr 
)

Constructor.

Note that this constructor takes the start state from the current state of the passed MetaSkeleton.

Parameters
[in]stateSpaceState space. param[in] metaSkeleton MetaSkeleton that getStartState will return the current state of when called.
[in]goalStateGoal state to plan to.
[in]constraintTrajectory-wide constraint that must be satisfied.

◆ ConfigurationToConfiguration() [2/2]

aikido::planner::dart::ConfigurationToConfiguration::ConfigurationToConfiguration ( statespace::dart::ConstMetaSkeletonStateSpacePtr  stateSpace,
const statespace::dart::MetaSkeletonStateSpace::State startState,
const statespace::dart::MetaSkeletonStateSpace::State goalState,
constraint::ConstTestablePtr  constraint = nullptr 
)

Constructor.

Note that this constructor sets the start state on construction.

Parameters
[in]stateSpaceState space.
[in]startStateStart state to plan from.
[in]goalStateGoal state to plan to.
[in]constraintTrajectory-wide constraint that must be satisfied.

Member Function Documentation

◆ getGoalState()

const statespace::dart::MetaSkeletonStateSpace::State* aikido::planner::dart::ConfigurationToConfiguration::getGoalState ( ) const

Returns the goal state.

◆ getStartState()

const statespace::dart::MetaSkeletonStateSpace::State* aikido::planner::dart::ConfigurationToConfiguration::getStartState ( ) const

Returns the start state.

◆ getStaticType()

static const std::string& aikido::planner::dart::ConfigurationToConfiguration::getStaticType ( )
static

Returns the type of the planning problem.

◆ getType()

const std::string& aikido::planner::dart::ConfigurationToConfiguration::getType ( ) const
overridevirtual

Returns type of this planning problem.

Implements aikido::planner::Problem.

Member Data Documentation

◆ mGoalState

statespace::dart::MetaSkeletonStateSpace::ScopedState aikido::planner::dart::ConfigurationToConfiguration::mGoalState
protected

Goal state.

◆ mMetaSkeleton

::dart::dynamics::ConstMetaSkeletonPtr aikido::planner::dart::ConfigurationToConfiguration::mMetaSkeleton
protected

MetaSkeleton, if given.

◆ mMetaSkeletonStateSpace

statespace::dart::ConstMetaSkeletonStateSpacePtr aikido::planner::dart::ConfigurationToConfiguration::mMetaSkeletonStateSpace
protected

MetaSkeletonStateSpace.

Prevents use of expensive dynamic cast on mStateSpace.

◆ mStartState

statespace::dart::MetaSkeletonStateSpace::ScopedState aikido::planner::dart::ConfigurationToConfiguration::mStartState
protected

Start state.