| 
    Aikido
    
   | 
 
Planning problem to plan to desired end-effector offset while maintaining the current end-effector orientation. More...
#include <aikido/planner/dart/ConfigurationToEndEffectorOffset.hpp>
  
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::State * | getStartState () 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... | |
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.
| 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.
| [in] | stateSpace | State space. | 
| [in] | metaSkeleton | MetaSkeleton that getStartState will return the current state of when called. | 
| [in] | endEffectorBodyNode | BodyNode to be planned to move to a desired offest while maintaining the current orientation. | 
| [in] | direction | Unit vector that represents the direction of motion [unit vector in the world frame]. | 
| [in] | signedDistance | Signed distance to move, in meters. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| If | the size of direction is zero.  | 
| 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.
| [in] | stateSpace | State space. | 
| [in] | startState | Start state to plan from. | 
| [in] | endEffectorBodyNode | BodyNode to be planned to move to a desired offest while maintaining the current orientation. | 
| [in] | direction | Unit vector that represents the direction of motion [unit vector in the world frame]. | 
| [in] | signedDistance | Signed distance to move, in meters. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| If | the size of direction is zero.  | 
| 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.
| [in] | stateSpace | State space. | 
| [in] | metaSkeleton | MetaSkeleton that getStartState will return the current state of when called. | 
| [in] | endEffectorBodyNode | BodyNode to be planned to move to a desired offest while maintaining the current orientation. Current direction is returned when getDirection is called. | 
| [in] | signedDistance | Signed distance to move, in meters. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| 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.
| [in] | stateSpace | State space. | 
| [in] | startState | Start state to plan from. | 
| [in] | endEffectorBodyNode | BodyNode to be planned to move to a desired offest while maintaining the current orientation. Current direction is returned when getDirection is called. | 
| [in] | signedDistance | Signed distance to move, in meters. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| 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.
| double aikido::planner::dart::ConfigurationToEndEffectorOffset::getDistance | ( | ) | const | 
Returns the signed distance in meters to move in the specified direction.
| ::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.
| 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.
      
  | 
  static | 
Returns the type of the planning problem.
      
  | 
  overridevirtual | 
Returns type of this planning problem.
Implements aikido::planner::Problem.
      
  | 
  protected | 
Direction of motion, if set on construction.
      
  | 
  protected | 
Signed distance to move in the direction specified.
      
  | 
  protected | 
End-effector body node.
      
  | 
  protected | 
MetaSkeleton, if given.
      
  | 
  protected | 
MetaSkeletonStateSpace.
Prevents use of expensive dynamic cast on mStateSpace.
      
  | 
  protected | 
Start state, if set on construction.