Aikido
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField Class Reference

Vector field for moving end-effector to a goal pose in SE(3). More...

#include <aikido/planner/vectorfield/MoveEndEffectorPoseVectorField.hpp>

Inheritance diagram for aikido::planner::vectorfield::MoveEndEffectorPoseVectorField:
aikido::planner::vectorfield::BodyNodePoseVectorField aikido::planner::vectorfield::VectorField

Public Member Functions

 MoveEndEffectorPoseVectorField (aikido::statespace::dart::MetaSkeletonStateSpacePtr stateSpace, dart::dynamics::MetaSkeletonPtr metaskeleton, dart::dynamics::BodyNodePtr bn, const Eigen::Isometry3d &goalPose, double poseErrorTolerance, double r, double maxStepSize, double jointLimitPadding)
 Constructor. More...
 
bool evaluateCartesianVelocity (const Eigen::Isometry3d &pose, Eigen::Vector6d &cartesianVelocity) const override
 Evaluate Cartesian velocity by current pose of body node. More...
 
VectorFieldPlannerStatus evaluateCartesianStatus (const Eigen::Isometry3d &pose) const override
 Evaluate current pose to determine the status of planning. More...
 
- Public Member Functions inherited from aikido::planner::vectorfield::BodyNodePoseVectorField
 BodyNodePoseVectorField (aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr metaSkeletonStateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr bodyNode, double maxStepSize, double jointLimitPadding, bool enforceJointVelocityLimits=false)
 Constructor. More...
 
bool evaluateVelocity (const aikido::statespace::StateSpace::State *state, Eigen::VectorXd &qd) const override
 Vectorfield callback function. More...
 
VectorFieldPlannerStatus evaluateStatus (const aikido::statespace::StateSpace::State *state) const override
 Vectorfield planning status callback function. More...
 
bool evaluateTrajectory (const aikido::trajectory::Trajectory &trajectory, const aikido::constraint::Testable *constraint, double evalStepSize, double &evalTimePivot, bool includeEndTime) const override
 Evaludate whether a trajectory satisfies a constraint. More...
 
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr getMetaSkeletonStateSpace () const
 Return const meta skeleton state space. More...
 
::dart::dynamics::MetaSkeletonPtr getMetaSkeleton ()
 Returns meta skeleton. More...
 
::dart::dynamics::ConstMetaSkeletonPtr getMetaSkeleton () const
 Returns const meta skeleton. More...
 
::dart::dynamics::ConstBodyNodePtr getBodyNode () const
 Returns const body node of end-effector. More...
 
- Public Member Functions inherited from aikido::planner::vectorfield::VectorField
 VectorField (aikido::statespace::ConstStateSpacePtr stateSpace)
 Constructor. More...
 
virtual ~VectorField ()=default
 Destructor. More...
 
aikido::statespace::ConstStateSpacePtr getStateSpace ()
 Returns state space. More...
 
aikido::statespace::ConstStateSpacePtr getStateSpace () const
 Returns const state space. More...
 

Protected Attributes

Eigen::Isometry3d mGoalPose
 Goal pose. More...
 
double mPoseErrorTolerance
 Tolerance of pose error. More...
 
double mConversionRatioFromRadiusToMeter
 Conversion ratio from radius to meter. More...
 
- Protected Attributes inherited from aikido::planner::vectorfield::BodyNodePoseVectorField
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
 Meta skeleton state space. More...
 
::dart::dynamics::MetaSkeletonPtr mMetaSkeleton
 Meta Skeleton. More...
 
::dart::dynamics::ConstBodyNodePtr mBodyNode
 BodyNode. More...
 
double mMaxStepSize
 Maximum step size of integrator. More...
 
double mJointLimitPadding
 Padding of joint limits. More...
 
Eigen::VectorXd mVelocityLowerLimits
 Joint velocities lower limits. More...
 
Eigen::VectorXd mVelocityUpperLimits
 Joint velocities upper limits. More...
 
bool mEnforceJointVelocityLimits
 Enfoce joint velocity limits. More...
 
- Protected Attributes inherited from aikido::planner::vectorfield::VectorField
aikido::statespace::ConstStateSpacePtr mStateSpace
 State space. More...
 

Detailed Description

Vector field for moving end-effector to a goal pose in SE(3).

It defines a vector field in meta-skeleton state space that moves an end-effector a desired pose in SE(3) by following a geodesic loss function in SE(3) via an optimized Jacobian. The geodesic loss function is defined as the geodesic (shortest path) from the current pose to the goal pose.

This class defines two callback functions for vectorfield planner. One for generating joint velocity in MetaSkeleton state space, and one for determining vectorfield planner status.

Constructor & Destructor Documentation

◆ MoveEndEffectorPoseVectorField()

aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::MoveEndEffectorPoseVectorField ( aikido::statespace::dart::MetaSkeletonStateSpacePtr  stateSpace,
dart::dynamics::MetaSkeletonPtr  metaskeleton,
dart::dynamics::BodyNodePtr  bn,
const Eigen::Isometry3d &  goalPose,
double  poseErrorTolerance,
double  r,
double  maxStepSize,
double  jointLimitPadding 
)

Constructor.

Parameters
[in]stateSpaceMetaSkeleton state space.
[in]metaskeletonMetaSkeleton to plan with
[in]bnBody node of end-effector.
[in]goalPoseDesired end-effector pose.
[in]poseErrorToleranceConstraint error tolerance in meters.
[in]rConversion of radius to meters in computing Geodesic distance.
[in]maxStepSizeThe maximum step size used to guarantee that the integrator does not step out of joint limits.
[in]jointLimitPaddingIf less then this distance to joint limit, velocity is bounded in that direction to 0.

Member Function Documentation

◆ evaluateCartesianStatus()

VectorFieldPlannerStatus aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::evaluateCartesianStatus ( const Eigen::Isometry3d &  pose) const
overridevirtual

Evaluate current pose to determine the status of planning.

Parameters
[in]poseCurrent pose of body node.
Returns
Status of planner.

Implements aikido::planner::vectorfield::BodyNodePoseVectorField.

◆ evaluateCartesianVelocity()

bool aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::evaluateCartesianVelocity ( const Eigen::Isometry3d &  pose,
Eigen::Vector6d &  cartesianVelocity 
) const
overridevirtual

Evaluate Cartesian velocity by current pose of body node.

Parameters
[in]poseCurrent pose of body node.
[out]cartesianVelocityCartesian velocity defined in se(3).

Implements aikido::planner::vectorfield::BodyNodePoseVectorField.

Member Data Documentation

◆ mConversionRatioFromRadiusToMeter

double aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mConversionRatioFromRadiusToMeter
protected

Conversion ratio from radius to meter.

◆ mGoalPose

Eigen::Isometry3d aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mGoalPose
protected

Goal pose.

◆ mPoseErrorTolerance

double aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mPoseErrorTolerance
protected

Tolerance of pose error.