chrono::ChLinkLockPlanar Class Reference
  Description
Plane-plane joint, with the 'ChLinkLock' formulation.
(allows a simpler creation of a link as a sub-type of ChLinkLock).
#include <ChLinkLock.h>
Inheritance diagram for chrono::ChLinkLockPlanar:

Collaboration diagram for chrono::ChLinkLockPlanar:

Public Member Functions | |
| virtual ChLinkLockPlanar * | Clone () const override | 
| "Virtual" copy constructor (covariant return type).  | |
| void | Lock (bool lock) | 
| Lock the joint.  More... | |
  Public Member Functions inherited from chrono::ChLinkLock | |
| ChLinkLock () | |
| Default constructor. Builds a ChLinkLockSpherical.  | |
| ChLinkLock (const ChLinkLock &other) | |
| Copy constructor.  | |
| virtual void | SetDisabled (bool mdis) override | 
| Enable/disable all constraints of the link.  | |
| virtual void | SetBroken (bool mon) override | 
| For example, a 3rd party software can set the 'broken' status via this method.  | |
| ChLinkMask & | GetMask () | 
| Get the link mask (a container for the ChConstraint items).  | |
| virtual void | SetupMarkers (ChMarker *mark1, ChMarker *mark2) override | 
| Set the two markers associated with this link.  | |
| ChLinkForce & | ForceX () | 
| Accessors for internal forces on free degrees of freedom.  More... | |
| ChLinkForce & | ForceY () | 
| ChLinkForce & | ForceZ () | 
| ChLinkForce & | ForceRx () | 
| ChLinkForce & | ForceRy () | 
| ChLinkForce & | ForceRz () | 
| ChLinkForce & | ForceD () | 
| ChLinkForce & | ForceRp () | 
| ChLinkLimit & | LimitX () | 
| Accessors for limits on free degrees of freedom.  More... | |
| ChLinkLimit & | LimitY () | 
| ChLinkLimit & | LimitZ () | 
| ChLinkLimit & | LimitRx () | 
| ChLinkLimit & | LimitRy () | 
| ChLinkLimit & | LimitRz () | 
| ChLinkLimit & | LimitD () | 
| ChLinkLimit & | LimitRp () | 
| virtual unsigned int | GetNumConstraints () override | 
| Get the number of scalar constraints for this link.  | |
| virtual unsigned int | GetNumConstraintsBilateral () override | 
| Get the number of bilateral constraints for this link.  | |
| virtual unsigned int | GetNumConstraintsUnilateral () override | 
| Get the number of unilateral constraints for this link.  | |
| virtual ChVectorDynamic | GetConstraintViolation () const override | 
| Link violation (residuals of the link constraint equations).  | |
| const ChConstraintVectorX & | GetConstraintViolationDt () const | 
| Time derivatives of link violation.  | |
| const ChConstraintVectorX & | GetConstraintViolationDt2 () const | 
| Second time derivatives of link violation.  | |
| const ChConstraintMatrixX7 & | GetCq1 () const | 
| The jacobian (body n.1 part, i.e. columns= 7 , rows= m_num_constr)  | |
| const ChConstraintMatrixX7 & | GetCq2 () const | 
| The jacobian (body n.2 part, i.e. columns= 7 , rows= m_num_constr)  | |
| const ChConstraintMatrixX6 & | GetCqw1 () const | 
| The jacobian for Wl (col 6, rows= m_num_constr), as [Cqw1_rot]=[Cq_rot]*[Gl_1]'.  | |
| const ChConstraintMatrixX6 & | GetCqw2 () const | 
| The jacobian for Wl (col 6, rows= m_num_constr) as [Cqw2_rot]=[Cq_rot]*[Gl_2]'.  | |
| const ChConstraintVectorX & | GetQc () const | 
| The gamma vector used in dynamics, [Cq]x''=Qc.  | |
| const ChConstraintVectorX & | GetCt () const | 
| The Ct vector used in kinematics, [Cq]x'=Ct.  | |
| const ChConstraintVectorX & | GetReact () const | 
| Access the reaction vector, after dynamics computations.  | |
| virtual void | UpdateTime (double mytime) | 
| Update time-dependent quantities in link state (e.g., motion laws, moving markers, etc.).  | |
| virtual void | UpdateState () | 
| Given current time and body state, computes the constraint differentiation to get the the state matrices Cq1, Cq2, Qc, Ct , and also C, C_dt, C_dtd.  | |
| virtual void | UpdateForces (double time) override | 
| Updates the local F, M forces adding penalties from ChLinkLimit objects, if any.  | |
| void | UpdateCqw () | 
| Updates Cqw1 and Cqw2 given updated Cq1 and Cq2, i.e.  More... | |
| virtual void | Update (double time, bool update_assets) override | 
| Full update.  More... | |
| virtual void | ArchiveOut (ChArchiveOut &archive_out) override | 
| Method to allow serialization of transient data to archives.  | |
| virtual void | ArchiveIn (ChArchiveIn &archive_in) override | 
| Method to allow deserialization of transient data from archives.  | |
  Public Member Functions inherited from chrono::ChLinkMarkers | |
| ChMarker * | GetMarker1 () const | 
| Return the 1st referenced marker (the secondary marker, on 1st body).  | |
| ChMarker * | GetMarker2 () const | 
| Return the 2nd referenced marker (the main marker, on 2nd body).  | |
| virtual ChFrame | GetFrame1Rel () const override | 
| Get the link frame 1, relative to body 1.  More... | |
| virtual ChFrame | GetFrame2Rel () const override | 
| Get the link frame 2, relative to body 2.  More... | |
| const ChCoordsysd & | GetRelCoordsys () const | 
| Relative position of marker 1 respect to marker 2.  | |
| const ChCoordsysd & | GetRelCoordsysDt () const | 
| Relative speed of marker 1 respect to marker 2.  | |
| const ChCoordsysd & | GetRelCoordsysDt2 () const | 
| Relative acceleration of marker 1 respect to marker 2.  | |
| double | GetRelAngle () const | 
| Relative rotation angle of marker 1 respect to marker 2.  | |
| const ChVector3d & | GetRelAxis () const | 
| Relative finite rotation axis of marker 1 respect to marker 2.  | |
| const ChVector3d & | GetRelAngleAxis () const | 
| const ChVector3d & | GetRelativeAngVel () const | 
| Relative angular speed of marker 1 respect to marker 2.  | |
| const ChVector3d & | GetRelativeAngAcc () const | 
| Relative angular acceleration of marker 1 respect to marker 2.  | |
| double | GetDistance () const | 
| Relative 'polar' distance of marker 1 respect to marker 2.  | |
| double | GetDistanceDt () const | 
| Relative speed of marker 1 respect to marker 2, along the polar distance vector.  | |
| const ChVector3d & | GetAccumulatedForce () const | 
| Get the total applied force accumulators (force, momentum) in link coords.  More... | |
| const ChVector3d & | GetAccumulatedTorque () const | 
| virtual void | Initialize (std::shared_ptr< ChMarker > mark1, std::shared_ptr< ChMarker > mark2) | 
| Initialize the link to join two markers.  More... | |
| virtual void | Initialize (std::shared_ptr< ChBody > mbody1, std::shared_ptr< ChBody > mbody2, const ChFrame<> &frame) | 
| Initialize the link to join two rigid bodies.  More... | |
| virtual void | Initialize (std::shared_ptr< ChBody > mbody1, std::shared_ptr< ChBody > mbody2, bool rel_frames, const ChFrame<> &frame1, const ChFrame<> &frame2) | 
| Initialize the link to join two rigid bodies.  More... | |
| virtual ChFrame | GetVisualModelFrame (unsigned int nclone=0) const override | 
| Get the reference frame (expressed in and relative to the absolute frame) of the visual model.  More... | |
| virtual void | UpdateRelMarkerCoords () | 
| Updates auxiliary quantities for all relative degrees of freedom of the two markers.  | |
| virtual void | IntLoadResidual_F (const unsigned int off, ChVectorDynamic<> &R, const double c) override | 
| Adds force to residual R, as R*= F*c NOTE: here the off offset in R is NOT used because add F at the TWO offsets of the two connected bodies, so it is assumed that offsets for Body1 and Body2 variables have been already set properly!  | |
| virtual void | ConstraintsFbLoadForces (double factor=1) override | 
| Overrides the empty behaviour of the parent ChLink implementation, which does not consider any user-imposed force between the two bodies.  More... | |
  Public Member Functions inherited from chrono::ChLink | |
| ChLink (const ChLink &other) | |
| virtual unsigned int | GetNumAffectedCoords () override | 
| Get the number of scalar variables affected by constraints in this link.  | |
| ChBodyFrame * | GetBody1 () const | 
| Get the constrained body 1.  | |
| ChBodyFrame * | GetBody2 () const | 
| Get the constrained body 2.  | |
| virtual ChFramed | GetFrame1Abs () const override | 
| Get the link frame 1, on body 1, expressed in the absolute frame.  | |
| virtual ChFramed | GetFrame2Abs () const override | 
| Get the link frame 2, on body 2, expressed in the absolute frame.  | |
| virtual ChWrenchd | GetReaction1 () const override | 
| Get the reaction force and torque on the 1st body, expressed in the link frame 1.  | |
| virtual ChWrenchd | GetReaction2 () const override | 
| Get the reaction force and torque on the 2nd body object, expressed in the link frame 2.  | |
| virtual void | UpdatedExternalTime (double prevtime, double time) | 
| Called from a external package (i.e. a plugin, a CAD app.) to report that time has changed.  | |
  Public Member Functions inherited from chrono::ChLinkBase | |
| ChLinkBase (const ChLinkBase &other) | |
| bool | IsValid () | 
| Tells if the link data is currently valid.  More... | |
| void | SetValid (bool mon) | 
| Set the status of link validity.  | |
| bool | IsDisabled () | 
| Tells if all constraints of this link are currently turned on or off by the user.  | |
| bool | IsBroken () | 
| Tells if the link is broken, for excess of pulling/pushing.  | |
| virtual bool | IsActive () const override | 
| Return true if the link is currently active and thereofre included into the system solver.  More... | |
| virtual bool | IsRequiringWaking () | 
| Tells if this link requires that the connected ChBody objects must be waken if they are sleeping.  More... | |
  Public Member Functions inherited from chrono::ChPhysicsItem | |
| ChPhysicsItem (const ChPhysicsItem &other) | |
| ChSystem * | GetSystem () const | 
| Get the pointer to the parent ChSystem().  | |
| virtual void | SetSystem (ChSystem *m_system) | 
| Set the pointer to the parent ChSystem().  More... | |
| virtual bool | IsCollisionEnabled () const | 
| Tell if the object is subject to collision.  More... | |
| virtual void | AddCollisionModelsToSystem (ChCollisionSystem *coll_sys) const | 
| Add to the provided collision system any collision models managed by this physics item.  More... | |
| virtual void | RemoveCollisionModelsFromSystem (ChCollisionSystem *coll_sys) const | 
| Remove from the provided collision system any collision models managed by this physics item.  More... | |
| virtual void | SyncCollisionModels () | 
| Synchronize the position and bounding box of any collision models managed by this physics item.  | |
| virtual ChAABB | GetTotalAABB () const | 
| Get the axis-aligned bounding box (AABB) of this object.  More... | |
| virtual ChVector3d | GetCenter () const | 
| Get a symbolic 'center' of the object.  More... | |
| virtual void | Setup () | 
| Perform setup operations.  More... | |
| virtual void | ForceToRest () | 
| Set zero speed (and zero accelerations) in state, without changing the position.  More... | |
| virtual unsigned int | GetNumCoordsPosLevel () | 
| Get the number of coordinates at the position level.  More... | |
| virtual unsigned int | GetNumCoordsVelLevel () | 
| Get the number of coordinates at the velocity level.  More... | |
| unsigned int | GetOffset_x () | 
| Get offset in the state vector (position part)  | |
| unsigned int | GetOffset_w () | 
| Get offset in the state vector (speed part)  | |
| unsigned int | GetOffset_L () | 
| Get offset in the lagrangian multipliers.  | |
| void | SetOffset_x (const unsigned int moff) | 
| Set offset in the state vector (position part) Note: only the ChSystem::Setup function should use this.  | |
| void | SetOffset_w (const unsigned int moff) | 
| Set offset in the state vector (speed part) Note: only the ChSystem::Setup function should use this.  | |
| void | SetOffset_L (const unsigned int moff) | 
| Set offset in the lagrangian multipliers Note: only the ChSystem::Setup function should use this.  | |
| virtual void | IntStateGather (const unsigned int off_x, ChState &x, const unsigned int off_v, ChStateDelta &v, double &T) | 
| From item's state to global state vectors y={x,v} pasting the states at the specified offsets.  More... | |
| virtual void | IntStateScatter (const unsigned int off_x, const ChState &x, const unsigned int off_v, const ChStateDelta &v, const double T, bool full_update) | 
| From global state vectors y={x,v} to item's state (and update) fetching the states at the specified offsets.  More... | |
| virtual void | IntStateGatherAcceleration (const unsigned int off_a, ChStateDelta &a) | 
| From item's state acceleration to global acceleration vector.  More... | |
| virtual void | IntStateScatterAcceleration (const unsigned int off_a, const ChStateDelta &a) | 
| From global acceleration vector to item's state acceleration.  More... | |
| virtual void | IntStateIncrement (const unsigned int off_x, ChState &x_new, const ChState &x, const unsigned int off_v, const ChStateDelta &Dv) | 
| Computes x_new = x + Dt , using vectors at specified offsets.  More... | |
| virtual void | IntStateGetIncrement (const unsigned int off_x, const ChState &x_new, const ChState &x, const unsigned int off_v, ChStateDelta &Dv) | 
| Computes Dt = x_new - x, using vectors at specified offsets.  More... | |
| virtual void | IntLoadResidual_Mv (const unsigned int off, ChVectorDynamic<> &R, const ChVectorDynamic<> &w, const double c) | 
| Takes the M*v term, multiplying mass by a vector, scale and adds to R at given offset: R += c*M*w.  More... | |
| virtual void | IntLoadLumpedMass_Md (const unsigned int off, ChVectorDynamic<> &Md, double &err, const double c) | 
| Adds the lumped mass to a Md vector, representing a mass diagonal matrix.  More... | |
| virtual void | InjectVariables (ChSystemDescriptor &descriptor) | 
| Register with the given system descriptor any ChVariable objects associated with this item.  | |
| virtual void | InjectKRMMatrices (ChSystemDescriptor &descriptor) | 
| Register with the given system descriptor any ChKRMBlock objects associated with this item.  | |
| virtual void | LoadKRMMatrices (double Kfactor, double Rfactor, double Mfactor) | 
| Compute and load current stiffnes (K), damping (R), and mass (M) matrices in encapsulated ChKRMBlock objects.  More... | |
| virtual void | VariablesFbReset () | 
| Sets the 'fb' part (the known term) of the encapsulated ChVariables to zero.  | |
| virtual void | VariablesFbLoadForces (double factor=1) | 
| Adds the current forces (applied to item) into the encapsulated ChVariables, in the 'fb' part: qf+=forces*factor.  | |
| virtual void | VariablesQbLoadSpeed () | 
| Initialize the 'qb' part of the ChVariables with the current value of speeds.  More... | |
| virtual void | VariablesFbIncrementMq () | 
| Adds M*q (masses multiplied current 'qb') to Fb, ex.  More... | |
| virtual void | VariablesQbSetSpeed (double step=0) | 
| Fetches the item speed (ex.  More... | |
| virtual void | VariablesQbIncrementPosition (double step) | 
| Increment item positions by the 'qb' part of the ChVariables, multiplied by a 'step' factor.  More... | |
  Public Member Functions inherited from chrono::ChObj | |
| ChObj (const ChObj &other) | |
| int | GetIdentifier () const | 
| Get the unique integer identifier of this object.  More... | |
| void | SetTag (int tag) | 
| Set an object integer tag (default: -1).  More... | |
| int | GetTag () const | 
| Get the tag of this object.  | |
| void | SetName (const std::string &myname) | 
| Set the name of this object.  | |
| const std::string & | GetName () const | 
| Get the name of this object.  | |
| double | GetChTime () const | 
| Gets the simulation time of this object.  | |
| void | SetChTime (double m_time) | 
| Sets the simulation time of this object.  | |
| void | AddVisualModel (std::shared_ptr< ChVisualModel > model) | 
| Add an (optional) visualization model.  More... | |
| std::shared_ptr< ChVisualModel > | GetVisualModel () const | 
| Access the visualization model (if any).  More... | |
| void | AddVisualShape (std::shared_ptr< ChVisualShape > shape, const ChFrame<> &frame=ChFrame<>()) | 
| Add the specified visual shape to the visualization model.  More... | |
| std::shared_ptr< ChVisualShape > | GetVisualShape (unsigned int i) const | 
| Access the specified visualization shape in the visualization model (if any).  More... | |
| void | AddVisualShapeFEA (std::shared_ptr< ChVisualShapeFEA > shapeFEA) | 
| Add the specified FEA visualization object to the visualization model.  More... | |
| std::shared_ptr< ChVisualShapeFEA > | GetVisualShapeFEA (unsigned int i) const | 
| Access the specified FEA visualization object in the visualization model (if any).  More... | |
| virtual unsigned int | GetNumVisualModelClones () const | 
| Return the number of clones of the visual model associated with this object.  More... | |
| void | AddCamera (std::shared_ptr< ChCamera > camera) | 
| Attach a camera to this object.  More... | |
| std::vector< std::shared_ptr< ChCamera > > | GetCameras () const | 
| Get the set of cameras attached to this object.  | |
| void | UpdateVisualModel () | 
| Utility function to update only the associated visual assets (if any).  | |
| virtual std::string & | ArchiveContainerName () | 
Additional Inherited Members | |
  Public Types inherited from chrono::ChLinkLock | |
| using | ChConstraintVectorX = Eigen::Matrix< double, Eigen::Dynamic, 1, Eigen::ColMajor, 7, 1 > | 
| using | ChConstraintMatrixX6 = Eigen::Matrix< double, Eigen::Dynamic, BODY_DOF, Eigen::RowMajor, 7, BODY_DOF > | 
| using | ChConstraintMatrixX7 = Eigen::Matrix< double, Eigen::Dynamic, BODY_QDOF, Eigen::RowMajor, 7, BODY_QDOF > | 
  Protected Types inherited from chrono::ChLinkLock | |
| enum | Type {  LOCK, SPHERICAL, POINTPLANE, POINTLINE, CYLINDRICAL, PRISMATIC, PLANEPLANE, OLDHAM, REVOLUTE, FREE, ALIGN, PARALLEL, PERPEND, TRAJECTORY, CLEARANCE, REVOLUTEPRISMATIC }  | 
| Type of link-lock.  | |
  Protected Member Functions inherited from chrono::ChLinkLock | |
| void | BuildLink () | 
| Resize matrices and initializes all mask-dependent quantities.  More... | |
| void | BuildLinkType (Type link_type) | 
| Set the mask and then resize matrices.  | |
| void | BuildLink (bool x, bool y, bool z, bool e0, bool e1, bool e2, bool e3) | 
| void | ChangeType (Type new_link_type) | 
| virtual void | IntStateScatterReactions (const unsigned int off_L, const ChVectorDynamic<> &L) override | 
| From global reaction vector to item's reaction forces.  More... | |
| virtual void | IntStateGatherReactions (const unsigned int off_L, ChVectorDynamic<> &L) override | 
| From item's reaction forces to global reaction vector.  More... | |
| virtual void | IntLoadResidual_CqL (const unsigned int off_L, ChVectorDynamic<> &R, const ChVectorDynamic<> &L, const double c) override | 
| Takes the term Cq'*L, scale and adds to R at given offset: R += c*Cq'*L.  More... | |
| virtual void | IntLoadConstraint_C (const unsigned int off, ChVectorDynamic<> &Qc, const double c, bool do_clamp, double recovery_clamp) override | 
| Takes the term C, scale and adds to Qc at given offset: Qc += c*C.  More... | |
| virtual void | IntLoadConstraint_Ct (const unsigned int off, ChVectorDynamic<> &Qc, const double c) override | 
| Takes the term Ct, scale and adds to Qc at given offset: Qc += c*Ct.  More... | |
| virtual void | IntToDescriptor (const unsigned int off_v, const ChStateDelta &v, const ChVectorDynamic<> &R, const unsigned int off_L, const ChVectorDynamic<> &L, const ChVectorDynamic<> &Qc) override | 
| Prepare variables and constraints to accommodate a solution:  More... | |
| virtual void | IntFromDescriptor (const unsigned int off_v, ChStateDelta &v, const unsigned int off_L, ChVectorDynamic<> &L) override | 
| After a solver solution, fetch values from variables and constraints into vectors:  More... | |
| virtual void | InjectConstraints (ChSystemDescriptor &descriptor) override | 
| Register with the given system descriptor any ChConstraint objects associated with this item.  | |
| virtual void | ConstraintsBiReset () override | 
| Sets to zero the known term (b_i) of encapsulated ChConstraints.  | |
| virtual void | ConstraintsBiLoad_C (double factor=1, double recovery_clamp=0.1, bool do_clamp=false) override | 
| Adds the current C (constraint violation) to the known term (b_i) of encapsulated ChConstraints.  | |
| virtual void | ConstraintsBiLoad_Ct (double factor=1) override | 
| Adds the current Ct (partial t-derivative, as in C_dt=0-> [Cq]*q_dt=-Ct) to the known term (b_i) of encapsulated ChConstraints.  | |
| virtual void | ConstraintsBiLoad_Qc (double factor=1) override | 
| Adds the current Qc (the vector of C_dtdt=0 -> [Cq]*q_dtdt=Qc ) to the known term (b_i) of encapsulated ChConstraints.  | |
| virtual void | LoadConstraintJacobians () override | 
| Compute and load current Jacobians in encapsulated ChConstraint objects.  | |
| virtual void | ConstraintsFetch_react (double factor=1) override | 
| Fetches the reactions from the lagrangian multiplier (l_i) of encapsulated ChConstraints.  More... | |
  Protected Member Functions inherited from chrono::ChLinkMarkers | |
| ChLinkMarkers (const ChLinkMarkers &other) | |
  Protected Member Functions inherited from chrono::ChObj | |
| int | GenerateUniqueIdentifier () | 
  Protected Attributes inherited from chrono::ChLinkLock | |
| Type | type | 
| type of link_lock joint  | |
| ChLinkMaskLF | mask | 
| scalar constraints  | |
| int | m_num_constr | 
| number of degrees of constraint  | |
| int | m_num_constr_bil | 
| number of degrees of constraint (bilateral constraintss)  | |
| int | m_num_constr_uni | 
| number of degrees of constraint (unilateral constraints, excluding joint limits)  | |
| std::unique_ptr< ChLinkForce > | force_D | 
| the force acting on the straight line m1-m2 (distance)  | |
| std::unique_ptr< ChLinkForce > | force_R | 
| the torque acting about rotation axis  | |
| std::unique_ptr< ChLinkForce > | force_X | 
| the force acting along X dof  | |
| std::unique_ptr< ChLinkForce > | force_Y | 
| the force acting along Y dof  | |
| std::unique_ptr< ChLinkForce > | force_Z | 
| the force acting along Z dof  | |
| std::unique_ptr< ChLinkForce > | force_Rx | 
| the torque acting about Rx dof  | |
| std::unique_ptr< ChLinkForce > | force_Ry | 
| the torque acting about Ry dof  | |
| std::unique_ptr< ChLinkForce > | force_Rz | 
| the torque acting about Rz dof  | |
| double | d_restlength | 
| the rest length of the "d_spring" spring  | |
| std::unique_ptr< ChLinkLimit > | limit_X | 
| the upper/lower limits for X dof  | |
| std::unique_ptr< ChLinkLimit > | limit_Y | 
| the upper/lower limits for Y dof  | |
| std::unique_ptr< ChLinkLimit > | limit_Z | 
| the upper/lower limits for Z dof  | |
| std::unique_ptr< ChLinkLimit > | limit_Rx | 
| the upper/lower limits for Rx dof  | |
| std::unique_ptr< ChLinkLimit > | limit_Ry | 
| the upper/lower limits for Ry dof  | |
| std::unique_ptr< ChLinkLimit > | limit_Rz | 
| the upper/lower limits for Rz dof  | |
| std::unique_ptr< ChLinkLimit > | limit_Rp | 
| the polar (conical) limit for "shoulder"rotation  | |
| std::unique_ptr< ChLinkLimit > | limit_D | 
| the polar (conical) limit for "shoulder"rotation  | |
| ChConstraintVectorX | C | 
| C(q,q_dt,t), the constraint violations.  | |
| ChConstraintVectorX | C_dt | 
| Speed constraint violations.  | |
| ChConstraintVectorX | C_dtdt | 
| Acceleration constraint violations.  | |
| ChConstraintMatrixX7 | Cq1 | 
| [Cq1], the jacobian of the constraint, for coords1, [m_num_constr,7]  | |
| ChConstraintMatrixX7 | Cq2 | 
| [Cq2], the jacobian of the constraint, for coords2. [m_num_constr,7]  | |
| ChConstraintMatrixX6 | Cqw1 | 
| Jacobian [m_num_constr,6] for 3 Wl rot.coordinates instead of quaternions.  | |
| ChConstraintMatrixX6 | Cqw2 | 
| Jacobian [m_num_constr,6] for 3 Wl rot.coordinates instead of quaternions.  | |
| ChConstraintVectorX | Q_c | 
| {Qc}, the known part, {Qc}=-{C_dtdt}-([Cq]{q_dt})q-2[Cq_dt]{q_dt}  | |
| ChConstraintVectorX | Ct | 
| partial derivative of the link kin. equation wrt to time  | |
| ChConstraintVectorX | react | 
| {l}, the lagrangians forces in the constraints  | |
| ChMatrixNM< double, 7, BODY_QDOF > | Cq1_temp | 
| ChMatrixNM< double, 7, BODY_QDOF > | Cq2_temp | 
| ChVectorN< double, 7 > | Q_c_temp | 
| ChCoordsysd | Ct_temp | 
  Protected Attributes inherited from chrono::ChLinkMarkers | |
| ChMarker * | marker1 | 
| secondary coordsys  | |
| ChMarker * | marker2 | 
| main coordsys  | |
| ChCoordsysd | relM | 
| relative marker position 2-1  | |
| ChCoordsysd | relM_dt | 
| relative marker speed  | |
| ChCoordsysd | relM_dtdt | 
| relative marker acceleration  | |
| double | relAngle | 
| relative angle of rotation  | |
| ChVector3d | relAxis | 
| relative axis of rotation  | |
| ChVector3d | relRotaxis | 
| relative rotaion vector =angle*axis  | |
| ChVector3d | relWvel | 
| relative angular speed  | |
| ChVector3d | relWacc | 
| relative angular acceleration  | |
| double | dist | 
| the distance between the two origins of markers,  | |
| double | dist_dt | 
| the speed between the two origins of markers  | |
| ChVector3d | C_force | 
| internal force applied by springs/dampers/actuators  | |
| ChVector3d | C_torque | 
| internal torque applied by springs/dampers/actuators  | |
| ChVector3d | PQw | 
| ChVector3d | PQw_dt | 
| ChVector3d | PQw_dtdt | 
| ChQuaternion | q_AD | 
| ChQuaternion | q_BC | 
| ChQuaternion | q_8 | 
| ChVector3d | q_4 | 
  Protected Attributes inherited from chrono::ChLink | |
| ChBodyFrame * | m_body1 | 
| first connected body  | |
| ChBodyFrame * | m_body2 | 
| second connected body  | |
| ChVector3d | react_force | 
| xyz reactions, expressed in local coordinate system of link;  | |
| ChVector3d | react_torque | 
| torque reactions, expressed in local coordinate system of link;  | |
  Protected Attributes inherited from chrono::ChLinkBase | |
| bool | disabled | 
| all constraints of link disabled because of user needs  | |
| bool | valid | 
| link data is valid  | |
| bool | broken | 
| link is broken because of excessive pulling/pushing.  | |
  Protected Attributes inherited from chrono::ChPhysicsItem | |
| ChSystem * | system | 
| parent system  | |
| unsigned int | offset_x | 
| offset in vector of state (position part)  | |
| unsigned int | offset_w | 
| offset in vector of state (speed part)  | |
| unsigned int | offset_L | 
| offset in vector of lagrangian multipliers  | |
  Protected Attributes inherited from chrono::ChObj | |
| double | ChTime | 
| object simulation time  | |
| std::string | m_name | 
| object name  | |
| int | m_identifier | 
| object unique identifier  | |
| int | m_tag | 
| user-supplied tag  | |
| std::shared_ptr< ChVisualModelInstance > | vis_model_instance | 
| instantiated visualization model  | |
| std::vector< std::shared_ptr< ChCamera > > | cameras | 
| set of cameras  | |
Member Function Documentation
◆ Lock()
| void chrono::ChLinkLockPlanar::Lock | ( | bool | lock | ) | 
Lock the joint.
If enabled (lock = true) this effectively converts this joint into a weld joint. If lock = false, the joint reverts to its original degrees of freedom.
The documentation for this class was generated from the following files:
- /builds/uwsbel/chrono/src/chrono/physics/ChLinkLock.h
 - /builds/uwsbel/chrono/src/chrono/physics/ChLinkLock.cpp
 
 Public Member Functions inherited from