Aikido
aikido::planner::vectorfield Namespace Reference

Classes

class  BodyNodePoseVectorField
 This class is a vector field over a MetaSkeletonStateSpace that is defined in terms of a Cartesian vector field over the pose of a BodyNode in that MetaSkeleton. More...
 
class  MoveEndEffectorOffsetVectorField
 Vector field for moving end-effector by a direction and distance. More...
 
class  MoveEndEffectorPoseVectorField
 Vector field for moving end-effector to a goal pose in SE(3). More...
 
class  VectorField
 This class defines a vector field. More...
 
class  VectorFieldConfigurationToEndEffectorOffsetPlanner
 Planner that generates a trajectory that moves the end-effector by a given direction and distance. More...
 

Typedefs

using BodyNodePoseVectorFieldPtr = std::shared_ptr< BodyNodePoseVectorField >
 
using ConstBodyNodePoseVectorFieldPtr = std::shared_ptr< const BodyNodePoseVectorField >
 
using WeakBodyNodePoseVectorFieldPtr = std::weak_ptr< BodyNodePoseVectorField >
 
using WeakConstBodyNodePoseVectorFieldPtr = std::weak_ptr< const BodyNodePoseVectorField >
 
using UniqueBodyNodePoseVectorFieldPtr = std::unique_ptr< BodyNodePoseVectorField >
 
using UniqueConstBodyNodePoseVectorFieldPtr = std::unique_ptr< const BodyNodePoseVectorField >
 
using VectorFieldPtr = std::shared_ptr< VectorField >
 

Enumerations

enum  VectorFieldPlannerStatus { VectorFieldPlannerStatus::TERMINATE, VectorFieldPlannerStatus::CACHE_AND_CONTINUE, VectorFieldPlannerStatus::CONTINUE, VectorFieldPlannerStatus::CACHE_AND_TERMINATE }
 Status of planning. More...
 

Functions

aikido::trajectory::UniqueInterpolatedPtr followVectorField (const aikido::planner::vectorfield::VectorField &vectorField, const aikido::statespace::StateSpace::State &startState, const aikido::constraint::Testable &constraint, std::chrono::duration< double > timelimit, double initialStepSize, double checkConstraintResolution, planner::Planner::Result *result)
 Generate a trajectory following the vector field along given time. More...
 
aikido::trajectory::UniqueInterpolatedPtr planToEndEffectorOffset (const aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr &stateSpace, const statespace::dart::MetaSkeletonStateSpace::State &startState, ::dart::dynamics::MetaSkeletonPtr metaskeleton, const ::dart::dynamics::ConstBodyNodePtr &bn, const aikido::constraint::ConstTestablePtr &constraint, const Eigen::Vector3d &direction, double minDistance, double maxDistance, double positionTolerance, double angularTolerance, double initialStepSize, double jointLimitTolerance, double constraintCheckResolution, std::chrono::duration< double > timelimit, planner::Planner::Result *result=nullptr)
 Plan to a trajectory that moves the end-effector by a given direction and distance. More...
 
aikido::trajectory::UniqueInterpolatedPtr planToEndEffectorPose (const aikido::statespace::dart::MetaSkeletonStateSpacePtr &stateSpace, ::dart::dynamics::MetaSkeletonPtr metaskeleton, const ::dart::dynamics::BodyNodePtr &bn, const aikido::constraint::TestablePtr &constraint, const Eigen::Isometry3d &goalPose, double poseErrorTolerance, double conversionRatioInGeodesicDistance, double initialStepSize, double jointLimitTolerance, double constraintCheckResolution, std::chrono::duration< double > timelimit, planner::Planner::Result *result=nullptr)
 Plan to an end-effector pose by following a geodesic loss function in SE(3) via an optimized Jacobian. More...
 
bool computeJointVelocityFromTwist (Eigen::VectorXd &jointVelocity, const Eigen::Vector6d &desiredTwist, const ::dart::dynamics::MetaSkeletonPtr metaSkeleton, const ::dart::dynamics::ConstBodyNodePtr bodyNode, double jointLimitPadding, const Eigen::VectorXd &jointVelocityLowerLimits, const Eigen::VectorXd &jointVelocityUpperLimits, bool enforceJointVelocityLimits, double stepSize)
 Compute joint velocity from a given twist. More...
 
Eigen::Vector6d computeGeodesicTwist (const Eigen::Isometry3d &fromTrans, const Eigen::Isometry3d &toTrans)
 Compute the twist in global coordinate that corresponds to the gradient of the geodesic distance between two transforms. More...
 
Eigen::Vector4d computeGeodesicError (const Eigen::Isometry3d &fromTrans, const Eigen::Isometry3d &toTrans)
 Compute the error in gloabl coordinate between two transforms. More...
 
double computeGeodesicDistance (const Eigen::Isometry3d &fromTrans, const Eigen::Isometry3d &toTrans, double r)
 Compute the geodesic distance between two transforms. More...
 

Typedef Documentation

◆ BodyNodePoseVectorFieldPtr

◆ ConstBodyNodePoseVectorFieldPtr

◆ UniqueBodyNodePoseVectorFieldPtr

◆ UniqueConstBodyNodePoseVectorFieldPtr

◆ VectorFieldPtr

◆ WeakBodyNodePoseVectorFieldPtr

◆ WeakConstBodyNodePoseVectorFieldPtr

Enumeration Type Documentation

◆ VectorFieldPlannerStatus

Status of planning.

TERMINATE - stop gracefully and output the CACHEd trajectory. CACHE_AND_CONTINUE - save the current trajectory and CONTINUE. return the saved trajectory if TERMINATEd. CONTINUE - keep going. CACHE_AND_TERMINATE - save the current trajectory and TERMINATE.

Enumerator
TERMINATE 
CACHE_AND_CONTINUE 
CONTINUE 
CACHE_AND_TERMINATE 

Function Documentation

◆ computeGeodesicDistance()

double aikido::planner::vectorfield::computeGeodesicDistance ( const Eigen::Isometry3d &  fromTrans,
const Eigen::Isometry3d &  toTrans,
double  r 
)

Compute the geodesic distance between two transforms.

gd = norm( relative translation + r * axis-angle error )

Parameters
[in]fromTransCurrent transformation.
[in]toTransGoal transformation.
[in]rIn units of meters/radians converts radians to meters.
Returns
Geodesic distance in meter.

◆ computeGeodesicError()

Eigen::Vector4d aikido::planner::vectorfield::computeGeodesicError ( const Eigen::Isometry3d &  fromTrans,
const Eigen::Isometry3d &  toTrans 
)

Compute the error in gloabl coordinate between two transforms.

Parameters
[in]fromTransCurrent transformation.
[in]toTransGoal transformation.
Returns
Geodesic error in global coordinate. It is a 4d vector, in which the first element is the norm of angle difference (in radian), and the last three elements are translation difference (in meter).

◆ computeGeodesicTwist()

Eigen::Vector6d aikido::planner::vectorfield::computeGeodesicTwist ( const Eigen::Isometry3d &  fromTrans,
const Eigen::Isometry3d &  toTrans 
)

Compute the twist in global coordinate that corresponds to the gradient of the geodesic distance between two transforms.

Parameters
[in]fromTransCurrent transformation.
[in]toTransGoal transformation.
Returns
Geodesic twist in global coordinate. It corresponds to the gradient of the geodesic distance between two transforms. The first three are angular velocities (meters per second), and the last three are linear velocities (radian per sec).

◆ computeJointVelocityFromTwist()

bool aikido::planner::vectorfield::computeJointVelocityFromTwist ( Eigen::VectorXd &  jointVelocity,
const Eigen::Vector6d &  desiredTwist,
const ::dart::dynamics::MetaSkeletonPtr  metaSkeleton,
const ::dart::dynamics::ConstBodyNodePtr  bodyNode,
double  jointLimitPadding,
const Eigen::VectorXd &  jointVelocityLowerLimits,
const Eigen::VectorXd &  jointVelocityUpperLimits,
bool  enforceJointVelocityLimits,
double  stepSize 
)

Compute joint velocity from a given twist.

Parameters
[out]jointVelocityCalculated joint velocities.
[in]desiredTwistDesired twist, which consists of angular velocity and linear velocity.
[in]metaSkeletonMetaSkeleton to plan with
[in]bodyNodeBody node of the end-effector.
[in]jointLimitPaddingIf less then this distance to joint limit, velocity is bounded in that direction to 0.
[in]jointVelocityLowerLimitsJoint velocity lower bounds.
[in]jointVelocityUpperLimitsJoint velocity upper bounds.
[in]enforceJointVelocityLimitsWhether joint velocity limits are considered in computation.
[in]stepSizeStep size in second. It is used in evaluating position bounds violation. It assumes that whether moving the time of stepSize by maximum joint velocity will reach the limit.
Returns
Whether a joint velocity is found

◆ followVectorField()

aikido::trajectory::UniqueInterpolatedPtr aikido::planner::vectorfield::followVectorField ( const aikido::planner::vectorfield::VectorField vectorField,
const aikido::statespace::StateSpace::State startState,
const aikido::constraint::Testable constraint,
std::chrono::duration< double >  timelimit,
double  initialStepSize,
double  checkConstraintResolution,
planner::Planner::Result result 
)

Generate a trajectory following the vector field along given time.

Note
The resulting interpolated trajectory is formed by taking the knots of the planned spline trajectory, which is not geometrically equivalent. See https://github.com/personalrobotics/aikido/issues/512
Parameters
[in]vectorFieldVector field to follow.
[in]startStateStart state of the planning.
[in]constraintConstraint to be satisfied.
[in]timelimitTimelimit for integration calculation.
[in]initialStepSizeInitial step size of integator in following vector field.
[in]checkConstraintResolutionResolution used in checking constraint satisfaction in generated trajectory.
[out]resultinformation about success or failure.
Returns
A trajectory following the vector field.

◆ planToEndEffectorOffset()

aikido::trajectory::UniqueInterpolatedPtr aikido::planner::vectorfield::planToEndEffectorOffset ( const aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace,
const statespace::dart::MetaSkeletonStateSpace::State startState,
::dart::dynamics::MetaSkeletonPtr  metaskeleton,
const ::dart::dynamics::ConstBodyNodePtr &  bn,
const aikido::constraint::ConstTestablePtr constraint,
const Eigen::Vector3d &  direction,
double  minDistance,
double  maxDistance,
double  positionTolerance,
double  angularTolerance,
double  initialStepSize,
double  jointLimitTolerance,
double  constraintCheckResolution,
std::chrono::duration< double >  timelimit,
planner::Planner::Result result = nullptr 
)

Plan to a trajectory that moves the end-effector by a given direction and distance.

Parameters
[in]stateSpaceMetaSkeleton state space.
[in]metaskeletonMetaSkeleton to plan with
[in]bnBody node of the end-effector.
[in]constraintTrajectory-wide constraint that must be satisfied.
[in]directionDirection of moving the end-effector.
[in]minDistanceDistance of moving the end-effector.
[in]maxDistanceMax distance of moving the end-effector.
[in]positionToleranceHow a planned trajectory is allowed to deviated from a straight line segment defined by the direction and the distance.
[in]angularToleranceHow a planned trajectory is allowed to deviate from a given direction.
[in]initialStepSizeInitial step size.
[in]jointLimitToleranceIf less then this distance to joint limit, velocity is bounded in that direction to 0.
[in]constraintCheckResolutionResolution used in constraint checking.
[in]timelimittimeout in seconds.
[out]resultinformation about success or failure.
Returns
Trajectory or nullptr if planning failed.

◆ planToEndEffectorPose()

aikido::trajectory::UniqueInterpolatedPtr aikido::planner::vectorfield::planToEndEffectorPose ( const aikido::statespace::dart::MetaSkeletonStateSpacePtr stateSpace,
::dart::dynamics::MetaSkeletonPtr  metaskeleton,
const ::dart::dynamics::BodyNodePtr &  bn,
const aikido::constraint::TestablePtr constraint,
const Eigen::Isometry3d &  goalPose,
double  poseErrorTolerance,
double  conversionRatioInGeodesicDistance,
double  initialStepSize,
double  jointLimitTolerance,
double  constraintCheckResolution,
std::chrono::duration< double >  timelimit,
planner::Planner::Result result = nullptr 
)

Plan to an end-effector pose by following a geodesic loss function in SE(3) via an optimized Jacobian.

Parameters
[in]stateSpaceMetaSkeleton state space.
[in]metaskeletonMetaSkeleton to plan with
[in]bnBody node of the end-effector.
[in]constraintTrajectory-wide constraint that must be satisfied.
[in]goalPoseDesired end-effector pose.
[in]poseErrorToleranceHow a planned trajectory is allowed to deviated from a straight line segment defined by the direction and the distance.
[in]conversionRatioInGeodesicDistanceConversion ratio from radius to meter in computing geodesic distance.
[in]initialStepSizeInitial step size.
[in]jointLimitToleranceIf less then this distance to joint limit, velocity is bounded in that direction to 0.
[in]constraintCheckResolutionResolution used in constraint checking.
[in]timelimitTimeout in seconds.
[out]resultinformation about success or failure.
Returns
Trajectory or nullptr if planning failed.