Aikido
|
Classes | |
struct | CRRTPlannerParameters |
struct | PlanToTSRParameters |
struct | VectorFieldPlannerParameters |
Paramters for Vector Field Planner. More... | |
Functions | |
std::unordered_map< std::string, const Eigen::VectorXd > | parseYAMLToNamedConfigurations (const YAML::Node &node) |
Parses YAML node for named configurtaions. More... | |
bool | 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 | getLookAtIsometry (const Eigen::Vector3d &positionFrom, const Eigen::Vector3d &positionTo) |
Get a pose at a point looking at another point. More... | |
const dart::dynamics::BodyNode * | 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 * | 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... | |
std::set< std::string > | dofNamesFromSkeleton (const dart::dynamics::MetaSkeletonPtr &skeleton) |
Get a set of degree-of-freedom names from MetaSkeleton. More... | |
Variables | |
const std::vector< double > | defaultVFParams |
Default Vector Field Planner Parameters Suitable for ADA-robot end-effector movements. More... | |
|
inline |
Get a set of degree-of-freedom names from MetaSkeleton.
[in] | skeleton | MetaSkeleton pointer |
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.
[in] | skeleton | MetaSkeleton that should contain the BodyNode |
[in] | bodyNodeName | Name of the BodyNode we are looking for |
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.
[in] | skeleton | MetaSkeleton that should contain the BodyNode |
[in] | bodyNodeName | Name of the BodyNode we are looking for |
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.
[in] | bodyNode | End-effector body node |
[in] | direction | End-effector direction |
[in] | distance | Offset to move |
[out] | goal | Goal TSR |
[out] | constraint | Constraint TSR |
[in] | positionTolerance | Tolerance in position, used in TSR |
[in] | angularTolerance | Tolerance in angle, used in TSR |
Eigen::Isometry3d aikido::robot::util::getLookAtIsometry | ( | const Eigen::Vector3d & | positionFrom, |
const Eigen::Vector3d & | positionTo | ||
) |
Get a pose at a point looking at another point.
[in] | positionFrom | Position to look from |
[in] | positionTo | Position to look to |
std::unordered_map<std::string, const Eigen::VectorXd> aikido::robot::util::parseYAMLToNamedConfigurations | ( | const YAML::Node & | node | ) |
const std::vector<double> aikido::robot::util::defaultVFParams |
Default Vector Field Planner Parameters Suitable for ADA-robot end-effector movements.