In file /home/blah/darwin2k/src/dyno/mechanism/dynoConstraint.h:

class constraint

base class for dynamic constraints.

Inheritance:


Public Fields

[more]mechanism* mech
mechanism owning the contraint
[more]ptrList* otherMechs
other mechanisms, if any (NULL if not)
[more]linkForceRecord* frec
linked list of applied forces.
[more]matrix Jc
Jacobian; converts joint-space to constraint-space
[more]double cDotTol
tolerance on constraint time derivative
[more]vector C
constraint value
[more]vector Cdot
constraint time derivative
[more]int jdirty
0 = jacobian up-to-date, 1 = not
[more]int* _hasPosLimit
does dimension d have a +ve force limit?
[more]double* maxForce
maximum +ve force for dimension d
[more]double* minForce
NOTE: this should only be non-null for bconstraints
[more]vector prevF
previous constraint force
[more]int eindex
starting index in eq constraint (h) vector
[more]int iindex
starting index in ineq constraint (g) vector
[more]int fdindex
starting index in fd (donlp force vector)
[more]int inSystem
indicates whether the constraint is in a system
[more]double kp
position coefficient for computing corrective accelerations
[more]double kv
velocity coefficient for computing corrective accelerations

Public Methods

[more]inline int index(void) const
returns the starting index of the constraint in the constraintSolver
[more]virtual int correctDrift(int i) const = 0
Indicates whether a corrective force should be computed and applied for dimension i.
[more]inline virtual double computeCorrection(int i, int includeVel)
Computes a corrective acceleration for dimension i.
[more]inline virtual int hasPosLimit(int i) const
Returns 1 if the specified dimension has a positive force limit
[more]inline virtual int hasNegLimit(int i) const
returns 1 if the specified dimension has a negative force limit.
[more]inline virtual int hasForceLimits(void) const
Returns 1 if the constraint has any force limits (positive or negative).
[more]inline virtual void allocatePosLimits(void)
Allocates variables for constraints with positive force limits.
[more]virtual void print(int printVal = 0) = 0
Prints the sval, in symbolic form (if printVal == 0) or numeric form (if printVal = 1).
[more]virtual int createConstraintEquations(void) = 0
Creates the s-val constraint equations for the constraint.
[more]virtual int deleteConstraintEquations(void) = 0
Removes constraint equations from the system of dynamic equations.
[more]virtual int setDynamicValues(void) = 0
Sets the constant terms for the constraint's s-val equations.
[more]virtual const double* getCoefficients(int whichDof) const = 0
returns an array of constraint coefficients.
[more]virtual int resize(int newSize) = 0
resizes the s-val equations for a system with 'newSize' acceleration variables.
[more]virtual int setDirtyFlags(void) = 0
sets the dirty flag for the constraint's s-val equations.
[more]virtual int updateFlags(void) = 0
updates flags for s-val equations when the dynamic equations have changed.
[more]inline virtual int isBilateral(void) const
returns 1 if the constraint is bilateral and 0 otherwise
[more]inline virtual int isFrictional(int i) const
convencience function for determining if the i'th constraint dimension is a frictional condition
[more]virtual int eval(int onlyConst = 0) = 0
evaluates the s-val constraint equations.
[more]inline virtual double computeFStep(vector &a, vector &da, vector &f, vector &df, int i)
computes the stepsize that will satisfy force conditions.
[more]inline virtual double computeAStep(vector &a, vector &da, vector &f, vector &df, int i)
computes the stepsize that will satisfy acceleration conditions.
[more]virtual int satisfied(const vector &a, const vector &f, int j) = 0
indicates whether the constraint's j'th acceleration condition is satisfied
[more]inline virtual int needsImpulse(int i)
indicates whether the i'th constraint dimension needs an impulse to satisfy its constraint.
[more]int computeJacobian(void)
computes the mapping from constraint forces to joint torques.
[more]virtual int violated(void) = 0
returns 1 if a constraint's positional conditions are violated (eg if a joint is past its min or max value
[more]virtual int applyToMech(mechanism* m, int subtract = 0)
this applies the constraint's force to the mechanism by using mechanism::applyForce().
[more]int getGeneralizedForce(vector &gf)
returns the generalized force computed by the constraint.
[more]virtual const linkForceRecord* getForces(void) = 0
computes the forces applied by the constraint (from either mech->cs->f or mech->accF) and returns a linked list of linkForceRecords, one for each force applied.


Inherited from dynoObject:

Public Fields

odynamicSystem* ds
oint active
oint stateSize

Public Methods

oinline virtual int getState(double* state)
oinline virtual int setState(const double* state)
oinline virtual int reset(void)


Inherited from synObject:

Public Fields

ostatic int staticClassID
oint objectID
oint verboseLevel

Public Methods

ovirtual const char* className(void) const
ovirtual synObject* copy(void) const
ovirtual int isOfType(int typeNum, int derivedOk)
ostatic int setStaticClassID(void)
ovirtual int classID(void) const


Documentation

base class for dynamic constraints. The constraint class is used to create dynamic constraints on mechanisms. Constraints restrict the motion of a mechanism by ensuring that the first and second derivatives of a constraint equation are zero. There are two general classes of constraints: bilateral constraints and unilateral constraints (represented by the classes bconstraint and uconstraint, respectively). The constraint equations for bilateral constraints are of the form
 C(t) = 0
 
while unilateral constraints are of the form
 C(t) >= 0
 
An example of a bilateral constraint is a mechanism with a closed kinematic chain, while a joint limit is a unilateral constraint. Unilateral constraints are much trickier (and more computationally expensive) to deal with than bilateral constraints.

From a usage point of view, you simply create a constraint and then call dynamicSystem::addConstraint(). Note that the mechanism(s) which are acted on by the constraint must already belong to a dynamicSystem before you call addConstraint()--otherwise, the constraint won't know what system to add itself to. If you wish to delete a constraint, use dynamicSystem::deleteConstraint. If you only wish to temporarily deactivate a constraint, set its 'active' member to 0. Constraints are associated with mechanisms, and if you do not explicitly remove and delete a constraint, the mechanism will do it automatically when you delete the mechanism. Note that you can only create constraints with the new operator; you can't declare static, global, or automatic constraints. (This is enforced by having a protected destructor.)

Creating new constraint classes is more involved, and unfortunately I don't have time to write about it right now! In the meantime, look at the source for one of the derived classes to get you on your way.

Random notes:

omechanism* mech
mechanism owning the contraint

optrList* otherMechs
other mechanisms, if any (NULL if not)

olinkForceRecord* frec
linked list of applied forces. Allocated and set by getForces

omatrix Jc
Jacobian; converts joint-space to constraint-space

odouble cDotTol
tolerance on constraint time derivative

ovector C
constraint value

ovector Cdot
constraint time derivative

oint jdirty
0 = jacobian up-to-date, 1 = not

oint* _hasPosLimit
does dimension d have a +ve force limit?

odouble* maxForce
maximum +ve force for dimension d

odouble* minForce
NOTE: this should only be non-null for bconstraints

ovector prevF
previous constraint force

oint eindex
starting index in eq constraint (h) vector

oint iindex
starting index in ineq constraint (g) vector

oint fdindex
starting index in fd (donlp force vector)

oint inSystem
indicates whether the constraint is in a system

odouble kp
position coefficient for computing corrective accelerations

odouble kv
velocity coefficient for computing corrective accelerations

oinline int index(void) const
returns the starting index of the constraint in the constraintSolver

ovirtual int correctDrift(int i) const = 0
Indicates whether a corrective force should be computed and applied for dimension i. Derived classes must override this method.

oinline virtual double computeCorrection(int i, int includeVel)
Computes a corrective acceleration for dimension i. A velocity-dependent term is included if includeVel is non-zero.

oinline virtual int hasPosLimit(int i) const
Returns 1 if the specified dimension has a positive force limit

oinline virtual int hasNegLimit(int i) const
returns 1 if the specified dimension has a negative force limit. This should never be true for unilateral constraints.

oinline virtual int hasForceLimits(void) const
Returns 1 if the constraint has any force limits (positive or negative). NOTE: if a derived class has a negative force limit, or has a positive force limit but does not use _hasPosLimit, then this function should be supplied by the derived class!

oinline virtual void allocatePosLimits(void)
Allocates variables for constraints with positive force limits. If the constraint will have any positive force limits, this function should be called to allocate the appropriate arrays. NOTE: only call this function if the constraint will actually be using the force limits

ovirtual void print(int printVal = 0) = 0
Prints the sval, in symbolic form (if printVal == 0) or numeric form (if printVal = 1). Derived classes must override this method.

ovirtual int createConstraintEquations(void) = 0
Creates the s-val constraint equations for the constraint. Derived classes must override this method.

ovirtual int deleteConstraintEquations(void) = 0
Removes constraint equations from the system of dynamic equations. Does not necessarily delete the svals for the equations. Derived classes must override this method.

ovirtual int setDynamicValues(void) = 0
Sets the constant terms for the constraint's s-val equations. Derived classes must override this method.

ovirtual const double* getCoefficients(int whichDof) const = 0
returns an array of constraint coefficients. Typically, this is a pointer to the coefficients of the s-val for the 'whichDof' constraint equation. Derived classes must override this method.

ovirtual int resize(int newSize) = 0
resizes the s-val equations for a system with 'newSize' acceleration variables. NOTE: actual sval size becomes newSize+1; newSize is size of system of equations, but s-vals have an additional entry for constant terms.

ovirtual int setDirtyFlags(void) = 0
sets the dirty flag for the constraint's s-val equations. Derived classes must override this method.

ovirtual int updateFlags(void) = 0
updates flags for s-val equations when the dynamic equations have changed. Derived classes must override this method.

oinline virtual int isBilateral(void) const
returns 1 if the constraint is bilateral and 0 otherwise

oinline virtual int isFrictional(int i) const
convencience function for determining if the i'th constraint dimension is a frictional condition

ovirtual int eval(int onlyConst = 0) = 0
evaluates the s-val constraint equations. Derived classes must override this method.

oinline virtual double computeFStep(vector &a, vector &da, vector &f, vector &df, int i)
computes the stepsize that will satisfy force conditions. Most derived classes do not need to override this method.

oinline virtual double computeAStep(vector &a, vector &da, vector &f, vector &df, int i)
computes the stepsize that will satisfy acceleration conditions. Most derived classes do not need to override this method.

ovirtual int satisfied(const vector &a, const vector &f, int j) = 0
indicates whether the constraint's j'th acceleration condition is satisfied

oinline virtual int needsImpulse(int i)
indicates whether the i'th constraint dimension needs an impulse to satisfy its constraint. This method assumes the constraint is currently active.

oint computeJacobian(void)
computes the mapping from constraint forces to joint torques.

ovirtual int violated(void) = 0
returns 1 if a constraint's positional conditions are violated (eg if a joint is past its min or max value

ovirtual int applyToMech(mechanism* m, int subtract = 0)
this applies the constraint's force to the mechanism by using mechanism::applyForce(). This is useful for re-computing joint loads after constraints have been satisfied, thus enabling structural analysis. This method uses constraint::getForces) to determine the forces that should be applied; derived classes need not override it.

oint getGeneralizedForce(vector &gf)
returns the generalized force computed by the constraint. For bilateral constraints, this can come from mech->accF if there are no active unilateral constraints; otherwise, it comes from mech->cs->f.

ovirtual const linkForceRecord* getForces(void) = 0
computes the forces applied by the constraint (from either mech->cs->f or mech->accF) and returns a linked list of linkForceRecords, one for each force applied. For example, if the constraint is between two links, then there will be two records in the list--one for each of the links to which a constraint force was applied. Callers should not delete the returned record, as it is reused by subsequent calls and will be deleted by the constructor.

Note that derived classes must allocate an array (even if only size 1) of linkForceRecords and assign it to frec in getForces(), as that behavior is expected by applyToMech().


Direct child classes:
uconstraint
bconstraint
Friends:
constraintSolver
mechanism
dynamicSystem

Alphabetic index HTML hierarchy of classes or Java



This page was generated with the help of DOC++.