Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTOROFFSET_HPP_
2 #define AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTOROFFSET_HPP_
4 #include <boost/optional.hpp>
5 #include <dart/dart.hpp>
42 ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
43 ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
44 const Eigen::Vector3d& direction,
45 double signedDistance,
63 ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
64 const Eigen::Vector3d& direction,
65 double signedDistance,
82 ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
83 ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
84 double signedDistance,
101 ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
102 double signedDistance,
106 const std::string&
getType()
const override;
152 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTOROFFSET_HPP_
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
ConfigurationToEndEffectorOffset(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, const Eigen::Vector3d &direction, double signedDistance, constraint::ConstTestablePtr constraint=nullptr)
Constructor.
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
Eigen::Vector3d getDirection() const
Returns the direction of motion specified in the world frame.
const std::string & getType() const override
Returns type of this planning problem.
const double mDistance
Signed distance to move in the direction specified.
Definition: ConfigurationToEndEffectorOffset.hpp:145
const boost::optional< Eigen::Vector3d > mDirection
Direction of motion, if set on construction.
Definition: ConfigurationToEndEffectorOffset.hpp:142
double getDistance() const
Returns the signed distance in meters to move in the specified direction.
::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton
MetaSkeleton, if given.
Definition: ConfigurationToEndEffectorOffset.hpp:133
Base class for various planning problems.
Definition: Problem.hpp:13
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
Start state, if set on construction.
Definition: ConfigurationToEndEffectorOffset.hpp:136
A tuple of states where the i-th state is from the i-th subspace.
Definition: CartesianProduct.hpp:162
static const std::string & getStaticType()
Returns the type of the planning problem.
Planning problem to plan to desired end-effector offset while maintaining the current end-effector or...
Definition: ConfigurationToEndEffectorOffset.hpp:23
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
::dart::dynamics::ConstBodyNodePtr getEndEffectorBodyNode() const
Returns the end-effector BodyNode to be planned to move a desired offest while maintaining the curren...
statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
MetaSkeletonStateSpace.
Definition: ConfigurationToEndEffectorOffset.hpp:130
const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode
End-effector body node.
Definition: ConfigurationToEndEffectorOffset.hpp:139
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13