Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_DART_CONFIGURATIONTOCONFIGURATIONS_HPP_
2 #define AIKIDO_PLANNER_DART_CONFIGURATIONTOCONFIGURATIONS_HPP_
4 #include <dart/dart.hpp>
19 = std::vector<const statespace::dart::MetaSkeletonStateSpace::State*>;
31 ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
49 const std::string&
getType()
const override;
75 std::vector<statespace::dart::MetaSkeletonStateSpace::ScopedState>
83 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOCONFIGURATIONS_HPP_
std::vector< statespace::dart::MetaSkeletonStateSpace::ScopedState > mGoalStates
Goal States.
Definition: ConfigurationToConfigurations.hpp:76
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
Planning problem to plan to multiple goal configurations.
Definition: ConfigurationToConfigurations.hpp:15
std::vector< const statespace::dart::MetaSkeletonStateSpace::State * > GoalStates
Definition: ConfigurationToConfigurations.hpp:19
::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton
MetaSkeleton, if given.
Definition: ConfigurationToConfigurations.hpp:69
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
MetaSkeletonStateSpace.
Definition: ConfigurationToConfigurations.hpp:66
const std::string & getType() const override
Returns type of this planning problem.
const statespace::dart::MetaSkeletonStateSpace::State * getStartState() const
Returns the start state.
static const std::string & getStaticType()
Returns the type of the planning problem.
Base class for various planning problems.
Definition: Problem.hpp:13
A tuple of states where the i-th state is from the i-th subspace.
Definition: CartesianProduct.hpp:162
std::size_t getNumGoalStates() const
Returns the number of the goal states.
ConfigurationToConfigurations(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, const GoalStates &goalStates, constraint::ConstTestablePtr constraint=nullptr)
Constructor.
Definition: FrameMarker.hpp:11
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
Start state.
Definition: ConfigurationToConfigurations.hpp:72
GoalStates getGoalStates() const
Returns goal states.
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13