Aikido
aikido::planner::dart::ConfigurationToEndEffectorOffset Class Reference

Planning problem to plan to desired end-effector offset while maintaining the current end-effector orientation. More...

#include <aikido/planner/dart/ConfigurationToEndEffectorOffset.hpp>

Inheritance diagram for aikido::planner::dart::ConfigurationToEndEffectorOffset:
aikido::planner::Problem

Public Member Functions

 ConfigurationToEndEffectorOffset (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, const Eigen::Vector3d &direction, double signedDistance, constraint::ConstTestablePtr constraint=nullptr)
 Constructor. More...
 
 ConfigurationToEndEffectorOffset (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, const statespace::dart::MetaSkeletonStateSpace::State *startState, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, const Eigen::Vector3d &direction, double signedDistance, constraint::ConstTestablePtr constraint=nullptr)
 Constructor. More...
 
 ConfigurationToEndEffectorOffset (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, double signedDistance, constraint::ConstTestablePtr constraint=nullptr)
 Constructor. More...
 
 ConfigurationToEndEffectorOffset (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, const statespace::dart::MetaSkeletonStateSpace::State *startState, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, double signedDistance, constraint::ConstTestablePtr constraint=nullptr)
 Constructor. More...
 
const std::string & getType () const override
 Returns type of this planning problem. More...
 
::dart::dynamics::ConstBodyNodePtr getEndEffectorBodyNode () const
 Returns the end-effector BodyNode to be planned to move a desired offest while maintaining the current orientation. More...
 
const statespace::dart::MetaSkeletonStateSpace::StategetStartState () const
 Returns the start state to plan from, either set on construction or taken from the current state of the MetaSkeleton. More...
 
Eigen::Vector3d getDirection () const
 Returns the direction of motion specified in the world frame. More...
 
double getDistance () const
 Returns the signed distance in meters to move in the specified direction. More...
 
- Public Member Functions inherited from aikido::planner::Problem
 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::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
 MetaSkeletonStateSpace. More...
 
::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton
 MetaSkeleton, if given. More...
 
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
 Start state, if set on construction. More...
 
const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode
 End-effector body node. More...
 
const boost::optional< Eigen::Vector3d > mDirection
 Direction of motion, if set on construction. More...
 
const double mDistance
 Signed distance to move in the direction specified. More...
 
- Protected Attributes inherited from aikido::planner::Problem
statespace::ConstStateSpacePtr mStateSpace
 State space associated with this problem. More...
 
constraint::ConstTestablePtr mConstraint
 Trajectory-wide constraint that must be satisfied. More...
 

Detailed Description

Planning problem to plan to desired end-effector offset while maintaining the current end-effector orientation.

Each constructor makes two choices: whether to take in a direction, and taking in either a start state OR a MetaSkeleton. If a direction is not passed, getDirection returns the current direction of the end effector body node. If a MetaSkeleton is passed instead of a start state, getStartState will return the current state of that MetaSkeleton. Thus, there are 2x2=4 constructors here.

Constructor & Destructor Documentation

◆ ConfigurationToEndEffectorOffset() [1/4]

aikido::planner::dart::ConfigurationToEndEffectorOffset::ConfigurationToEndEffectorOffset ( statespace::dart::ConstMetaSkeletonStateSpacePtr  stateSpace,
::dart::dynamics::ConstMetaSkeletonPtr  metaSkeleton,
::dart::dynamics::ConstBodyNodePtr  endEffectorBodyNode,
const Eigen::Vector3d &  direction,
double  signedDistance,
constraint::ConstTestablePtr  constraint = nullptr 
)

Constructor.

Note that this constructor takes the start state from the current state of the passed MetaSkeleton, and sets the direction on construction.

Parameters
[in]stateSpaceState space.
[in]metaSkeletonMetaSkeleton that getStartState will return the current state of when called.
[in]endEffectorBodyNodeBodyNode to be planned to move to a desired offest while maintaining the current orientation.
[in]directionUnit vector that represents the direction of motion [unit vector in the world frame].
[in]signedDistanceSigned distance to move, in meters.
[in]constraintTrajectory-wide constraint that must be satisfied.
Exceptions
Ifthe size of direction is zero.

◆ ConfigurationToEndEffectorOffset() [2/4]

aikido::planner::dart::ConfigurationToEndEffectorOffset::ConfigurationToEndEffectorOffset ( statespace::dart::ConstMetaSkeletonStateSpacePtr  stateSpace,
const statespace::dart::MetaSkeletonStateSpace::State startState,
::dart::dynamics::ConstBodyNodePtr  endEffectorBodyNode,
const Eigen::Vector3d &  direction,
double  signedDistance,
constraint::ConstTestablePtr  constraint = nullptr 
)

Constructor.

Note that this constructor sets the start state and direction on construction.

Parameters
[in]stateSpaceState space.
[in]startStateStart state to plan from.
[in]endEffectorBodyNodeBodyNode to be planned to move to a desired offest while maintaining the current orientation.
[in]directionUnit vector that represents the direction of motion [unit vector in the world frame].
[in]signedDistanceSigned distance to move, in meters.
[in]constraintTrajectory-wide constraint that must be satisfied.
Exceptions
Ifthe size of direction is zero.

◆ ConfigurationToEndEffectorOffset() [3/4]

aikido::planner::dart::ConfigurationToEndEffectorOffset::ConfigurationToEndEffectorOffset ( statespace::dart::ConstMetaSkeletonStateSpacePtr  stateSpace,
::dart::dynamics::ConstMetaSkeletonPtr  metaSkeleton,
::dart::dynamics::ConstBodyNodePtr  endEffectorBodyNode,
double  signedDistance,
constraint::ConstTestablePtr  constraint = nullptr 
)

Constructor.

Note that this constructor takes the start state from the current state of the passed MetaSkeleton, and takes the direction from the end-effector BodyNode's current direction.

Parameters
[in]stateSpaceState space.
[in]metaSkeletonMetaSkeleton that getStartState will return the current state of when called.
[in]endEffectorBodyNodeBodyNode to be planned to move to a desired offest while maintaining the current orientation. Current direction is returned when getDirection is called.
[in]signedDistanceSigned distance to move, in meters.
[in]constraintTrajectory-wide constraint that must be satisfied.

◆ ConfigurationToEndEffectorOffset() [4/4]

aikido::planner::dart::ConfigurationToEndEffectorOffset::ConfigurationToEndEffectorOffset ( statespace::dart::ConstMetaSkeletonStateSpacePtr  stateSpace,
const statespace::dart::MetaSkeletonStateSpace::State startState,
::dart::dynamics::ConstBodyNodePtr  endEffectorBodyNode,
double  signedDistance,
constraint::ConstTestablePtr  constraint = nullptr 
)

Constructor.

Note that this constructor sets the start state on construction, and takes the direction from the end-effector BodyNode's current direction.

Parameters
[in]stateSpaceState space.
[in]startStateStart state to plan from.
[in]endEffectorBodyNodeBodyNode to be planned to move to a desired offest while maintaining the current orientation. Current direction is returned when getDirection is called.
[in]signedDistanceSigned distance to move, in meters.
[in]constraintTrajectory-wide constraint that must be satisfied.

Member Function Documentation

◆ getDirection()

Eigen::Vector3d aikido::planner::dart::ConfigurationToEndEffectorOffset::getDirection ( ) const

Returns the direction of motion specified in the world frame.

Note that if no direction was passed, the current direction of the end effector body node is returned.

◆ getDistance()

double aikido::planner::dart::ConfigurationToEndEffectorOffset::getDistance ( ) const

Returns the signed distance in meters to move in the specified direction.

◆ getEndEffectorBodyNode()

::dart::dynamics::ConstBodyNodePtr aikido::planner::dart::ConfigurationToEndEffectorOffset::getEndEffectorBodyNode ( ) const

Returns the end-effector BodyNode to be planned to move a desired offest while maintaining the current orientation.

◆ getStartState()

const statespace::dart::MetaSkeletonStateSpace::State* aikido::planner::dart::ConfigurationToEndEffectorOffset::getStartState ( ) const

Returns the start state to plan from, either set on construction or taken from the current state of the MetaSkeleton.

◆ getStaticType()

static const std::string& aikido::planner::dart::ConfigurationToEndEffectorOffset::getStaticType ( )
static

Returns the type of the planning problem.

◆ getType()

const std::string& aikido::planner::dart::ConfigurationToEndEffectorOffset::getType ( ) const
overridevirtual

Returns type of this planning problem.

Implements aikido::planner::Problem.

Member Data Documentation

◆ mDirection

const boost::optional<Eigen::Vector3d> aikido::planner::dart::ConfigurationToEndEffectorOffset::mDirection
protected

Direction of motion, if set on construction.

◆ mDistance

const double aikido::planner::dart::ConfigurationToEndEffectorOffset::mDistance
protected

Signed distance to move in the direction specified.

◆ mEndEffectorBodyNode

const ::dart::dynamics::ConstBodyNodePtr aikido::planner::dart::ConfigurationToEndEffectorOffset::mEndEffectorBodyNode
protected

End-effector body node.

◆ mMetaSkeleton

::dart::dynamics::ConstMetaSkeletonPtr aikido::planner::dart::ConfigurationToEndEffectorOffset::mMetaSkeleton
protected

MetaSkeleton, if given.

◆ mMetaSkeletonStateSpace

statespace::dart::ConstMetaSkeletonStateSpacePtr aikido::planner::dart::ConfigurationToEndEffectorOffset::mMetaSkeletonStateSpace
protected

MetaSkeletonStateSpace.

Prevents use of expensive dynamic cast on mStateSpace.

◆ mStartState

statespace::dart::MetaSkeletonStateSpace::ScopedState aikido::planner::dart::ConfigurationToEndEffectorOffset::mStartState
protected

Start state, if set on construction.