Contact Class Reference

A contact between 2 bodies. More...

#include <contact.h>

Inheritance diagram for Contact:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void computeWrenches ()
 Converts pure friction edges into full contact wrenches by considering normal force.
 Contact (Body *b1, Body *b2, position pos, vec3 norm)
 Constructs a contact between two bodies.
 Contact ()
 Initializes an empty contact (not really used).
Matrix frictionConstraintsMatrix () const
 Returns a matrix for friction constraints at this contact that can be used in an LCP.
Matrix frictionForceMatrix () const
 Returns the matrix that relates friction edge amplitudes to normal and frictional force.
BodygetBody1 () const
transf getBody1Tran () const
BodygetBody2 () const
transf getBody2Tran () const
double getCof () const
 Gets the coefficient of friction for this contact.
double getConstraintError ()
 The error that shows that this contact constraints are violated during dynamic simulation.
int getContactDim () const
SoSeparator * getContactForcePointers () const
transf getContactFrame () const
double * getDynamicContactWrench ()
transf getFrame () const
 Gets the frame.
frictionT getFrictionType () const
int getLmiDim () const
position getLocation () const
 Gets the location.
ContactgetMate () const
vec3 getNormal ()
double getNormalForceLimit () const
position getPosition ()
double * getPrevBetas ()
 Get dynamic sovler LCP information from the previous time step.
double getPrevCn ()
 Get dynamic sovler LCP information from the previous time step.
double getPrevLambda ()
 Get dynamic sovler LCP information from the previous time step.
virtual SoSeparator * getVisualIndicator ()
 Returns the IV root of the visual markers that shows the location of this contact.
void inherit (Contact *c)
bool inherits ()
 Tells us if this contact has inherited some information from previous time step.
bool isSlipping () const
 Returns the slip flag which does not work very well.
Matrix localToWorldWrenchMatrix () const
 Returns the matrix that transforms a force on this contact into a wrench on the other body.
bool preventsMotion (const transf &motion) const
void setContactForce (double *optmx)
 Called by GFO routine to set optimal contact force.
void setDynamicContactForce (const vec3 &force)
void setDynamicContactWrench (double f[6])
void setLCPInfo (double cn, double l, double *betas)
 Set dynamic sovler LCP information which might be used at the next time step.
void setMate (Contact *m)
void setNormalForceLimit (double nfl)
virtual int setUpFrictionEdges (bool dynamicsOn=false)=0
 Main function for defining the space of friction that can be applied at this contact.
void updateCof ()
 Updates the coefficient of friction (called when the body materials have changed).
virtual ~Contact ()
 Destructor.

Static Public Member Functions

static Matrix frictionConstraintsBlockMatrix (const std::list< Contact * > &contacts)
 Returns a block matrix composed of individual constraint matrices for the contacts in the list.
static Matrix frictionForceBlockMatrix (const std::list< Contact * > &contacts)
 Returns a block matrix made up of individual force matrices from the contacts in the list.
static Matrix localToWorldWrenchBlockMatrix (const std::list< Contact * > &contacts)
 Returns a block matrix made up of individual force to world wrench conversion matrices.
static Matrix normalForceSumMatrix (const std::list< Contact * > &contacts)
 Returns a matrix that adds just the normal force components of an amplitudes vector.

Public Attributes

float coneB
float coneG
SoMaterial * coneMat
 A debug tool to see that contact inheritance works right.
float coneR
 A debug tool to see that contact inheritance works right.
double frictionEdges [6 *MAX_FRICTION_EDGES]
 6 x numFrictionEdges matrix of friction cone boundary wrenches used in dynmaics
int numFCWrenches
 Number of total friction wrenches.
int numFrictionEdges
 number of friction edges defining the frictional component of contact wrenches
Wrenchwrench
 Array of wrenches bounding the Contact Wrench Space (CWS).

Static Public Attributes

static const double INHERITANCE_ANGULAR_THRESHOLD = 0.984
 Maximum angular distance for which two contacts at consecutive time steps are considered to be the same contact.
static const double INHERITANCE_THRESHOLD = 1
 Maximum linear distance for which two contacts at consecutive time steps are considered to be the same contact.
static const double THRESHOLD = 0.1
 Maximum separation distance (in mm) between two bodies that are considered to be in contact.

Protected Member Functions

int setUpFrictionEllipsoid (int numLatitudes, int numDirs[], double phi[], double eccen[])
 Sets up frictional forces at this contact using a linearized ellipsoid.
void wrenchFromFrictionEdge (double *edge, const vec3 &radius, Wrench *wr)
 computes a single contact wrench from a friction edge

Protected Attributes

Bodybody1
 Pointer to the body this contact is on.
transf body1Tran
 Pose of body 1 in world space at time of contact.
Bodybody2
 Pointer to the other body involved in this contact.
transf body2Tran
 Pose of body 2 in world space at time of contact.
double cof
 Coefficient of static friction.
int contactDim
 Contact dimension (num basisvecs): 1 for FL, 3 for PCWF, 4 for SFCE, 4 for SFCL.
SoSeparator * contactForcePointers
 Root Inventor node stores arrow geometry representing current contact force.
double dynamicForce [6]
 The current dynamic force acting at this contact.
transf frame
 Pose of the contact frame with respect to the body1 frame.
frictionT frictionType
 The type of friction model at this contact.
bool inheritanceInfo
 Tells us wether this contact has inherited some information from the previous dynamic time step.
double kcof
 Coefficient of kinetic friction.
int lmiDim
 LMI dimension: 1 for FL, 3 for PCWF, 4 for SFCE, 7 for SFCL.
position loc
 Coordinates of the contact with respect to body 1 base frame.
Contactmate
 Points to the other contact in this pair.
bool mSlip
 Based on LCP solution, this flag shows if the contact is slipping or not. Does not work well.
vec3 normal
 Contact normal with respect to body 1 base frame.
double normalForceLimit
 The maximum normal force for this contact point due to hand torque limits.
double * optimalCoeffs
 A contactDim vector containing the optimal values to multiply with basisVecs. This will produce the contact forces necessary to generate the needed object wrench.
double * prevBetas
 Dynamics LCP information from the previous time step;.
double prevCn
 Dynamics LCP information from the previous time step;.
double prevLambda
 Dynamics LCP information from the previous time step;.

Friends

class VirtualContact

Detailed Description

A contact between 2 bodies.

Contacts always come in pairs. When two bodies touch, a contact is defined for each of them. They have the same (or very close to the same) global positions, opposite inward pointing normals, and share the same coefficients of friction. Any instance of this class will have as mate its reciprocal contact on the other body.

A contact is defined in places where two bodies are separated by less then the contact threshold (usually set to 0.1 mm). In GraspIt, two bodies are NEVER allowed to interpenetrate; they are considered in contact if they are apart, but separated by less than the threshold.

We always define contacts to occur precisely at a point (as opposed to a small area). This makes computations much easier, as we don't have to compute deformations. The Grasp class will however consider the case of objects that match geometry so that many point contacts can occur on the same patch. For soft bodies, we have the SoftContact class which inherits from this one and tries to approximate the frictional effects of having a contact patch (while not computing such a patch explicitly).

Contacts also define their own linearized friction models. This means that, for each contact, friction is constrained to lie within some convex polyhedron. The edges that define this polyhedron are different for different types of contacts, which inherit from this class. However, once the edges of the friction polyhedron are defined, all contact behave identically.

You will also find here code for two projects which are not used right now. The first one if Grasp Force Optimization (GFO). See the grasp class for that code; it is finished but has never been tested. Also, the GFO code has never been updated to work with the new Contact hierarchy of PointContact, SoftContact etc, and uses a parallel mechanism to keep track of friction models. The second one concerns the dynamics engine: in theory, we can try to save contact information from a time step to help the solver during the next time step. The framework is in place, but we have never used it.

Definition at line 95 of file contact.h.


Constructor & Destructor Documentation

Contact::Contact (  )  [inline]

Initializes an empty contact (not really used).

Definition at line 194 of file contact.h.

Contact::Contact ( Body b1,
Body b2,
position  pos,
vec3  norm 
)

Constructs a contact between two bodies.

Initializes a new contact on body b1. The other contacting body is b2. The contact position pos and the contact normal norm are expressed in local body b1 coordinates.

Definition at line 67 of file contact.cpp.

Contact::~Contact (  )  [virtual]

Destructor.

Deletes contact basis vectors, optimal force coefficients, and friction cone boundary wrenches. If the contact has an undeleted mate, it removes the mate's connection to this contact, and removes the mate contact from the other body (thus deleting it).

Definition at line 102 of file contact.cpp.


Member Function Documentation

void Contact::computeWrenches (  )  [virtual]

Converts pure friction edges into full contact wrenches by considering normal force.

Takes the information about pure friction at this contact, contained in the frictionEdges, and adds normal force and the effect of coeff of friction to obtain actual wrenches that can be applied at this contact. Essentially builds the Contact Wrench Space based on the friction information and (normalized) contact forces. See wrenchFromFrictionEdge for details.

Reimplemented in SoftContact.

Definition at line 150 of file contact.cpp.

Matrix Contact::frictionConstraintsBlockMatrix ( const std::list< Contact * > &  contacts  )  [static]

Returns a block matrix composed of individual constraint matrices for the contacts in the list.

Creates the friction constraint matrices of all contacts in the list using Contact::frictionConstraintMatrix(), then assembles all the matrices in block diagonal form.

Definition at line 283 of file contact.cpp.

Matrix Contact::frictionConstraintsMatrix (  )  const

Returns a matrix for friction constraints at this contact that can be used in an LCP.

Assembles a friction constraint matrix for this contact that can be used in an LCP. This matrix is of the form [-mu 1 1 ... 1] with a 1 for each friction edge. This is used in a constraint as F * beta <= 0, saying that the sum of friction edge amplitudes (thus friction force) must be less than normal force times friction coefficient.

Definition at line 224 of file contact.cpp.

Matrix Contact::frictionForceBlockMatrix ( const std::list< Contact * > &  contacts  )  [static]

Returns a block matrix made up of individual force matrices from the contacts in the list.

Creates the individual force matrices for all contacts in the list using frictionConstraintMatrix() then assembles them in block diagonal form.

Definition at line 260 of file contact.cpp.

Matrix Contact::frictionForceMatrix (  )  const

Returns the matrix that relates friction edge amplitudes to normal and frictional force.

Returns the matric that relates friction edge amplitudes to friction force. That matrix is of the form [n D] where n is the contact normal and D has as columns the friction edges. The computations are done in local contact coordinate system (contact normal along the z axis).

Definition at line 238 of file contact.cpp.

Body* Contact::getBody1 (  )  const [inline]

Returns a pointer to body this contact is on.

Definition at line 222 of file contact.h.

transf Contact::getBody1Tran (  )  const [inline]

Returns the pose of body1 when this contact was formed.

Definition at line 228 of file contact.h.

Body* Contact::getBody2 (  )  const [inline]

Returns a pointer to the other body invovled in this contact.

Definition at line 225 of file contact.h.

transf Contact::getBody2Tran (  )  const [inline]

Returns the pose of body2 when this contact was formed.

Definition at line 231 of file contact.h.

double Contact::getCof (  )  const

Gets the coefficient of friction for this contact.

Returns the correct coefficient of friction for this contact. If either body is dynamic, and the relative velocity between them is greater than 1.0 mm/sec (should be made a parameter), then it returns the kinetic COF, otherwise it returns the static COF.

Definition at line 418 of file contact.cpp.

double Contact::getConstraintError (  ) 

The error that shows that this contact constraints are violated during dynamic simulation.

Each body has a thin layer around it that is Contact::THRESHOLD mm thick, and when another body is within that layer, the two bodies are in contact. During dynamic simulation, contacts provide constraints to prevent the two bodies from interpenetrating. However, the constraint is a velocity constraint not a position one, so errors in position due to numerical issues can occur. If the two bodies get closer than half the contact threshold, we correct this specifying a constraint error in the dynamics, which will serve to move the bodies apart. This routine returns the distance that two bodies have violated that halfway constraint.

Definition at line 469 of file contact.cpp.

int Contact::getContactDim (  )  const [inline]

Returns the contact dimension (number of basis wrenches).

Definition at line 264 of file contact.h.

SoSeparator* Contact::getContactForcePointers (  )  const [inline]

Returns the Inventor root of the pointer geometry for this contact

Definition at line 255 of file contact.h.

transf Contact::getContactFrame (  )  const [inline]

Returns pose of the contact frame relative to the base frame of body1.

Definition at line 249 of file contact.h.

double* Contact::getDynamicContactWrench (  )  [inline]

Returns the current dynamic force acting at this contact.

Definition at line 252 of file contact.h.

transf Contact::getFrame (  )  const [inline]

Gets the frame.

Definition at line 240 of file contact.h.

frictionT Contact::getFrictionType (  )  const [inline]

Returns the type of friction modeled at this contact.

Definition at line 246 of file contact.h.

int Contact::getLmiDim (  )  const [inline]

Returns the dimension of the LMI block for this contact. (used in GFO)

Definition at line 267 of file contact.h.

position Contact::getLocation (  )  const [inline]

Gets the location.

Definition at line 237 of file contact.h.

Contact* Contact::getMate (  )  const [inline]

Returns a pointer to the other half of this contact pair.

Definition at line 219 of file contact.h.

vec3 Contact::getNormal (  )  [inline]

Return contact normal wrt Body1 frame.

Definition at line 216 of file contact.h.

double Contact::getNormalForceLimit (  )  const [inline]

Returns the maximum normal force due to torque limits in the hand computed by GFO.

Definition at line 273 of file contact.h.

position Contact::getPosition (  )  [inline]

Returns contact position wrt Body1 frame.

Definition at line 213 of file contact.h.

double* Contact::getPrevBetas (  )  [inline]

Get dynamic sovler LCP information from the previous time step.

Definition at line 330 of file contact.h.

double Contact::getPrevCn (  )  [inline]

Get dynamic sovler LCP information from the previous time step.

Definition at line 326 of file contact.h.

double Contact::getPrevLambda (  )  [inline]

Get dynamic sovler LCP information from the previous time step.

Definition at line 328 of file contact.h.

virtual SoSeparator* Contact::getVisualIndicator (  )  [inline, virtual]

Returns the IV root of the visual markers that shows the location of this contact.

Reimplemented in PointContact, SoftContact, and VirtualContact.

Definition at line 323 of file contact.h.

void Contact::inherit ( Contact c  ) 

This contact inherits some properties from a contact from a previous dynamic time step.

Attempts to save some information from a previously computed dynamics time step. The contact c is from the previous time step, but has been determined to be close enough to this one that it is probably the same contact, having slightly evolved over a time step.

Definition at line 482 of file contact.cpp.

bool Contact::inherits (  )  [inline]

Tells us if this contact has inherited some information from previous time step.

Definition at line 338 of file contact.h.

bool Contact::isSlipping (  )  const [inline]

Returns the slip flag which does not work very well.

Definition at line 335 of file contact.h.

Matrix Contact::localToWorldWrenchBlockMatrix ( const std::list< Contact * > &  contacts  )  [static]

Returns a block matrix made up of individual force to world wrench conversion matrices.

Assembles together the localToWorldWrenchMatrix for all the contacts in the list in block diagonal form.

Definition at line 367 of file contact.cpp.

Matrix Contact::localToWorldWrenchMatrix (  )  const

Returns the matrix that transforms a force on this contact into a wrench on the other body.

The matrix, when multiplied with a wrench applied at this contact will give the resultant wrench applied on the other body in contact (thus computed relative to that object's center of mass), expressed in world coordinates.

The matrix looks like this: | R 0 | |CR R | Where R is the 3x3 rotation matrix between the coordinate systems and C also contains the cross product matrix that depends on the translation between them.

Definition at line 337 of file contact.cpp.

Matrix Contact::normalForceSumMatrix ( const std::list< Contact * > &  contacts  )  [static]

Returns a matrix that adds just the normal force components of an amplitudes vector.

Creates a line vector that, when multiplied by a vector of contact wrench amplitudes returns the sum of the normal components. Therefore, it has 1 in the positions corresponding to normal force amplitudes and 0 in the positions corresponding to friction wrench amplitudes.

Definition at line 307 of file contact.cpp.

bool Contact::preventsMotion ( const transf motion  )  const

Determines whether this contact will prevent motion of body 1 as expressed in local body 1 coordinates

First computes the new location of the contact point using the motion transform (expressed with respect to the body coordinate frame). If the dot product of the contact point motion vector and the contact normal is less than zero, then the contact prevents this motion.

Definition at line 391 of file contact.cpp.

void Contact::setContactForce ( double *  optmx  ) 

Called by GFO routine to set optimal contact force.

When the grasp force optimization completes it calls this routine to set this contact's optimal force. This force is a compromise between minimizing internal grasp forces and how close the force is to the boundary of the friction cone, or starting to slip.

Definition at line 451 of file contact.cpp.

void Contact::setDynamicContactForce ( const vec3 force  )  [inline]

Sets just the force part of a dynamic wrench using a vec3

Definition at line 302 of file contact.h.

void Contact::setDynamicContactWrench ( double  f[6]  )  [inline]

Sets the dynamic force acting at this contact during the current time step. Used when drawing contact forces.

Definition at line 298 of file contact.h.

void Contact::setLCPInfo ( double  cn,
double  l,
double *  betas 
)

Set dynamic sovler LCP information which might be used at the next time step.

Definition at line 500 of file contact.cpp.

void Contact::setMate ( Contact m  )  [inline]

Connects the mate contact to this one

Definition at line 210 of file contact.h.

void Contact::setNormalForceLimit ( double  nfl  )  [inline]

Sets the normal force limit based on hand torque limits as computed during GFO.

Definition at line 270 of file contact.h.

virtual int Contact::setUpFrictionEdges ( bool  dynamicsOn = false  )  [pure virtual]

Main function for defining the space of friction that can be applied at this contact.

Implemented in PointContact, SoftContact, and VirtualContact.

int Contact::setUpFrictionEllipsoid ( int  numLatitudes,
int  numDirs[],
double  phi[],
double  eccen[] 
) [protected]

Sets up frictional forces at this contact using a linearized ellipsoid.

Sets up the friction edges of this contact using an ellipsoid approximation. This is convenience function, as friction edges can be set in many ways. However, we currently use PCWF and SFC models which are both cases of linearized ellipsoids, so this function can be used for both.

Consider a 3D friction ellipsoid, where the first two dimensions are tangential frictional force (along X and Y) and the third is frictional torque (along Z). This function samples this ellipsoid at numLatitudes latitudes contained in phi[]; at each latitude l it takes numDirs[l] equally spaced discrete samples. Each of those samples becomes a friction edge, after it is converted to the full 6D space by filling in the other dimensions with zeroes.

Definition at line 181 of file contact.cpp.

void Contact::updateCof (  ) 

Updates the coefficient of friction (called when the body materials have changed).

Recomputes the COF for this contact. This is called when the material of one of the two bodies is changed.

Definition at line 403 of file contact.cpp.

void Contact::wrenchFromFrictionEdge ( double *  edge,
const vec3 radius,
Wrench wr 
) [protected]

computes a single contact wrench from a friction edge

Friction edges contain "normalised" friction information: just the frictional component, and without reference to normal force or coeff of friction (c.o.f.). They only care about the relationship between frictional components.

To get an actual wrench that can be applied at the contact, we must add normal force (normalised here to 1N) and take into account the relationship btw normal force and c.o.f.

Definition at line 124 of file contact.cpp.


Friends And Related Function Documentation

friend class VirtualContact [friend]

Definition at line 97 of file contact.h.


Member Data Documentation

Body* Contact::body1 [protected]

Pointer to the body this contact is on.

Definition at line 101 of file contact.h.

Pose of body 1 in world space at time of contact.

Definition at line 134 of file contact.h.

Body* Contact::body2 [protected]

Pointer to the other body involved in this contact.

Definition at line 104 of file contact.h.

Pose of body 2 in world space at time of contact.

Definition at line 137 of file contact.h.

double Contact::cof [protected]

Coefficient of static friction.

Definition at line 110 of file contact.h.

Definition at line 343 of file contact.h.

Definition at line 343 of file contact.h.

SoMaterial* Contact::coneMat

A debug tool to see that contact inheritance works right.

Definition at line 341 of file contact.h.

A debug tool to see that contact inheritance works right.

Definition at line 343 of file contact.h.

int Contact::contactDim [protected]

Contact dimension (num basisvecs): 1 for FL, 3 for PCWF, 4 for SFCE, 4 for SFCL.

Definition at line 119 of file contact.h.

SoSeparator* Contact::contactForcePointers [protected]

Root Inventor node stores arrow geometry representing current contact force.

Definition at line 140 of file contact.h.

double Contact::dynamicForce[6] [protected]

The current dynamic force acting at this contact.

Definition at line 149 of file contact.h.

transf Contact::frame [protected]

Pose of the contact frame with respect to the body1 frame.

Definition at line 131 of file contact.h.

double Contact::frictionEdges[6 *MAX_FRICTION_EDGES]

6 x numFrictionEdges matrix of friction cone boundary wrenches used in dynmaics

Friction edges contain "normalised" friction information: just the frictional component, and without reference to normal force or coeff of friction (c.o.f.). They only care about the relationship between frictional components.

Definition at line 177 of file contact.h.

The type of friction model at this contact.

Definition at line 116 of file contact.h.

const double Contact::INHERITANCE_ANGULAR_THRESHOLD = 0.984 [static]

Maximum angular distance for which two contacts at consecutive time steps are considered to be the same contact.

Definition at line 320 of file contact.h.

const double Contact::INHERITANCE_THRESHOLD = 1 [static]

Maximum linear distance for which two contacts at consecutive time steps are considered to be the same contact.

Definition at line 317 of file contact.h.

bool Contact::inheritanceInfo [protected]

Tells us wether this contact has inherited some information from the previous dynamic time step.

Definition at line 158 of file contact.h.

double Contact::kcof [protected]

Coefficient of kinetic friction.

Definition at line 113 of file contact.h.

int Contact::lmiDim [protected]

LMI dimension: 1 for FL, 3 for PCWF, 4 for SFCE, 7 for SFCL.

Definition at line 122 of file contact.h.

position Contact::loc [protected]

Coordinates of the contact with respect to body 1 base frame.

Definition at line 125 of file contact.h.

Contact* Contact::mate [protected]

Points to the other contact in this pair.

Definition at line 107 of file contact.h.

bool Contact::mSlip [protected]

Based on LCP solution, this flag shows if the contact is slipping or not. Does not work well.

Definition at line 161 of file contact.h.

vec3 Contact::normal [protected]

Contact normal with respect to body 1 base frame.

Definition at line 128 of file contact.h.

double Contact::normalForceLimit [protected]

The maximum normal force for this contact point due to hand torque limits.

Definition at line 143 of file contact.h.

Number of total friction wrenches.

Definition at line 191 of file contact.h.

number of friction edges defining the frictional component of contact wrenches

Definition at line 180 of file contact.h.

double* Contact::optimalCoeffs [protected]

A contactDim vector containing the optimal values to multiply with basisVecs. This will produce the contact forces necessary to generate the needed object wrench.

Definition at line 146 of file contact.h.

double* Contact::prevBetas [protected]

Dynamics LCP information from the previous time step;.

Definition at line 156 of file contact.h.

double Contact::prevCn [protected]

Dynamics LCP information from the previous time step;.

Definition at line 152 of file contact.h.

double Contact::prevLambda [protected]

Dynamics LCP information from the previous time step;.

Definition at line 154 of file contact.h.

const double Contact::THRESHOLD = 0.1 [static]

Maximum separation distance (in mm) between two bodies that are considered to be in contact.

Definition at line 314 of file contact.h.

Array of wrenches bounding the Contact Wrench Space (CWS).

The CWS is a convex polyhedron that defines the space of wrenches that can be applied at this contact. Also encapsulates normal forces (usually normalised to 1N) and the relationship between normal and frictional components (usually encapsulated in the coefficient of friction).

Definition at line 188 of file contact.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


graspit
Author(s):
autogenerated on Wed Jan 25 11:00:20 2012