| 
    Aikido
    
   | 
 
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... | |
| class | VectorFieldConfigurationToEndEffectorPosePlanner | 
| Planner that generates a trajectory that moves the end-effector to a given pose.  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::ConstMetaSkeletonStateSpacePtr &stateSpace, const statespace::dart::MetaSkeletonStateSpace::State &startState, ::dart::dynamics::MetaSkeletonPtr metaskeleton, const ::dart::dynamics::ConstBodyNodePtr &bn, const aikido::constraint::ConstTestablePtr &constraint, const Eigen::Isometry3d &goalPose, double goalTolerance, double conversionRatioInGeodesicDistance, double positionTolerance, double angularTolerance, 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... | |
| using aikido::planner::vectorfield::BodyNodePoseVectorFieldPtr = typedef std::shared_ptr< BodyNodePoseVectorField > | 
| using aikido::planner::vectorfield::ConstBodyNodePoseVectorFieldPtr = typedef std::shared_ptr< const BodyNodePoseVectorField > | 
| using aikido::planner::vectorfield::UniqueBodyNodePoseVectorFieldPtr = typedef std::unique_ptr< BodyNodePoseVectorField > | 
| using aikido::planner::vectorfield::UniqueConstBodyNodePoseVectorFieldPtr = typedef std::unique_ptr< const BodyNodePoseVectorField > | 
| using aikido::planner::vectorfield::VectorFieldPtr = typedef std::shared_ptr<VectorField> | 
| using aikido::planner::vectorfield::WeakBodyNodePoseVectorFieldPtr = typedef std::weak_ptr< BodyNodePoseVectorField > | 
| using aikido::planner::vectorfield::WeakConstBodyNodePoseVectorFieldPtr = typedef std::weak_ptr< const BodyNodePoseVectorField > | 
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 | |
| 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 )
| [in] | fromTrans | Current transformation. | 
| [in] | toTrans | Goal transformation. | 
| [in] | r | In units of meters/radians converts radians to meters. | 
| Eigen::Vector4d aikido::planner::vectorfield::computeGeodesicError | ( | const Eigen::Isometry3d & | fromTrans, | 
| const Eigen::Isometry3d & | toTrans | ||
| ) | 
Compute the error in gloabl coordinate between two transforms.
| [in] | fromTrans | Current transformation. | 
| [in] | toTrans | Goal transformation. | 
| 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.
| [in] | fromTrans | Current transformation. | 
| [in] | toTrans | Goal transformation. | 
| 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.
| [out] | jointVelocity | Calculated joint velocities. | 
| [in] | desiredTwist | Desired twist, which consists of angular velocity and linear velocity. | 
| [in] | metaSkeleton | MetaSkeleton to plan with | 
| [in] | bodyNode | Body node of the end-effector. | 
| [in] | jointLimitPadding | If less then this distance to joint limit, velocity is bounded in that direction to 0. | 
| [in] | jointVelocityLowerLimits | Joint velocity lower bounds. | 
| [in] | jointVelocityUpperLimits | Joint velocity upper bounds. | 
| [in] | enforceJointVelocityLimits | Whether joint velocity limits are considered in computation. | 
| [in] | stepSize | Step 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. | 
| 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.
| [in] | vectorField | Vector field to follow. | 
| [in] | startState | Start state of the planning. | 
| [in] | constraint | Constraint to be satisfied. | 
| [in] | timelimit | Timelimit for integration calculation. | 
| [in] | initialStepSize | Initial step size of integator in following vector field. | 
| [in] | checkConstraintResolution | Resolution used in checking constraint satisfaction in generated trajectory. | 
| [out] | result | information about success or failure. | 
| 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.
| [in] | stateSpace | MetaSkeleton state space. | 
| [in] | metaskeleton | MetaSkeleton to plan with | 
| [in] | bn | Body node of the end-effector. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| [in] | direction | Direction of moving the end-effector. | 
| [in] | minDistance | Distance of moving the end-effector. | 
| [in] | maxDistance | Max distance of moving the end-effector. | 
| [in] | positionTolerance | How a planned trajectory is allowed to deviated from a straight line segment defined by the direction and the distance. | 
| [in] | angularTolerance | How a planned trajectory is allowed to deviate from a given direction. | 
| [in] | initialStepSize | Initial step size. | 
| [in] | jointLimitTolerance | If less then this distance to joint limit, velocity is bounded in that direction to 0. | 
| [in] | constraintCheckResolution | Resolution used in constraint checking. | 
| [in] | timelimit | timeout in seconds. | 
| [out] | result | information about success or failure. | 
nullptr if planning failed. | aikido::trajectory::UniqueInterpolatedPtr aikido::planner::vectorfield::planToEndEffectorPose | ( | 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::Isometry3d & | goalPose, | ||
| double | goalTolerance, | ||
| double | conversionRatioInGeodesicDistance, | ||
| double | positionTolerance, | ||
| double | angularTolerance, | ||
| 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.
| [in] | stateSpace | MetaSkeleton state space. | 
| [in] | metaskeleton | MetaSkeleton to plan with | 
| [in] | bn | Body node of the end-effector. | 
| [in] | constraint | Trajectory-wide constraint that must be satisfied. | 
| [in] | goalPose | Desired end-effector pose. | 
| [in] | goalTolerance | Geodesic distance from goal to stop planning | 
| [in] | conversionRatioInGeodesicDistance | Conversion ratio from radian to meter in computing geodesic distance | 
| [in] | positionTolerance | How a planned trajectory is allowed to deviate from a straight line segment. | 
| [in] | angularTolerance | How a planned trajectory is allowed to deviate from a straight rotation. | 
| [in] | initialStepSize | Initial step size. | 
| [in] | jointLimitTolerance | If less then this distance to joint limit, velocity is bounded in that direction to 0. | 
| [in] | constraintCheckResolution | Resolution used in constraint checking. | 
| [in] | timelimit | Timeout in seconds. | 
| [out] | result | Information about success or failure. | 
nullptr if plannin failed.