Klamp't  0.8.1
Public Member Functions | Public Attributes | List of all members
Hold Struct Reference

A single contact between the robot and the environment. More...

#include <Hold.h>

Public Member Functions

void Transform (const RigidTransform &T)
 Transforms the hold by T.
 
void GetCentroid (Vector3 &c) const
 Returns the centroid of the contacts.
 
void GetNormal (Vector3 &n) const
 
Vector3 GetCentroid () const
 Same as above.
 
Vector3 GetNormal () const
 
void SetupIKConstraint (const Vector3 &localPos0, const Vector3 &rot)
 
void SetupFixedIKConstraint (const Vector3 &localPos0, const Matrix3 &rot)
 
void SetupPointIKConstraint (const Vector3 &localPos0)
 
void SetupAxisIKConstraint (const Vector3 &localPos0, const Vector3 &axis, const Vector3 &axis_w)
 

Public Attributes

int link
 
vector< ContactPoint > contacts
 
IKGoal ikConstraint
 

Detailed Description

A single contact between the robot and the environment.

Consists of one or more contact points, along with the relative position of the robot link with the environment. Can be considered a "finalized" version of a ContactFeatureMapping, where the actual contact interface has been determined.

See also
ContactPoint
ContactFeatureMapping

Member Function Documentation

void Hold::SetupAxisIKConstraint ( const Vector3 &  localPos0,
const Vector3 &  axis,
const Vector3 &  axis_w 
)

Given the current set of contact points, the IK constraint is defined by matching the local position of the 0'th contact point and the local axis to the world axis (axis_w is usually parallel to (contacts[1].x-contacts[0].x)

Parameters
localPos0The local position of the 0'th contact point
axisThe local rotation axis
axis_wThe world rotation axis
void Hold::SetupFixedIKConstraint ( const Vector3 &  localPos0,
const Matrix3 &  rot 
)

Given the current set of contact points, the IK constraint is defined by the local position of the 0'th contact point and the local-to-world rotation of the constrained link.

Parameters
localPos0The local position of the 0'th contact point
rotThe link's fixed rotation
void Hold::SetupIKConstraint ( const Vector3 &  localPos0,
const Vector3 &  rot 
)

Given the current set of contact points, the IK constraint is defined by the local position of the 0'th contact point and the local-to-world rotation of the constrained link. If 1 contact point, it's a free rotation about that point 2, it's a constrained rotation around that axis 3 or more, both position/rotation are constrained.

Parameters
localPos0The local position of the 0'th contact point
rotA moment rotation $e^{[rot]}$ that represents the link's desired rotation. Ignored if there is only 1 contact point.
void Hold::SetupPointIKConstraint ( const Vector3 &  localPos0)

Given the current set of contact points, the IK constraint is defined by matching the local position of the 0'th contact point.

Parameters
localPos0The local position of the 0'th contact point

The documentation for this struct was generated from the following file: