DART  6.10.1
dart::constraint::JointLimitConstraint Class Reference

JointLimitConstraint handles joint position and velocity limits. More...

#include <JointLimitConstraint.hpp>

Inheritance diagram for dart::constraint::JointLimitConstraint:
dart::constraint::ConstraintBase

Public Member Functions

 JointLimitConstraint (dynamics::Joint *joint)
 Constructor. More...
 
 ~JointLimitConstraint () override=default
 Destructor. More...
 
const std::string & getType () const override
 Returns a string representing the constraint type. More...
 
std::size_t getDimension () const
 Return dimesion of this constranit. More...
 
virtual void uniteSkeletons ()
 

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 *lcp) override
 Fill LCP variables. More...
 
void applyUnitImpulse (std::size_t index) override
 Apply unit impulse to constraint space. More...
 
void getVelocityChange (double *delVel, 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
 
bool isActive () const override
 Return true if this constraint is active. More...
 

Protected Attributes

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

Private Attributes

dynamics::JointmJoint
 The Joint that this constraint is associated with. More...
 
dynamics::BodyNodemBodyNode
 The child BodyNode of the Joint that this constraint is associated with. More...
 
std::size_t mAppliedImpulseIndex
 Index of applied impulse. More...
 
Eigen::Matrix< std::size_t, 6, 1 > mLifeTime
 Life time of constraint of each DOF. More...
 
Eigen::Matrix< bool, 6, 1 > mIsPositionLimitViolated
 Whether joint value exceeds the position limit. More...
 
Eigen::Matrix< bool, 6, 1 > mIsVelocityLimitViolated
 Whether joint value exceeds the velocity limit. More...
 
Eigen::Matrix< double, 6, 1 > mViolation
 How much current joint values are exceeded from the limits. More...
 
Eigen::Matrix< double, 6, 1 > mNegativeVel
 The desired delta velocity to satisfy the joint limit constraint. More...
 
Eigen::Matrix< double, 6, 1 > mOldX
 Constraint impulse of the previous step. More...
 
Eigen::Matrix< double, 6, 1 > mUpperBound
 Upper limit of the constraint impulse. More...
 
Eigen::Matrix< double, 6, 1 > mLowerBound
 Lower limit of the constraint impulse. More...
 

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+1
 Maximum error reduction velocity. More...
 
static double mConstraintForceMixing = 1e-9
 Global constraint force mixing parameter in the range of [1e-9, 1]. More...
 

Friends

class ConstraintSolver
 
class ConstrainedGroup
 

Detailed Description

JointLimitConstraint handles joint position and velocity limits.

Constructor & Destructor Documentation

◆ JointLimitConstraint()

dart::constraint::JointLimitConstraint::JointLimitConstraint ( dynamics::Joint joint)
explicit

Constructor.

◆ ~JointLimitConstraint()

dart::constraint::JointLimitConstraint::~JointLimitConstraint ( )
overridedefault

Destructor.

Member Function Documentation

◆ applyImpulse()

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

Apply computed constraint impulse to constrained skeletons.

Implements dart::constraint::ConstraintBase.

◆ applyUnitImpulse()

void dart::constraint::JointLimitConstraint::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

◆ excite()

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

Excite the constraint.

Implements dart::constraint::ConstraintBase.

◆ getConstraintForceMixing()

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

Get global constraint force mixing parameter.

◆ getDimension()

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

Return dimesion of this constranit.

◆ getErrorAllowance()

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

Get global error reduction parameter.

◆ getErrorReductionParameter()

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

Get global error reduction parameter.

◆ getInformation()

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

Fill LCP variables.

Implements dart::constraint::ConstraintBase.

◆ getMaxErrorReductionVelocity()

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

Get global error reduction parameter.

◆ getRootSkeleton() [1/2]

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

◆ getRootSkeleton() [2/2]

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

◆ getStaticType()

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

Returns constraint type for this class.

◆ getType()

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

Returns a string representing the constraint type.

Reimplemented from dart::constraint::ConstraintBase.

◆ getVelocityChange()

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

Get velocity change due to the uint impulse.

Implements dart::constraint::ConstraintBase.

◆ isActive()

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

Return true if this constraint is active.

Implements dart::constraint::ConstraintBase.

◆ setConstraintForceMixing()

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

Set global constraint force mixing parameter.

◆ setErrorAllowance()

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

Set global error reduction parameter.

◆ setErrorReductionParameter()

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

Set global error reduction parameter.

◆ setMaxErrorReductionVelocity()

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

Set global error reduction parameter.

◆ unexcite()

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

Unexcite the constraint.

Implements dart::constraint::ConstraintBase.

◆ uniteSkeletons()

void dart::constraint::ConstraintBase::uniteSkeletons ( )
virtualinherited

◆ update()

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

Update constraint using updated Skeleton's states.

Implements dart::constraint::ConstraintBase.

Friends And Related Function Documentation

◆ ConstrainedGroup

friend class ConstrainedGroup
friend

◆ ConstraintSolver

friend class ConstraintSolver
friend

Member Data Documentation

◆ mAppliedImpulseIndex

std::size_t dart::constraint::JointLimitConstraint::mAppliedImpulseIndex
private

Index of applied impulse.

◆ mBodyNode

dynamics::BodyNode* dart::constraint::JointLimitConstraint::mBodyNode
private

The child BodyNode of the Joint that this constraint is associated with.

◆ mConstraintForceMixing

double dart::constraint::JointLimitConstraint::mConstraintForceMixing = 1e-9
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

◆ mDim

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

Dimension of constraint.

◆ mErrorAllowance

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

Global constraint error allowance.

◆ mErrorReductionParameter

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

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

The default is 0.01.

◆ mIsPositionLimitViolated

Eigen::Matrix<bool, 6, 1> dart::constraint::JointLimitConstraint::mIsPositionLimitViolated
private

Whether joint value exceeds the position limit.

◆ mIsVelocityLimitViolated

Eigen::Matrix<bool, 6, 1> dart::constraint::JointLimitConstraint::mIsVelocityLimitViolated
private

Whether joint value exceeds the velocity limit.

◆ mJoint

dynamics::Joint* dart::constraint::JointLimitConstraint::mJoint
private

The Joint that this constraint is associated with.

◆ mLifeTime

Eigen::Matrix<std::size_t, 6, 1> dart::constraint::JointLimitConstraint::mLifeTime
private

Life time of constraint of each DOF.

◆ mLowerBound

Eigen::Matrix<double, 6, 1> dart::constraint::JointLimitConstraint::mLowerBound
private

Lower limit of the constraint impulse.

◆ mMaxErrorReductionVelocity

double dart::constraint::JointLimitConstraint::mMaxErrorReductionVelocity = 1e+1
staticprivate

Maximum error reduction velocity.

◆ mNegativeVel

Eigen::Matrix<double, 6, 1> dart::constraint::JointLimitConstraint::mNegativeVel
private

The desired delta velocity to satisfy the joint limit constraint.

◆ mOldX

Eigen::Matrix<double, 6, 1> dart::constraint::JointLimitConstraint::mOldX
private

Constraint impulse of the previous step.

◆ mUpperBound

Eigen::Matrix<double, 6, 1> dart::constraint::JointLimitConstraint::mUpperBound
private

Upper limit of the constraint impulse.

◆ mViolation

Eigen::Matrix<double, 6, 1> dart::constraint::JointLimitConstraint::mViolation
private

How much current joint values are exceeded from the limits.