|
trajectory::TrajectoryPtr | aikido::robot::util::planToConfiguration (const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const statespace::StateSpace::State *goalState, const constraint::TestablePtr &collisionTestable, common::RNG *rng, double timelimit) |
| Plan the robot to a specific configuration. More...
|
|
trajectory::TrajectoryPtr | aikido::robot::util::planToConfigurations (const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const std::vector< statespace::StateSpace::State * > &goalStates, const constraint::TestablePtr &collisionTestable, common::RNG *rng, double timelimit) |
| Plan the robot to a set of configurations. More...
|
|
trajectory::TrajectoryPtr | aikido::robot::util::planToTSR (const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const dart::dynamics::BodyNodePtr &bodyNode, const constraint::dart::TSRPtr &tsr, const constraint::TestablePtr &collisionTestable, common::RNG *rng, double timelimit, std::size_t maxNumTrials, const distance::ConstConfigurationRankerPtr &ranker=nullptr) |
| Plan the configuration of the metakeleton such that the specified bodynode is set to a sample in TSR. More...
|
|
trajectory::InterpolatedPtr | aikido::robot::util::planToTSRwithTrajectoryConstraint (const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const dart::dynamics::BodyNodePtr &bodyNode, const constraint::dart::TSRPtr &goalTsr, const constraint::dart::TSRPtr &constraintTsr, const constraint::TestablePtr &collisionTestable, double timelimit, const CRRTPlannerParameters &crrtParameters=CRRTPlannerParameters()) |
| Returns a Trajectory that moves the configuration of the metakeleton such that the specified bodynode is set to a sample in a goal TSR and the trajectory is constrained to a constraint TSR Uses CRRTPlanner. More...
|
|
trajectory::TrajectoryPtr | aikido::robot::util::planToEndEffectorOffset (const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const dart::dynamics::BodyNodePtr &body, const Eigen::Vector3d &direction, const constraint::TestablePtr &collisionTestable, double distance, double timelimit, double positionTolerance=1e-3, double angularTolerance=1e-3, const VectorFieldPlannerParameters &vfParameters=VectorFieldPlannerParameters(), const CRRTPlannerParameters &crrtParameters=CRRTPlannerParameters()) |
| Plan to a desired end-effector offset with fixed orientation. More...
|
|
trajectory::InterpolatedPtr | aikido::robot::util::planToEndEffectorOffsetByCRRT (const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const dart::dynamics::BodyNodePtr &bodyNode, const constraint::TestablePtr &collisionTestable, const Eigen::Vector3d &direction, double distance, double timelimit, double positionTolerance=1e-3, double angularTolerance=1e-3, const CRRTPlannerParameters &crrtParameters=CRRTPlannerParameters()) |
| Plan to a desired end-effector offset with fixed orientation using CRRT. More...
|
|
std::unordered_map< std::string, const Eigen::VectorXd > | aikido::robot::util::parseYAMLToNamedConfigurations (const YAML::Node &node) |
| Parses YAML node for named configurtaions. More...
|
|
bool | aikido::robot::util::getGoalAndConstraintTSRForEndEffectorOffset (const dart::dynamics::BodyNodePtr &bodyNode, const Eigen::Vector3d &direction, double distance, const constraint::dart::TSRPtr &goal, const constraint::dart::TSRPtr &constraint, double positionTolerance=1e-3, double angularTolerance=1e-3) |
| Gets Goal and Constraint TSR for end-effector. More...
|
|
Eigen::Isometry3d | aikido::robot::util::getLookAtIsometry (const Eigen::Vector3d &positionFrom, const Eigen::Vector3d &positionTo) |
| Get a pose at a point looking at another point. More...
|
|
const dart::dynamics::BodyNode * | aikido::robot::util::getBodyNodeOrThrow (const dart::dynamics::MetaSkeleton &skeleton, const std::string &bodyNodeName) |
| Get a specific BodyNode of a MetaSkeleton or throw an execption if it doesn't exist. More...
|
|
dart::dynamics::BodyNode * | aikido::robot::util::getBodyNodeOrThrow (dart::dynamics::MetaSkeleton &skeleton, const std::string &bodyNodeName) |
| Get a specific BodyNode of a MetaSkeleton or throw an execption if it doesn't exist. More...
|
|