DART  6.10.1
dart::constraint::ContactConstraint Class Reference

ContactConstraint represents a contact constraint between two bodies. More...

#include <ContactConstraint.hpp>

Inheritance diagram for dart::constraint::ContactConstraint:
dart::constraint::ConstraintBase

Public Member Functions

 ContactConstraint (collision::Contact &contact, double timeStep)
 Constructor. More...
 
 ~ContactConstraint () override=default
 Destructor. More...
 
const std::string & getType () const override
 Returns a string representing the constraint type. More...
 
void setFrictionDirection (const Eigen::Vector3d &dir)
 Set first frictional direction. More...
 
const Eigen::Vector3d & getFrictionDirection1 () const
 Get first frictional direction. More...
 
std::size_t getDimension () const
 Return dimesion of this constranit. More...
 

Static Public Member Functions

static const std::string & getStaticType ()
 Returns constraint type for this class. More...
 
static void setErrorAllowance (double allowance)
 Set global error reduction parameter. More...
 
static double getErrorAllowance ()
 Get global error reduction parameter. More...
 
static void setErrorReductionParameter (double erp)
 Set global error reduction parameter. More...
 
static double getErrorReductionParameter ()
 Get global error reduction parameter. More...
 
static void setMaxErrorReductionVelocity (double erv)
 Set global error reduction parameter. More...
 
static double getMaxErrorReductionVelocity ()
 Get global error reduction parameter. More...
 
static void setConstraintForceMixing (double cfm)
 Set global constraint force mixing parameter. More...
 
static double getConstraintForceMixing ()
 Get global constraint force mixing parameter. More...
 
static dynamics::SkeletonPtr getRootSkeleton (dynamics::SkeletonPtr skeleton)
 
static dynamics::SkeletonPtr compressPath (dynamics::SkeletonPtr skeleton)
 

Protected Member Functions

void update () override
 Update constraint using updated Skeleton's states. More...
 
void getInformation (ConstraintInfo *info) override
 Fill LCP variables. More...
 
void applyUnitImpulse (std::size_t index) override
 Apply unit impulse to constraint space. More...
 
void getVelocityChange (double *vel, bool withCfm) override
 Get velocity change due to the uint impulse. More...
 
void excite () override
 Excite the constraint. More...
 
void unexcite () override
 Unexcite the constraint. More...
 
void applyImpulse (double *lambda) override
 Apply computed constraint impulse to constrained skeletons. More...
 
dynamics::SkeletonPtr getRootSkeleton () const override
 
void uniteSkeletons () override
 
bool isActive () const override
 Return true if this constraint is active. More...
 

Static Protected Member Functions

static double computeFrictionCoefficient (const dynamics::ShapeNode *shapeNode)
 
static double computePrimaryFrictionCoefficient (const dynamics::ShapeNode *shapeNode)
 
static double computeSecondaryFrictionCoefficient (const dynamics::ShapeNode *shapeNode)
 
static double computePrimarySlipCompliance (const dynamics::ShapeNode *shapeNode)
 
static double computeSecondarySlipCompliance (const dynamics::ShapeNode *shapeNode)
 
static Eigen::Vector3d computeWorldFirstFrictionDir (const dynamics::ShapeNode *shapenode)
 
static double computeRestitutionCoefficient (const dynamics::ShapeNode *shapeNode)
 

Protected Attributes

std::size_t mDim
 Dimension of constraint. More...
 

Private Types

using TangentBasisMatrix = Eigen::Matrix< double, 3, 2 >
 

Private Member Functions

void getRelVelocity (double *relVel)
 Get change in relative velocity at contact point due to external impulse. More...
 
void updateFirstFrictionalDirection ()
 
TangentBasisMatrix getTangentBasisMatrixODE (const Eigen::Vector3d &n)
 
double getPrimarySlipCompliance () const
 Get primary slip compliance. More...
 
void setPrimarySlipCompliance (double slip)
 Set primary slip compliance. More...
 
double getSecondarySlipCompliance () const
 Get secondary slip compliance. More...
 
void setSecondarySlipCompliance (double slip)
 Set secondary slip compliance. More...
 
const collision::ContactgetContact () const
 Get contact object associated witht this constraint. More...
 

Private Attributes

double mTimeStep
 Time step. More...
 
dynamics::BodyNodemBodyNodeA
 Fircst body node. More...
 
dynamics::BodyNodemBodyNodeB
 Second body node. More...
 
collision::ContactmContact
 Contact between mBodyNode1 and mBodyNode2. More...
 
Eigen::Vector3d mFirstFrictionalDirection
 First frictional direction. More...
 
double mPrimaryFrictionCoeff
 Primary Coefficient of Friction. More...
 
double mSecondaryFrictionCoeff
 Primary Coefficient of Friction. More...
 
double mPrimarySlipCompliance
 Primary Coefficient of Slip Compliance. More...
 
double mSecondarySlipCompliance
 Secondary Coefficient of Slip Compliance. More...
 
double mRestitutionCoeff
 Coefficient of restitution. More...
 
bool mIsSelfCollision
 Whether this contact is self-collision. More...
 
Eigen::Matrix< double, 6, Eigen::Dynamic > mSpatialNormalA
 Local body jacobians for mBodyNode1. More...
 
Eigen::Matrix< double, 6, Eigen::Dynamic > mSpatialNormalB
 Local body jacobians for mBodyNode2. More...
 
bool mIsFrictionOn
 
std::size_t mAppliedImpulseIndex
 Index of applied impulse. More...
 
bool mIsBounceOn
 
bool mActive
 

Static Private Attributes

static double mErrorAllowance = 0.0
 Global constraint error allowance. More...
 
static double mErrorReductionParameter = 0.01
 Global constraint error redection parameter in the range of [0, 1]. More...
 
static double mMaxErrorReductionVelocity = 1e-3
 Maximum error reduction velocity. More...
 
static double mConstraintForceMixing = 1e-5
 Global constraint force mixing parameter in the range of [1e-9, 1]. More...
 

Friends

class ConstraintSolver
 
class ConstrainedGroup
 

Detailed Description

ContactConstraint represents a contact constraint between two bodies.

Member Typedef Documentation

◆ TangentBasisMatrix

using dart::constraint::ContactConstraint::TangentBasisMatrix = Eigen::Matrix<double, 3, 2>
private

Constructor & Destructor Documentation

◆ ContactConstraint()

dart::constraint::ContactConstraint::ContactConstraint ( collision::Contact contact,
double  timeStep 
)

Constructor.

◆ ~ContactConstraint()

dart::constraint::ContactConstraint::~ContactConstraint ( )
overridedefault

Destructor.

Member Function Documentation

◆ applyImpulse()

void dart::constraint::ContactConstraint::applyImpulse ( double *  lambda)
overrideprotectedvirtual

Apply computed constraint impulse to constrained skeletons.

Implements dart::constraint::ConstraintBase.

◆ applyUnitImpulse()

void dart::constraint::ContactConstraint::applyUnitImpulse ( std::size_t  index)
overrideprotectedvirtual

Apply unit impulse to constraint space.

Implements dart::constraint::ConstraintBase.

◆ compressPath()

dynamics::SkeletonPtr dart::constraint::ConstraintBase::compressPath ( dynamics::SkeletonPtr  skeleton)
staticinherited

◆ computeFrictionCoefficient()

double dart::constraint::ContactConstraint::computeFrictionCoefficient ( const dynamics::ShapeNode shapeNode)
staticprotected

◆ computePrimaryFrictionCoefficient()

double dart::constraint::ContactConstraint::computePrimaryFrictionCoefficient ( const dynamics::ShapeNode shapeNode)
staticprotected

◆ computePrimarySlipCompliance()

double dart::constraint::ContactConstraint::computePrimarySlipCompliance ( const dynamics::ShapeNode shapeNode)
staticprotected

◆ computeRestitutionCoefficient()

double dart::constraint::ContactConstraint::computeRestitutionCoefficient ( const dynamics::ShapeNode shapeNode)
staticprotected

◆ computeSecondaryFrictionCoefficient()

double dart::constraint::ContactConstraint::computeSecondaryFrictionCoefficient ( const dynamics::ShapeNode shapeNode)
staticprotected

◆ computeSecondarySlipCompliance()

double dart::constraint::ContactConstraint::computeSecondarySlipCompliance ( const dynamics::ShapeNode shapeNode)
staticprotected

◆ computeWorldFirstFrictionDir()

Eigen::Vector3d dart::constraint::ContactConstraint::computeWorldFirstFrictionDir ( const dynamics::ShapeNode shapenode)
staticprotected

◆ excite()

void dart::constraint::ContactConstraint::excite ( )
overrideprotectedvirtual

Excite the constraint.

Implements dart::constraint::ConstraintBase.

◆ getConstraintForceMixing()

double dart::constraint::ContactConstraint::getConstraintForceMixing ( )
static

Get global constraint force mixing parameter.

◆ getContact()

const collision::Contact & dart::constraint::ContactConstraint::getContact ( ) const
private

Get contact object associated witht this constraint.

◆ getDimension()

std::size_t dart::constraint::ConstraintBase::getDimension ( ) const
inherited

Return dimesion of this constranit.

◆ getErrorAllowance()

double dart::constraint::ContactConstraint::getErrorAllowance ( )
static

Get global error reduction parameter.

◆ getErrorReductionParameter()

double dart::constraint::ContactConstraint::getErrorReductionParameter ( )
static

Get global error reduction parameter.

◆ getFrictionDirection1()

const Eigen::Vector3d & dart::constraint::ContactConstraint::getFrictionDirection1 ( ) const

Get first frictional direction.

◆ getInformation()

void dart::constraint::ContactConstraint::getInformation ( ConstraintInfo info)
overrideprotectedvirtual

Fill LCP variables.

Implements dart::constraint::ConstraintBase.

◆ getMaxErrorReductionVelocity()

double dart::constraint::ContactConstraint::getMaxErrorReductionVelocity ( )
static

Get global error reduction parameter.

◆ getPrimarySlipCompliance()

double dart::constraint::ContactConstraint::getPrimarySlipCompliance ( ) const
private

Get primary slip compliance.

◆ getRelVelocity()

void dart::constraint::ContactConstraint::getRelVelocity ( double *  relVel)
private

Get change in relative velocity at contact point due to external impulse.

Parameters
[out]relVelChange in relative velocity at contact point of the two colliding bodies.

◆ getRootSkeleton() [1/2]

dynamics::SkeletonPtr dart::constraint::ContactConstraint::getRootSkeleton ( ) const
overrideprotectedvirtual

◆ getRootSkeleton() [2/2]

dynamics::SkeletonPtr dart::constraint::ConstraintBase::getRootSkeleton ( dynamics::SkeletonPtr  skeleton)
staticinherited

◆ getSecondarySlipCompliance()

double dart::constraint::ContactConstraint::getSecondarySlipCompliance ( ) const
private

Get secondary slip compliance.

◆ getStaticType()

const std::string & dart::constraint::ContactConstraint::getStaticType ( )
static

Returns constraint type for this class.

◆ getTangentBasisMatrixODE()

ContactConstraint::TangentBasisMatrix dart::constraint::ContactConstraint::getTangentBasisMatrixODE ( const Eigen::Vector3d &  n)
private

◆ getType()

const std::string & dart::constraint::ContactConstraint::getType ( ) const
overridevirtual

Returns a string representing the constraint type.

Reimplemented from dart::constraint::ConstraintBase.

◆ getVelocityChange()

void dart::constraint::ContactConstraint::getVelocityChange ( double *  vel,
bool  withCfm 
)
overrideprotectedvirtual

Get velocity change due to the uint impulse.

Implements dart::constraint::ConstraintBase.

◆ isActive()

bool dart::constraint::ContactConstraint::isActive ( ) const
overrideprotectedvirtual

Return true if this constraint is active.

Implements dart::constraint::ConstraintBase.

◆ setConstraintForceMixing()

void dart::constraint::ContactConstraint::setConstraintForceMixing ( double  cfm)
static

Set global constraint force mixing parameter.

◆ setErrorAllowance()

void dart::constraint::ContactConstraint::setErrorAllowance ( double  allowance)
static

Set global error reduction parameter.

◆ setErrorReductionParameter()

void dart::constraint::ContactConstraint::setErrorReductionParameter ( double  erp)
static

Set global error reduction parameter.

◆ setFrictionDirection()

void dart::constraint::ContactConstraint::setFrictionDirection ( const Eigen::Vector3d &  dir)

Set first frictional direction.

◆ setMaxErrorReductionVelocity()

void dart::constraint::ContactConstraint::setMaxErrorReductionVelocity ( double  erv)
static

Set global error reduction parameter.

◆ setPrimarySlipCompliance()

void dart::constraint::ContactConstraint::setPrimarySlipCompliance ( double  slip)
private

Set primary slip compliance.

◆ setSecondarySlipCompliance()

void dart::constraint::ContactConstraint::setSecondarySlipCompliance ( double  slip)
private

Set secondary slip compliance.

◆ unexcite()

void dart::constraint::ContactConstraint::unexcite ( )
overrideprotectedvirtual

Unexcite the constraint.

Implements dart::constraint::ConstraintBase.

◆ uniteSkeletons()

void dart::constraint::ContactConstraint::uniteSkeletons ( )
overrideprotectedvirtual

Reimplemented from dart::constraint::ConstraintBase.

◆ update()

void dart::constraint::ContactConstraint::update ( )
overrideprotectedvirtual

Update constraint using updated Skeleton's states.

Implements dart::constraint::ConstraintBase.

◆ updateFirstFrictionalDirection()

void dart::constraint::ContactConstraint::updateFirstFrictionalDirection ( )
private

Friends And Related Function Documentation

◆ ConstrainedGroup

friend class ConstrainedGroup
friend

◆ ConstraintSolver

friend class ConstraintSolver
friend

Member Data Documentation

◆ mActive

bool dart::constraint::ContactConstraint::mActive
private

◆ mAppliedImpulseIndex

std::size_t dart::constraint::ContactConstraint::mAppliedImpulseIndex
private

Index of applied impulse.

◆ mBodyNodeA

dynamics::BodyNode* dart::constraint::ContactConstraint::mBodyNodeA
private

Fircst body node.

◆ mBodyNodeB

dynamics::BodyNode* dart::constraint::ContactConstraint::mBodyNodeB
private

Second body node.

◆ mConstraintForceMixing

double dart::constraint::ContactConstraint::mConstraintForceMixing = 1e-5
staticprivate

Global constraint force mixing parameter in the range of [1e-9, 1].

The default is 1e-5

See also
http://www.ode.org/ode-latest-userguide.html#sec_3_8_0

◆ mContact

collision::Contact& dart::constraint::ContactConstraint::mContact
private

Contact between mBodyNode1 and mBodyNode2.

◆ mDim

std::size_t dart::constraint::ConstraintBase::mDim
protectedinherited

Dimension of constraint.

◆ mErrorAllowance

double dart::constraint::ContactConstraint::mErrorAllowance = 0.0
staticprivate

Global constraint error allowance.

◆ mErrorReductionParameter

double dart::constraint::ContactConstraint::mErrorReductionParameter = 0.01
staticprivate

Global constraint error redection parameter in the range of [0, 1].

The default is 0.01.

◆ mFirstFrictionalDirection

Eigen::Vector3d dart::constraint::ContactConstraint::mFirstFrictionalDirection
private

First frictional direction.

◆ mIsBounceOn

bool dart::constraint::ContactConstraint::mIsBounceOn
private

◆ mIsFrictionOn

bool dart::constraint::ContactConstraint::mIsFrictionOn
private

◆ mIsSelfCollision

bool dart::constraint::ContactConstraint::mIsSelfCollision
private

Whether this contact is self-collision.

◆ mMaxErrorReductionVelocity

double dart::constraint::ContactConstraint::mMaxErrorReductionVelocity = 1e-3
staticprivate

Maximum error reduction velocity.

◆ mPrimaryFrictionCoeff

double dart::constraint::ContactConstraint::mPrimaryFrictionCoeff
private

Primary Coefficient of Friction.

◆ mPrimarySlipCompliance

double dart::constraint::ContactConstraint::mPrimarySlipCompliance
private

Primary Coefficient of Slip Compliance.

◆ mRestitutionCoeff

double dart::constraint::ContactConstraint::mRestitutionCoeff
private

Coefficient of restitution.

◆ mSecondaryFrictionCoeff

double dart::constraint::ContactConstraint::mSecondaryFrictionCoeff
private

Primary Coefficient of Friction.

◆ mSecondarySlipCompliance

double dart::constraint::ContactConstraint::mSecondarySlipCompliance
private

Secondary Coefficient of Slip Compliance.

◆ mSpatialNormalA

Eigen::Matrix<double, 6, Eigen::Dynamic> dart::constraint::ContactConstraint::mSpatialNormalA
private

Local body jacobians for mBodyNode1.

◆ mSpatialNormalB

Eigen::Matrix<double, 6, Eigen::Dynamic> dart::constraint::ContactConstraint::mSpatialNormalB
private

Local body jacobians for mBodyNode2.

◆ mTimeStep

double dart::constraint::ContactConstraint::mTimeStep
private

Time step.