SoftContact Class Reference

Soft Contact implements an SFC model for contacts between soft bodies. More...

#include <contact.h>

Inheritance diagram for SoftContact:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void computeWrenches ()
 Also attempt to apply some torques in the contact plane; currently disabled.
SoSeparator * getVisualIndicator ()
 Visual indicator is a small patch of the fit analytical surface on the body.
int setUpFrictionEdges (bool dynamicsOn=false)
 Friction model is a 3D friction ellipsoid also containing frictional torque.
 SoftContact (Body *b1, Body *b2, position pos, vec3 norm, Neighborhood *bn)
 Also takes a local neighborhood of points around body 1.
 ~SoftContact ()
 Deletes its local record of the body neighborhood.

Protected Member Functions

double CalcContact_Mattress (double nForce)
 Calculates friction characteristics using a Mattress model.
int CalcRelPhi ()
int CalcRprimes ()
 Calculate the relative curvatures of the two bodies for contact dynamics.
void FitPoints ()
 Fits an analytical surface to a local patch on body1 around the contact.

Protected Attributes

double a
 Parameters of unrotated fit in form z= ax^2+by^2+cxy.
double b
vec3bodyNghbd
 A list of points from body1 that surround the contact in the frame of body1.
double c
mat3 fitRot
 The rotation from the contact frame to the frame in which the fit is given by the radii of curvature, r1 and r2.
double fitRotAngle
 The angle of the fitRot rotation.
double majorAxis
 The major axis of the ellipse of contact.
double minorAxis
 The minor axis of the ellipse of contact.
int numPts
 The number of points in the current fit for analytical surfaces.
double r1
 Second order fit of points from body1 in the form r1x^2 + r2y^2.
double r1prime
 The relative radii of curvature of the two bodies.
double r2
double r2prime
 The relative radii of curvature of the two bodies.
double relPhi
 The relative angle between r1 and the mate's r1.

Detailed Description

Soft Contact implements an SFC model for contacts between soft bodies.

The SoftContact attempts to capture some of the frictional effects between soft bodies without explicitly computing the deformation at the contacts. It locally fits analytical surfaces to both bodies involved by computing their local radii of curvature. After this, it uses analytical models to compute the expected contact area and pressure distribution.

Based on the contact area, it then tries to approximate the relationship between tangential friction and frictional torque using the limit surface, which becomes a 3D friction ellipsoid. The friction space is thus 3D, and the wrench space becomes 4D.

Its visual indicator shows the analytical surface that has been fit to both bodies involved, as a small patch around the contact location.

Definition at line 380 of file contact.h.


Constructor & Destructor Documentation

SoftContact::SoftContact ( Body b1,
Body b2,
position  pos,
vec3  norm,
Neighborhood bn 
)

Also takes a local neighborhood of points around body 1.

Does not set up friction edges yet; we need to wait until the mate of this contact is also defined because we will need its own analytical surface before we can come up with friction edges.

Definition at line 650 of file contact.cpp.

SoftContact::~SoftContact (  ) 

Deletes its local record of the body neighborhood.

Definition at line 686 of file contact.cpp.


Member Function Documentation

double SoftContact::CalcContact_Mattress ( double  nForce  )  [protected]

Calculates friction characteristics using a Mattress model.

Calculates the axes of the ellipse of contact using the mattress model and a given normal force (for dynamics its the normal component of the dynamic contact force). Sets major axis and minor axis. Returns the max torque available. See Contact Mechanics, KL Johnson Chapter 4

Definition at line 932 of file contact.cpp.

int SoftContact::CalcRelPhi (  )  [protected]

Calculates the angle betwen the main radius curvature on body1 and the main radius of curvature on body 2.

Definition at line 828 of file contact.cpp.

int SoftContact::CalcRprimes (  )  [protected]

Calculate the relative curvatures of the two bodies for contact dynamics.

Calculates the relative radii of curvature of the contact, using the radii of curvature of both bodies and the angle between them. See Johnson, Contact Mechanics Chapter 4 page 85 for calculations.

Definition at line 854 of file contact.cpp.

void SoftContact::computeWrenches (  )  [virtual]

Also attempt to apply some torques in the contact plane; currently disabled.

The Soft Contact version of computeWrenches can also take into account the fact that a soft contact can generate some moments in the plane of the contacts. It creates wrenches like the regular contact, but multiple times, moving the location of the force around the area of contact. Currently disabled.

Reimplemented from Contact.

Definition at line 756 of file contact.cpp.

void SoftContact::FitPoints (  )  [protected]

Fits an analytical surface to a local patch on body1 around the contact.

Computes an analytical surface of the form ax^2 + bx + c in a small patch around the contact on body1. The fit is in the local body1 coordinate system.

Definition at line 811 of file contact.cpp.

SoSeparator * SoftContact::getVisualIndicator (  )  [virtual]

Visual indicator is a small patch of the fit analytical surface on the body.

Gets the visual indicator as a small patch of the fit analytical surface around the body. Also places a small arrow indicating the direction of the main radius of curvature computed for the body.

Reimplemented from Contact.

Definition at line 975 of file contact.cpp.

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

Friction model is a 3D friction ellipsoid also containing frictional torque.

Sets up friction edges as a 3D friction ellipsoid. All the computations for fitting analytical surfaces to the two bodies should already have been completed.

Implements Contact.

Definition at line 695 of file contact.cpp.


Member Data Documentation

double SoftContact::a [protected]

Parameters of unrotated fit in form z= ax^2+by^2+cxy.

Definition at line 392 of file contact.h.

double SoftContact::b [protected]

Definition at line 392 of file contact.h.

A list of points from body1 that surround the contact in the frame of body1.

Definition at line 384 of file contact.h.

double SoftContact::c [protected]

Definition at line 392 of file contact.h.

The rotation from the contact frame to the frame in which the fit is given by the radii of curvature, r1 and r2.

Definition at line 398 of file contact.h.

double SoftContact::fitRotAngle [protected]

The angle of the fitRot rotation.

Definition at line 401 of file contact.h.

double SoftContact::majorAxis [protected]

The major axis of the ellipse of contact.

Definition at line 404 of file contact.h.

double SoftContact::minorAxis [protected]

The minor axis of the ellipse of contact.

Definition at line 406 of file contact.h.

int SoftContact::numPts [protected]

The number of points in the current fit for analytical surfaces.

Definition at line 387 of file contact.h.

double SoftContact::r1 [protected]

Second order fit of points from body1 in the form r1x^2 + r2y^2.

Definition at line 390 of file contact.h.

double SoftContact::r1prime [protected]

The relative radii of curvature of the two bodies.

Definition at line 409 of file contact.h.

double SoftContact::r2 [protected]

Definition at line 390 of file contact.h.

double SoftContact::r2prime [protected]

The relative radii of curvature of the two bodies.

Definition at line 411 of file contact.h.

double SoftContact::relPhi [protected]

The relative angle between r1 and the mate's r1.

Definition at line 395 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:24 2012