Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTORPOSE_HPP_
2 #define AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTORPOSE_HPP_
4 #include <dart/dart.hpp>
31 ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
32 ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
33 const Eigen::Isometry3d& goalPose,
49 ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
50 const Eigen::Isometry3d& goalPose,
54 const std::string&
getType()
const override;
71 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
94 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTORPOSE_HPP_
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
::dart::dynamics::ConstBodyNodePtr getEndEffectorBodyNode() const
Returns the end-effector BodyNode to be planned to move to a desired pose.
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
Start state, if set on construction.
Definition: ConfigurationToEndEffectorPose.hpp:81
::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton
MetaSkeleton, if given.
Definition: ConfigurationToEndEffectorPose.hpp:78
statespace::ScopedState< StateHandle > ScopedState
Definition: CartesianProduct.hpp:28
ConfigurationToEndEffectorPose(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, const Eigen::Isometry3d &goalPose, constraint::ConstTestablePtr constraint=nullptr)
Constructor.
static const std::string & getStaticType()
Returns the type of the planning problem.
const std::string & getType() const override
Returns type of this planning problem.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
MetaSkeletonStateSpace.
Definition: ConfigurationToEndEffectorPose.hpp:75
const Eigen::Isometry3d & getGoalPose() const
Returns the goal pose.
Base class for various planning problems.
Definition: Problem.hpp:13
const statespace::dart::MetaSkeletonStateSpace::State * getStartState() const
Return the start state to plan from, either set on construction or taken from the current state of th...
A tuple of states where the i-th state is from the i-th subspace.
Definition: CartesianProduct.hpp:162
Planning problem to plan to a desired end-effector pose.
Definition: ConfigurationToEndEffectorPose.hpp:15
const Eigen::Isometry3d mGoalPose
Goal pose.
Definition: ConfigurationToEndEffectorPose.hpp:87
Definition: FrameMarker.hpp:11
const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode
End-effector body node.
Definition: ConfigurationToEndEffectorPose.hpp:84
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13