Aikido
aikido::robot::util Namespace Reference

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

Function Documentation

◆ dofNamesFromSkeleton()

std::set<std::string> aikido::robot::util::dofNamesFromSkeleton ( const dart::dynamics::MetaSkeletonPtr &  skeleton)
inline

Get a set of degree-of-freedom names from MetaSkeleton.

Parameters
[in]skeletonMetaSkeleton pointer
Returns
A set of DoFs with skeleton->getNumDofs() elements

◆ getBodyNodeOrThrow() [1/2]

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.

Parameters
[in]skeletonMetaSkeleton that should contain the BodyNode
[in]bodyNodeNameName of the BodyNode we are looking for
Returns
The BodyNode

◆ getBodyNodeOrThrow() [2/2]

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.

Parameters
[in]skeletonMetaSkeleton that should contain the BodyNode
[in]bodyNodeNameName of the BodyNode we are looking for
Returns
The BodyNode

◆ getGoalAndConstraintTSRForEndEffectorOffset()

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.

Parameters
[in]bodyNodeEnd-effector body node
[in]directionEnd-effector direction
[in]distanceOffset to move
[out]goalGoal TSR
[out]constraintConstraint TSR
[in]positionToleranceTolerance in position, used in TSR
[in]angularToleranceTolerance in angle, used in TSR
Returns
True if all outputs are successfully made.

◆ getLookAtIsometry()

Eigen::Isometry3d aikido::robot::util::getLookAtIsometry ( const Eigen::Vector3d &  positionFrom,
const Eigen::Vector3d &  positionTo 
)

Get a pose at a point looking at another point.

Parameters
[in]positionFromPosition to look from
[in]positionToPosition to look to
Returns
Pose at positionFrom, looking at positionTo.

◆ parseYAMLToNamedConfigurations()

std::unordered_map<std::string, const Eigen::VectorXd> aikido::robot::util::parseYAMLToNamedConfigurations ( const YAML::Node &  node)

Parses YAML node for named configurtaions.

Parameters
[in]nodeYAML node containing named configurations
Returns
Unordered map of (name, configuration) pairs.

Variable Documentation

◆ defaultVFParams

const std::vector<double> aikido::robot::util::defaultVFParams
Initial value:
{
0.03,
0.004,
0.01,
0.01,
1e-3,
1e-3,
1.5,
0.01,
1.0
}

Default Vector Field Planner Parameters Suitable for ADA-robot end-effector movements.