DART  6.10.1
dart::constraint::BoxedLcpConstraintSolver Class Reference

#include <BoxedLcpConstraintSolver.hpp>

Inheritance diagram for dart::constraint::BoxedLcpConstraintSolver:
dart::constraint::ConstraintSolver

Public Member Functions

 BoxedLcpConstraintSolver (double timeStep, BoxedLcpSolverPtr boxedLcpSolver=nullptr, BoxedLcpSolverPtr secondaryBoxedLcpSolver=nullptr)
 Constructor. More...
 
 BoxedLcpConstraintSolver ()
 Constructos with default primary and secondary LCP solvers, which are Dantzig and PGS, respectively. More...
 
 BoxedLcpConstraintSolver (BoxedLcpSolverPtr boxedLcpSolver)
 Constructors with specific primary LCP solver. More...
 
 BoxedLcpConstraintSolver (BoxedLcpSolverPtr boxedLcpSolver, BoxedLcpSolverPtr secondaryBoxedLcpSolver)
 Constructs with specific primary and secondary LCP solvers. More...
 
void setBoxedLcpSolver (BoxedLcpSolverPtr lcpSolver)
 Sets boxed LCP (BLCP) solver. More...
 
ConstBoxedLcpSolverPtr getBoxedLcpSolver () const
 Returns boxed LCP (BLCP) solver. More...
 
void setSecondaryBoxedLcpSolver (BoxedLcpSolverPtr lcpSolver)
 Sets boxed LCP (BLCP) solver that is used when the primary solver failed. More...
 
ConstBoxedLcpSolverPtr getSecondaryBoxedLcpSolver () const
 Returns boxed LCP (BLCP) solver that is used when the primary solver failed. More...
 
void addSkeleton (const dynamics::SkeletonPtr &skeleton)
 Add single skeleton. More...
 
void addSkeletons (const std::vector< dynamics::SkeletonPtr > &skeletons)
 Add mutiple skeletons. More...
 
const std::vector< dynamics::SkeletonPtr > & getSkeletons () const
 Returns all the skeletons added to this ConstraintSolver. More...
 
void removeSkeleton (const dynamics::SkeletonPtr &skeleton)
 Remove single skeleton. More...
 
void removeSkeletons (const std::vector< dynamics::SkeletonPtr > &skeletons)
 Remove multiple skeletons. More...
 
void removeAllSkeletons ()
 Remove all skeletons in this constraint solver. More...
 
void addConstraint (const ConstraintBasePtr &constraint)
 Add a constraint. More...
 
void removeConstraint (const ConstraintBasePtr &constraint)
 Remove a constraint. More...
 
void removeAllConstraints ()
 Remove all constraints. More...
 
std::size_t getNumConstraints () const
 Returns the number of constraints that was manually added to this ConstraintSolver. More...
 
constraint::ConstraintBasePtr getConstraint (std::size_t index)
 Returns a constraint by index. More...
 
constraint::ConstConstraintBasePtr getConstraint (std::size_t index) const
 Returns a constraint by index. More...
 
std::vector< constraint::ConstraintBasePtrgetConstraints ()
 Returns all the constraints added to this ConstraintSolver. More...
 
std::vector< constraint::ConstConstraintBasePtrgetConstraints () const
 Returns all the constraints added to this ConstraintSolver. More...
 
void clearLastCollisionResult ()
 Clears the last collision result. More...
 
virtual void setTimeStep (double _timeStep)
 Set time step. More...
 
double getTimeStep () const
 Get time step. More...
 
void setCollisionDetector (collision::CollisionDetector *collisionDetector)
 Set collision detector. More...
 
void setCollisionDetector (const std::shared_ptr< collision::CollisionDetector > &collisionDetector)
 Set collision detector. More...
 
collision::CollisionDetectorPtr getCollisionDetector ()
 Get collision detector. More...
 
collision::ConstCollisionDetectorPtr getCollisionDetector () const
 Get (const) collision detector. More...
 
collision::CollisionGroupPtr getCollisionGroup ()
 Return collision group of collision objects that are added to this ConstraintSolver. More...
 
collision::ConstCollisionGroupPtr getCollisionGroup () const
 Return (const) collision group of collision objects that are added to this ConstraintSolver. More...
 
collision::CollisionOptiongetCollisionOption ()
 Returns collision option that is used for collision checkings in this ConstraintSolver to generate contact constraints. More...
 
const collision::CollisionOptiongetCollisionOption () const
 Returns collision option that is used for collision checkings in this ConstraintSolver to generate contact constraints. More...
 
collision::CollisionResultgetLastCollisionResult ()
 Return the last collision checking result. More...
 
const collision::CollisionResultgetLastCollisionResult () const
 Return the last collision checking result. More...
 
void setLCPSolver (std::unique_ptr< LCPSolver > lcpSolver)
 Set LCP solver. More...
 
LCPSolvergetLCPSolver () const
 Get LCP solver. More...
 
void solve ()
 Solve constraint impulses and apply them to the skeletons. More...
 
virtual void setFromOtherConstraintSolver (const ConstraintSolver &other)
 Sets this constraint solver using other constraint solver. More...
 

Protected Types

using CollisionDetector = collision::CollisionDetector
 

Protected Member Functions

void solveConstrainedGroup (ConstrainedGroup &group) override
 
bool containSkeleton (const dynamics::ConstSkeletonPtr &skeleton) const
 Check if the skeleton is contained in this solver. More...
 
bool checkAndAddSkeleton (const dynamics::SkeletonPtr &skeleton)
 Add skeleton if the constraint is not contained in this solver. More...
 
bool containConstraint (const ConstConstraintBasePtr &constraint) const
 Check if the constraint is contained in this solver. More...
 
bool checkAndAddConstraint (const ConstraintBasePtr &constraint)
 Add constraint if the constraint is not contained in this solver. More...
 
void updateConstraints ()
 Update constraints. More...
 
void buildConstrainedGroups ()
 Build constrained groupsContact. More...
 
void solveConstrainedGroups ()
 Solve constrained groups. More...
 
bool isSoftContact (const collision::Contact &contact) const
 Return true if at least one of colliding body is soft body. More...
 

Protected Attributes

BoxedLcpSolverPtr mBoxedLcpSolver
 Boxed LCP solver. More...
 
BoxedLcpSolverPtr mSecondaryBoxedLcpSolver
 Boxed LCP solver to be used when the primary solver failed. More...
 
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > mA
 Cache data for boxed LCP formulation. More...
 
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > mABackup
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXd mX
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXd mXBackup
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXd mB
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXd mBBackup
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXd mW
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXd mLo
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXd mLoBackup
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXd mHi
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXd mHiBackup
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXi mFIndex
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXi mFIndexBackup
 Cache data for boxed LCP formulation. More...
 
Eigen::VectorXi mOffset
 Cache data for boxed LCP formulation. More...
 
collision::CollisionDetectorPtr mCollisionDetector
 Collision detector. More...
 
collision::CollisionGroupPtr mCollisionGroup
 Collision group. More...
 
collision::CollisionOption mCollisionOption
 Collision detection option. More...
 
collision::CollisionResult mCollisionResult
 Last collision checking result. More...
 
double mTimeStep
 Time step. More...
 
std::vector< dynamics::SkeletonPtrmSkeletons
 Skeleton list. More...
 
std::vector< ContactConstraintPtrmContactConstraints
 Contact constraints those are automatically created. More...
 
std::vector< SoftContactConstraintPtrmSoftContactConstraints
 Soft contact constraints those are automatically created. More...
 
std::vector< JointLimitConstraintPtrmJointLimitConstraints
 Joint limit constraints those are automatically created. More...
 
std::vector< ServoMotorConstraintPtrmServoMotorConstraints
 Servo motor constraints those are automatically created. More...
 
std::vector< MimicMotorConstraintPtrmMimicMotorConstraints
 Mimic motor constraints those are automatically created. More...
 
std::vector< JointCoulombFrictionConstraintPtrmJointCoulombFrictionConstraints
 Joint Coulomb friction constraints those are automatically created. More...
 
std::vector< ConstraintBasePtrmManualConstraints
 Constraints that manually added. More...
 
std::vector< ConstraintBasePtrmActiveConstraints
 Active constraints. More...
 
std::vector< ConstrainedGroupmConstrainedGroups
 Constraint group list. More...
 

Private Member Functions

bool isSymmetric (std::size_t n, double *A)
 Return true if the matrix is symmetric. More...
 
bool isSymmetric (std::size_t n, double *A, std::size_t begin, std::size_t end)
 Return true if the diagonla block of matrix is symmetric. More...
 
void print (std::size_t n, double *A, double *x, double *lo, double *hi, double *b, double *w, int *findex)
 Print debug information. More...
 

Member Typedef Documentation

◆ CollisionDetector

Constructor & Destructor Documentation

◆ BoxedLcpConstraintSolver() [1/4]

dart::constraint::BoxedLcpConstraintSolver::BoxedLcpConstraintSolver ( double  timeStep,
BoxedLcpSolverPtr  boxedLcpSolver = nullptr,
BoxedLcpSolverPtr  secondaryBoxedLcpSolver = nullptr 
)

Constructor.

Parameters
[in]timeStepSimulation time step
[in]boxedLcpSolverThe primary boxed LCP solver. When nullptr is passed, Dantzig solver will be used.
[in]secondaryBoxedLcpSolverThe secondary boxed-LCP solver. When nullptr is passed, PGS solver will be used. This is to make the default solver setting to be Dantzig + PGS. In order to disable use of secondary solver, call setSecondaryBoxedLcpSolver(nullptr) explicitly.
Deprecated:
Deprecated in DART 6.8. Please use other constructors that doesn't take timespte. Timestep should be set by the owner of this solver such as dart::simulation::World when the solver added.

◆ BoxedLcpConstraintSolver() [2/4]

dart::constraint::BoxedLcpConstraintSolver::BoxedLcpConstraintSolver ( )

Constructos with default primary and secondary LCP solvers, which are Dantzig and PGS, respectively.

◆ BoxedLcpConstraintSolver() [3/4]

dart::constraint::BoxedLcpConstraintSolver::BoxedLcpConstraintSolver ( BoxedLcpSolverPtr  boxedLcpSolver)

Constructors with specific primary LCP solver.

Parameters
[in]boxedLcpSolverThe primary boxed LCP solver. When nullptr is passed, which is discouraged, Dantzig solver will be used.

◆ BoxedLcpConstraintSolver() [4/4]

dart::constraint::BoxedLcpConstraintSolver::BoxedLcpConstraintSolver ( BoxedLcpSolverPtr  boxedLcpSolver,
BoxedLcpSolverPtr  secondaryBoxedLcpSolver 
)

Constructs with specific primary and secondary LCP solvers.

Parameters
[in]boxedLcpSolverThe primary boxed LCP solver. When nullptr is passed, which is discouraged, Dantzig solver will be used.
[in]secondaryBoxedLcpSolverThe secondary boxed-LCP solver. Pass nullptr to disable using secondary LCP solver.

Member Function Documentation

◆ addConstraint()

void dart::constraint::ConstraintSolver::addConstraint ( const ConstraintBasePtr constraint)
inherited

Add a constraint.

◆ addSkeleton()

void dart::constraint::ConstraintSolver::addSkeleton ( const dynamics::SkeletonPtr skeleton)
inherited

Add single skeleton.

◆ addSkeletons()

void dart::constraint::ConstraintSolver::addSkeletons ( const std::vector< dynamics::SkeletonPtr > &  skeletons)
inherited

Add mutiple skeletons.

◆ buildConstrainedGroups()

void dart::constraint::ConstraintSolver::buildConstrainedGroups ( )
protectedinherited

Build constrained groupsContact.

◆ checkAndAddConstraint()

bool dart::constraint::ConstraintSolver::checkAndAddConstraint ( const ConstraintBasePtr constraint)
protectedinherited

Add constraint if the constraint is not contained in this solver.

◆ checkAndAddSkeleton()

bool dart::constraint::ConstraintSolver::checkAndAddSkeleton ( const dynamics::SkeletonPtr skeleton)
protectedinherited

Add skeleton if the constraint is not contained in this solver.

◆ clearLastCollisionResult()

void dart::constraint::ConstraintSolver::clearLastCollisionResult ( )
inherited

Clears the last collision result.

◆ containConstraint()

bool dart::constraint::ConstraintSolver::containConstraint ( const ConstConstraintBasePtr constraint) const
protectedinherited

Check if the constraint is contained in this solver.

◆ containSkeleton()

bool dart::constraint::ConstraintSolver::containSkeleton ( const dynamics::ConstSkeletonPtr skeleton) const
protectedinherited

Check if the skeleton is contained in this solver.

◆ getBoxedLcpSolver()

ConstBoxedLcpSolverPtr dart::constraint::BoxedLcpConstraintSolver::getBoxedLcpSolver ( ) const

Returns boxed LCP (BLCP) solver.

◆ getCollisionDetector() [1/2]

collision::CollisionDetectorPtr dart::constraint::ConstraintSolver::getCollisionDetector ( )
inherited

Get collision detector.

◆ getCollisionDetector() [2/2]

collision::ConstCollisionDetectorPtr dart::constraint::ConstraintSolver::getCollisionDetector ( ) const
inherited

Get (const) collision detector.

◆ getCollisionGroup() [1/2]

collision::CollisionGroupPtr dart::constraint::ConstraintSolver::getCollisionGroup ( )
inherited

Return collision group of collision objects that are added to this ConstraintSolver.

◆ getCollisionGroup() [2/2]

collision::ConstCollisionGroupPtr dart::constraint::ConstraintSolver::getCollisionGroup ( ) const
inherited

Return (const) collision group of collision objects that are added to this ConstraintSolver.

◆ getCollisionOption() [1/2]

collision::CollisionOption & dart::constraint::ConstraintSolver::getCollisionOption ( )
inherited

Returns collision option that is used for collision checkings in this ConstraintSolver to generate contact constraints.

◆ getCollisionOption() [2/2]

const collision::CollisionOption & dart::constraint::ConstraintSolver::getCollisionOption ( ) const
inherited

Returns collision option that is used for collision checkings in this ConstraintSolver to generate contact constraints.

◆ getConstraint() [1/2]

ConstraintBasePtr dart::constraint::ConstraintSolver::getConstraint ( std::size_t  index)
inherited

Returns a constraint by index.

◆ getConstraint() [2/2]

ConstConstraintBasePtr dart::constraint::ConstraintSolver::getConstraint ( std::size_t  index) const
inherited

Returns a constraint by index.

◆ getConstraints() [1/2]

std::vector< ConstraintBasePtr > dart::constraint::ConstraintSolver::getConstraints ( )
inherited

Returns all the constraints added to this ConstraintSolver.

◆ getConstraints() [2/2]

std::vector< ConstConstraintBasePtr > dart::constraint::ConstraintSolver::getConstraints ( ) const
inherited

Returns all the constraints added to this ConstraintSolver.

◆ getLastCollisionResult() [1/2]

collision::CollisionResult & dart::constraint::ConstraintSolver::getLastCollisionResult ( )
inherited

Return the last collision checking result.

◆ getLastCollisionResult() [2/2]

const collision::CollisionResult & dart::constraint::ConstraintSolver::getLastCollisionResult ( ) const
inherited

Return the last collision checking result.

◆ getLCPSolver()

LCPSolver * dart::constraint::ConstraintSolver::getLCPSolver ( ) const
inherited

Get LCP solver.

◆ getNumConstraints()

std::size_t dart::constraint::ConstraintSolver::getNumConstraints ( ) const
inherited

Returns the number of constraints that was manually added to this ConstraintSolver.

◆ getSecondaryBoxedLcpSolver()

ConstBoxedLcpSolverPtr dart::constraint::BoxedLcpConstraintSolver::getSecondaryBoxedLcpSolver ( ) const

Returns boxed LCP (BLCP) solver that is used when the primary solver failed.

◆ getSkeletons()

const std::vector< SkeletonPtr > & dart::constraint::ConstraintSolver::getSkeletons ( ) const
inherited

Returns all the skeletons added to this ConstraintSolver.

◆ getTimeStep()

double dart::constraint::ConstraintSolver::getTimeStep ( ) const
inherited

Get time step.

◆ isSoftContact()

bool dart::constraint::ConstraintSolver::isSoftContact ( const collision::Contact contact) const
protectedinherited

Return true if at least one of colliding body is soft body.

◆ isSymmetric() [1/2]

bool dart::constraint::BoxedLcpConstraintSolver::isSymmetric ( std::size_t  n,
double *  A 
)
private

Return true if the matrix is symmetric.

◆ isSymmetric() [2/2]

bool dart::constraint::BoxedLcpConstraintSolver::isSymmetric ( std::size_t  n,
double *  A,
std::size_t  begin,
std::size_t  end 
)
private

Return true if the diagonla block of matrix is symmetric.

◆ print()

void dart::constraint::BoxedLcpConstraintSolver::print ( std::size_t  n,
double *  A,
double *  x,
double *  lo,
double *  hi,
double *  b,
double *  w,
int *  findex 
)
private

Print debug information.

◆ removeAllConstraints()

void dart::constraint::ConstraintSolver::removeAllConstraints ( )
inherited

Remove all constraints.

◆ removeAllSkeletons()

void dart::constraint::ConstraintSolver::removeAllSkeletons ( )
inherited

Remove all skeletons in this constraint solver.

◆ removeConstraint()

void dart::constraint::ConstraintSolver::removeConstraint ( const ConstraintBasePtr constraint)
inherited

Remove a constraint.

◆ removeSkeleton()

void dart::constraint::ConstraintSolver::removeSkeleton ( const dynamics::SkeletonPtr skeleton)
inherited

Remove single skeleton.

◆ removeSkeletons()

void dart::constraint::ConstraintSolver::removeSkeletons ( const std::vector< dynamics::SkeletonPtr > &  skeletons)
inherited

Remove multiple skeletons.

◆ setBoxedLcpSolver()

void dart::constraint::BoxedLcpConstraintSolver::setBoxedLcpSolver ( BoxedLcpSolverPtr  lcpSolver)

Sets boxed LCP (BLCP) solver.

Parameters
[in]lcpSolverThe primary boxed LCP solver. When nullptr is passed, Dantzig solver will be used.

◆ setCollisionDetector() [1/2]

void dart::constraint::ConstraintSolver::setCollisionDetector ( collision::CollisionDetector collisionDetector)
inherited

Set collision detector.

This function acquires ownership of the CollisionDetector passed as an argument. This method is deprecated in favor of the overload that accepts a std::shared_ptr.

◆ setCollisionDetector() [2/2]

void dart::constraint::ConstraintSolver::setCollisionDetector ( const std::shared_ptr< collision::CollisionDetector > &  collisionDetector)
inherited

Set collision detector.

◆ setFromOtherConstraintSolver()

void dart::constraint::ConstraintSolver::setFromOtherConstraintSolver ( const ConstraintSolver other)
virtualinherited

Sets this constraint solver using other constraint solver.

All the properties and registered skeletons and constraints will be copied over.

◆ setLCPSolver()

void dart::constraint::ConstraintSolver::setLCPSolver ( std::unique_ptr< LCPSolver lcpSolver)
inherited

Set LCP solver.

◆ setSecondaryBoxedLcpSolver()

void dart::constraint::BoxedLcpConstraintSolver::setSecondaryBoxedLcpSolver ( BoxedLcpSolverPtr  lcpSolver)

Sets boxed LCP (BLCP) solver that is used when the primary solver failed.

◆ setTimeStep()

void dart::constraint::ConstraintSolver::setTimeStep ( double  _timeStep)
virtualinherited

Set time step.

◆ solve()

void dart::constraint::ConstraintSolver::solve ( )
inherited

Solve constraint impulses and apply them to the skeletons.

◆ solveConstrainedGroup()

void dart::constraint::BoxedLcpConstraintSolver::solveConstrainedGroup ( ConstrainedGroup group)
overrideprotectedvirtual

◆ solveConstrainedGroups()

void dart::constraint::ConstraintSolver::solveConstrainedGroups ( )
protectedinherited

Solve constrained groups.

◆ updateConstraints()

void dart::constraint::ConstraintSolver::updateConstraints ( )
protectedinherited

Update constraints.

Member Data Documentation

◆ mA

Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> dart::constraint::BoxedLcpConstraintSolver::mA
protected

Cache data for boxed LCP formulation.

◆ mABackup

Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> dart::constraint::BoxedLcpConstraintSolver::mABackup
protected

Cache data for boxed LCP formulation.

◆ mActiveConstraints

std::vector<ConstraintBasePtr> dart::constraint::ConstraintSolver::mActiveConstraints
protectedinherited

Active constraints.

◆ mB

Eigen::VectorXd dart::constraint::BoxedLcpConstraintSolver::mB
protected

Cache data for boxed LCP formulation.

◆ mBBackup

Eigen::VectorXd dart::constraint::BoxedLcpConstraintSolver::mBBackup
protected

Cache data for boxed LCP formulation.

◆ mBoxedLcpSolver

BoxedLcpSolverPtr dart::constraint::BoxedLcpConstraintSolver::mBoxedLcpSolver
protected

Boxed LCP solver.

◆ mCollisionDetector

collision::CollisionDetectorPtr dart::constraint::ConstraintSolver::mCollisionDetector
protectedinherited

Collision detector.

◆ mCollisionGroup

collision::CollisionGroupPtr dart::constraint::ConstraintSolver::mCollisionGroup
protectedinherited

Collision group.

◆ mCollisionOption

collision::CollisionOption dart::constraint::ConstraintSolver::mCollisionOption
protectedinherited

Collision detection option.

◆ mCollisionResult

collision::CollisionResult dart::constraint::ConstraintSolver::mCollisionResult
protectedinherited

Last collision checking result.

◆ mConstrainedGroups

std::vector<ConstrainedGroup> dart::constraint::ConstraintSolver::mConstrainedGroups
protectedinherited

Constraint group list.

◆ mContactConstraints

std::vector<ContactConstraintPtr> dart::constraint::ConstraintSolver::mContactConstraints
protectedinherited

Contact constraints those are automatically created.

◆ mFIndex

Eigen::VectorXi dart::constraint::BoxedLcpConstraintSolver::mFIndex
protected

Cache data for boxed LCP formulation.

◆ mFIndexBackup

Eigen::VectorXi dart::constraint::BoxedLcpConstraintSolver::mFIndexBackup
protected

Cache data for boxed LCP formulation.

◆ mHi

Eigen::VectorXd dart::constraint::BoxedLcpConstraintSolver::mHi
protected

Cache data for boxed LCP formulation.

◆ mHiBackup

Eigen::VectorXd dart::constraint::BoxedLcpConstraintSolver::mHiBackup
protected

Cache data for boxed LCP formulation.

◆ mJointCoulombFrictionConstraints

std::vector<JointCoulombFrictionConstraintPtr> dart::constraint::ConstraintSolver::mJointCoulombFrictionConstraints
protectedinherited

Joint Coulomb friction constraints those are automatically created.

◆ mJointLimitConstraints

std::vector<JointLimitConstraintPtr> dart::constraint::ConstraintSolver::mJointLimitConstraints
protectedinherited

Joint limit constraints those are automatically created.

◆ mLo

Eigen::VectorXd dart::constraint::BoxedLcpConstraintSolver::mLo
protected

Cache data for boxed LCP formulation.

◆ mLoBackup

Eigen::VectorXd dart::constraint::BoxedLcpConstraintSolver::mLoBackup
protected

Cache data for boxed LCP formulation.

◆ mManualConstraints

std::vector<ConstraintBasePtr> dart::constraint::ConstraintSolver::mManualConstraints
protectedinherited

Constraints that manually added.

◆ mMimicMotorConstraints

std::vector<MimicMotorConstraintPtr> dart::constraint::ConstraintSolver::mMimicMotorConstraints
protectedinherited

Mimic motor constraints those are automatically created.

◆ mOffset

Eigen::VectorXi dart::constraint::BoxedLcpConstraintSolver::mOffset
protected

Cache data for boxed LCP formulation.

◆ mSecondaryBoxedLcpSolver

BoxedLcpSolverPtr dart::constraint::BoxedLcpConstraintSolver::mSecondaryBoxedLcpSolver
protected

Boxed LCP solver to be used when the primary solver failed.

◆ mServoMotorConstraints

std::vector<ServoMotorConstraintPtr> dart::constraint::ConstraintSolver::mServoMotorConstraints
protectedinherited

Servo motor constraints those are automatically created.

◆ mSkeletons

std::vector<dynamics::SkeletonPtr> dart::constraint::ConstraintSolver::mSkeletons
protectedinherited

Skeleton list.

◆ mSoftContactConstraints

std::vector<SoftContactConstraintPtr> dart::constraint::ConstraintSolver::mSoftContactConstraints
protectedinherited

Soft contact constraints those are automatically created.

◆ mTimeStep

double dart::constraint::ConstraintSolver::mTimeStep
protectedinherited

Time step.

◆ mW

Eigen::VectorXd dart::constraint::BoxedLcpConstraintSolver::mW
protected

Cache data for boxed LCP formulation.

◆ mX

Eigen::VectorXd dart::constraint::BoxedLcpConstraintSolver::mX
protected

Cache data for boxed LCP formulation.

◆ mXBackup

Eigen::VectorXd dart::constraint::BoxedLcpConstraintSolver::mXBackup
protected

Cache data for boxed LCP formulation.