|
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. More...
|
|
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. More...
|
|
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. More...
|
|