Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_DART_CONFIGURATIONTOTSR_HPP_
2 #define AIKIDO_PLANNER_DART_CONFIGURATIONTOTSR_HPP_
4 #include <dart/dart.hpp>
34 ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
35 ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
36 std::size_t maxSamples,
55 ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
56 std::size_t maxSamples,
61 const std::string&
getType()
const override;
104 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOTSR_HPP_
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
Planning problem to plan to a given single Task Space Region (TSR).
Definition: ConfigurationToTSR.hpp:16
::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton
MetaSkeleton, if given.
Definition: ConfigurationToTSR.hpp:85
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
MetaSkeletonStateSpace.
Definition: ConfigurationToTSR.hpp:82
std::shared_ptr< const TSR > ConstTSRPtr
Definition: TSR.hpp:17
const std::string & getType() const override
Returns type of this planning problem.
static const std::string & getStaticType()
Returns the type of the planning problem.
std::size_t getMaxSamples() const
Returns the maximum number of TSR samples to plan to.
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
Start state, if set on construction.
Definition: ConfigurationToTSR.hpp:88
Base class for various planning problems.
Definition: Problem.hpp:13
constraint::dart::ConstTSRPtr getGoalTSR() const
Returns the goal TSR.
::dart::dynamics::ConstBodyNodePtr getEndEffectorBodyNode() const
Returns the end-effector BodyNode to be planned to move to a desired TSR.
A tuple of states where the i-th state is from the i-th subspace.
Definition: CartesianProduct.hpp:162
std::size_t mMaxSamples
Maximum number of TSR samples to plan to.
Definition: ConfigurationToTSR.hpp:94
ConfigurationToTSR(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, std::size_t maxSamples, constraint::dart::ConstTSRPtr goalTSR, constraint::ConstTestablePtr constraint=nullptr)
Constructor.
const statespace::dart::MetaSkeletonStateSpace::State * getStartState() const
Returns the start state to plan from, either set on construction or taken from the current state of t...
Definition: FrameMarker.hpp:11
const constraint::dart::ConstTSRPtr mGoalTSR
Goal TSR.
Definition: ConfigurationToTSR.hpp:97
const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode
End-effector body node.
Definition: ConfigurationToTSR.hpp:91
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13