Aikido
|
Planning problem to plan to multiple goal configurations. More...
#include <aikido/planner/ConfigurationToConfigurations.hpp>
Public Types | |
using | GoalStates = std::vector< const statespace::StateSpace::State * > |
Public Member Functions | |
ConfigurationToConfigurations (statespace::ConstStateSpacePtr stateSpace, const statespace::StateSpace::State *startState, const GoalStates &goalStates, 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... | |
std::size_t | getNumGoalStates () const |
Returns the number of the goal states. More... | |
GoalStates | getGoalStates () const |
Returns goal states. More... | |
![]() | |
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... | |
std::vector< statespace::StateSpace::ScopedState > | mGoalStates |
Goal States. More... | |
![]() | |
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.
Plan a trajectory from start state to any of the goal states using an interpolator to interpolate between the states.
using aikido::planner::ConfigurationToConfigurations::GoalStates = std::vector<const statespace::StateSpace::State*> |
aikido::planner::ConfigurationToConfigurations::ConfigurationToConfigurations | ( | statespace::ConstStateSpacePtr | stateSpace, |
const statespace::StateSpace::State * | startState, | ||
const GoalStates & | goalStates, | ||
constraint::ConstTestablePtr | constraint | ||
) |
Constructor.
[in] | stateSpace | State space. |
[in] | startState | Start state. |
[in] | goalStates | Goal states. |
[in] | constraint | Trajectory-wide constraint that must be satisfied. |
If | stateSpace is not compatible with constraint's state space. |
GoalStates aikido::planner::ConfigurationToConfigurations::getGoalStates | ( | ) | const |
Returns goal states.
std::size_t aikido::planner::ConfigurationToConfigurations::getNumGoalStates | ( | ) | const |
Returns the number of the goal states.
const statespace::StateSpace::State* aikido::planner::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 |
Start state.