Description
Mate constraint of parallel type.
This link corresponds to the typical axis-is-parallel-to-axis (or edge to edge, etc.) mating used in 3D CAD assemblies. The axes to be kept parallel are the two Z axes of the two frames.
#include <ChLinkMate.h>


Public Member Functions | |
| ChLinkMateParallel (const ChLinkMateParallel &other) | |
| virtual ChLinkMateParallel * | Clone () const override |
| "Virtual" copy constructor (covariant return type). | |
| void | SetFlipped (bool doflip) |
| Tell if the two axes must be opposed (flipped=true) or must have the same verse (flipped=false) | |
| bool | IsFlipped () const |
| virtual void | Initialize (std::shared_ptr< ChBodyFrame > body1, std::shared_ptr< ChBodyFrame > body2, bool pos_are_relative, const ChVector3d &point1, const ChVector3d &point2, const ChVector3d &dir1, const ChVector3d &dir2) override |
| Specialized initialization for parallel mate, given the two bodies to be connected, two points and two directions (each expressed in body or abs. | |
| 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::ChLinkMateGeneric | |
| ChLinkMateGeneric (bool mc_x=true, bool mc_y=true, bool mc_z=true, bool mc_rx=true, bool mc_ry=true, bool mc_rz=true) | |
| ChLinkMateGeneric (const ChLinkMateGeneric &other) | |
| 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. | |
| virtual ChFramed | GetFrame1Rel () const override |
| Get the link frame 1, relative to body 1. | |
| virtual ChFramed | GetFrame2Rel () const override |
| Get the link frame 2, relative to body 2. | |
| bool | IsConstrainedX () const |
| bool | IsConstrainedY () const |
| bool | IsConstrainedZ () const |
| bool | IsConstrainedRx () const |
| bool | IsConstrainedRy () const |
| bool | IsConstrainedRz () const |
| void | SetConstrainedCoords (bool mc_x, bool mc_y, bool mc_z, bool mc_rx, bool mc_ry, bool mc_rz) |
| Sets which movements (of frame 1 respect to frame 2) are constrained. | |
| virtual void | Initialize (std::shared_ptr< ChBodyFrame > body1, std::shared_ptr< ChBodyFrame > body2, ChFrame<> absframe) |
| Initialize the link given the two bodies to be connected and the absolute position of the link. | |
| virtual void | Initialize (std::shared_ptr< ChBodyFrame > body1, std::shared_ptr< ChBodyFrame > body2, bool pos_are_relative, ChFrame<> frame1, ChFrame<> frame2) |
| Initialize the link given the two bodies to be connected and two frames (either referring to absolute or body coordinates) in which the link must be placed. | |
| virtual void | SetDisabled (bool mdis) override |
| Enable/disable all the constraint of the link as desired. | |
| virtual void | SetBroken (bool mon) override |
| Set this link as 'broken'. | |
| void | SetUseTangentStiffness (bool useKc) |
| Enable/disable calculation of the tangent stiffness matrix (Kc) of this constraint (default: false). | |
| virtual unsigned int | GetNumConstraints () override |
| Get the number of scalar constraints. | |
| virtual unsigned int | GetNumConstraintsBilateral () override |
| Get the number of bilateral scalar constraints. | |
| virtual unsigned int | GetNumConstraintsUnilateral () override |
| Get the number of unilateral scalar constraints. | |
| virtual ChVectorDynamic | GetConstraintViolation () const override |
| Link violation (residuals of the link constraint equations). | |
Public Member Functions inherited from chrono::ChLinkMate | |
| ChLinkMate (const ChLinkMate &other) | |
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 | UpdateTime (double mytime) |
| Given new time, current body state, update time-dependent quantities in link state, for example motion laws, moving markers, etc. | |
| virtual void | Update (bool update_assets=true) override |
| As above, but with current time. | |
| 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. | |
| 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. | |
| virtual bool | IsRequiringWaking () |
| Tells if this link requires that the connected ChBody objects must be waken if they are sleeping. | |
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(). | |
| void | AddVisualModel (std::shared_ptr< ChVisualModel > model) |
| Add an (optional) visualization model. | |
| std::shared_ptr< ChVisualModel > | GetVisualModel () const |
| Access the visualization model (if any). | |
| void | AddVisualShape (std::shared_ptr< ChVisualShape > shape, const ChFrame<> &frame=ChFrame<>()) |
| Add the specified visual shape to the visualization model. | |
| std::shared_ptr< ChVisualShape > | GetVisualShape (unsigned int i) const |
| Access the specified visualization shape in the visualization model (if any). | |
| void | AddVisualShapeFEA (std::shared_ptr< ChVisualShapeFEA > shapeFEA) |
| Add the specified FEA visualization object to the visualization model. | |
| std::shared_ptr< ChVisualShapeFEA > | GetVisualShapeFEA (unsigned int i) const |
| Access the specified FEA visualization object in the visualization model (if any). | |
| virtual unsigned int | GetNumVisualModelClones () const |
| Return the number of clones of the visual model associated with this physics item. | |
| void | AddCamera (std::shared_ptr< ChCamera > camera) |
| Attach a ChCamera to this physical item. | |
| std::vector< std::shared_ptr< ChCamera > > | GetCameras () const |
| Get the set of cameras attached to this physics item. | |
| virtual bool | IsCollisionEnabled () const |
| Tell if the object is subject to collision. | |
| virtual void | AddCollisionModelsToSystem (ChCollisionSystem *coll_sys) const |
| Add to the provided collision system any collision models managed by this physics item. | |
| virtual void | RemoveCollisionModelsFromSystem (ChCollisionSystem *coll_sys) const |
| Remove from the provided collision system any collision models managed by this physics item. | |
| virtual void | SyncCollisionModels () |
| Synchronize the position and bounding box of any collsion models managed by this physics item. | |
| virtual ChAABB | GetTotalAABB () |
| Get the entire AABB axis-aligned bounding box of the object. | |
| virtual void | GetCenter (ChVector3d &mcenter) |
| Get a symbolic 'center' of the object. | |
| virtual void | Setup () |
| This might recompute the number of coordinates, DOFs, constraints, in case this might change (ex in ChAssembly), as well as state offsets of contained items (ex in ChMesh) | |
| virtual void | ForceToRest () |
| Set zero speed (and zero accelerations) in state, without changing the position. | |
| virtual unsigned int | GetNumCoordsPosLevel () |
| Get the number of coordinates at the position level. | |
| virtual unsigned int | GetNumCoordsVelLevel () |
| Get the number of coordinates at the velocity level. | |
| 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. | |
| 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. | |
| virtual void | IntStateGatherAcceleration (const unsigned int off_a, ChStateDelta &a) |
| From item's state acceleration to global acceleration vector. | |
| virtual void | IntStateScatterAcceleration (const unsigned int off_a, const ChStateDelta &a) |
| From global acceleration vector to item's state acceleration. | |
| 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. | |
| 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. | |
| virtual void | IntLoadResidual_F (const unsigned int off, ChVectorDynamic<> &R, const double c) |
| Takes the F force term, scale and adds to R at given offset: R += c*F. | |
| 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. | |
| 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. | |
| virtual void | InjectVariables (ChSystemDescriptor &descriptor) |
| Register with the given system descriptor any ChVariable objects associated with this item. | |
| 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. | |
| virtual void | VariablesFbIncrementMq () |
| Adds M*q (masses multiplied current 'qb') to Fb, ex. | |
| virtual void | VariablesQbSetSpeed (double step=0) |
| Fetches the item speed (ex. | |
| virtual void | VariablesQbIncrementPosition (double step) |
| Increment item positions by the 'qb' part of the ChVariables, multiplied by a 'step' factor. | |
| virtual void | ConstraintsBiLoad_Qc (double factor=1) |
| 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 | ConstraintsFbLoadForces (double factor=1) |
| Adds the current link-forces, if any, (caused by springs, etc.) to the 'fb' vectors of the ChVariables referenced by encapsulated ChConstraints. | |
Public Member Functions inherited from chrono::ChObj | |
| ChObj (const ChObj &other) | |
| int | GetIdentifier () const |
| Get the unique integer identifier of this object. | |
| void | SetTag (int tag) |
| Set an object integer tag (default: -1). | |
| 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. | |
| virtual std::string & | ArchiveContainerName () |
Protected Attributes | |
| bool | m_flipped |
Protected Attributes inherited from chrono::ChLinkMateGeneric | |
| ChFrame | frame1 |
| ChFrame | frame2 |
| bool | c_x |
| bool | c_y |
| bool | c_z |
| bool | c_rx |
| bool | c_ry |
| bool | c_rz |
| int | m_num_constr |
| number of constraints | |
| int | m_num_constr_bil |
| number of bilateral constraints | |
| int | m_num_constr_uni |
| number of unilateral constraints | |
| ChLinkMask | mask |
| ChConstraintVectorX | C |
| residuals | |
| ChMatrix33 | P |
| projection matrix from Lagrange multiplier to reaction torque | |
| ChVector3d | gamma_f |
| translational Lagrange multipliers | |
| ChVector3d | gamma_m |
| rotational Lagrange multipliers | |
| std::unique_ptr< ChKRMBlock > | Kmatr = nullptr |
| the tangent stiffness matrix of constraint | |
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 | |
| std::shared_ptr< ChVisualModelInstance > | vis_model_instance |
| instantiated visualization model | |
| std::vector< std::shared_ptr< ChCamera > > | cameras |
| set of cameras | |
| 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 | |
Additional Inherited Members | |
Public Types inherited from chrono::ChLinkMateGeneric | |
| using | ChConstraintVectorX = Eigen::Matrix<double, Eigen::Dynamic, 1, Eigen::ColMajor, 6, 1> |
Protected Member Functions inherited from chrono::ChLinkMateGeneric | |
| void | SetupLinkMask () |
| void | ChangedLinkMask () |
| virtual void | Update (double mtime, bool update_assets=true) override |
| Update link state, constraint Jacobian, and frames. | |
| virtual void | IntStateGatherReactions (const unsigned int off_L, ChVectorDynamic<> &L) override |
| From item's reaction forces to global reaction vector. | |
| virtual void | IntStateScatterReactions (const unsigned int off_L, const ChVectorDynamic<> &L) override |
| From global reaction vector to item's reaction forces. | |
| 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. | |
| 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. | |
| 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. | |
| 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: | |
| 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: | |
| 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 | 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. | |
| virtual void | InjectKRMMatrices (ChSystemDescriptor &descriptor) override |
| Register with the given system descriptor any ChKRMBlock objects associated with this item. | |
| virtual void | LoadKRMMatrices (double Kfactor, double Rfactor, double Mfactor) override |
| Add the current stiffness K matrix in encapsulated ChKRMBlock item(s), if any. | |
Protected Member Functions inherited from chrono::ChObj | |
| int | GenerateUniqueIdentifier () |
Member Function Documentation
◆ ArchiveIn()
|
overridevirtual |
Method to allow deserialization of transient data from archives.
Method to allow de serialization of transient data from archives.
Reimplemented from chrono::ChLinkMateGeneric.
◆ ArchiveOut()
|
overridevirtual |
Method to allow serialization of transient data to archives.
Reimplemented from chrono::ChLinkMateGeneric.
◆ Clone()
|
inlineoverridevirtual |
"Virtual" copy constructor (covariant return type).
Reimplemented from chrono::ChLinkMateGeneric.
◆ Initialize()
|
overridevirtual |
Specialized initialization for parallel mate, given the two bodies to be connected, two points and two directions (each expressed in body or abs.
coordinates).
- Parameters
-
body1 first body to link body2 second body to link pos_are_relative true: following pos. are relative to bodies point1 point on slave axis 1 (rel. or abs.) point2 point on master axis 2 (rel. or abs.) dir1 direction of slave axis 1 (rel. or abs.) dir2 direction of master axis 2 (rel. or abs.)
Reimplemented from chrono::ChLinkMateGeneric.
The documentation for this class was generated from the following files:
- C:/M/B/src/chrono-9.0.1/src/chrono/physics/ChLinkMate.h
- C:/M/B/src/chrono-9.0.1/src/chrono/physics/ChLinkMate.cpp
Public Member Functions inherited from