Description

Physical system.

This class is used to represent a multibody physical system, so it acts also as a database for most items involved in simulations, most noticeably objects of ChBody and ChLink classes, which are used to represent mechanisms.

Moreover, it also owns some global settings and features, like the gravity acceleration, the global time and so on.

This object will be responsible of performing the entire physical simulation (dynamics, kinematics, statics, etc.), so you need at least one ChSystem object in your program, in order to perform simulations (you'll insert rigid bodies and links into it..)

Note that this is an abstract class, in your code you must create a system from one of the concrete classes: chrono::ChSystemNSC (for non-smooth contacts) or chrono::ChSystemSMC (for smooth 'penalty' contacts).

Further info at the Simulation system manual page.

#include <ChSystem.h>

Inheritance diagram for chrono::ChSystem:
Collaboration diagram for chrono::ChSystem:

Classes

class  CustomCollisionCallback
 Class to be used as a callback interface for user defined actions performed at each collision detection step. More...
 

Public Member Functions

 ChSystem ()
 Create a physical system.
 
 ChSystem (const ChSystem &other)
 Copy constructor.
 
virtual ~ChSystem ()
 Destructor.
 
void SetStep (double m_step)
 Sets the time step used for integration (dynamical simulation). More...
 
double GetStep () const
 Gets the current time step used for the integration (dynamical simulation).
 
void SetEndTime (double m_end_time)
 Sets the end of simulation.
 
double GetEndTime () const
 Gets the end of the simulation.
 
void SetStepMin (double m_step_min)
 Sets the lower limit for time step (only needed if using integration methods which support time step adaption).
 
double GetStepMin () const
 Gets the lower limit for time step.
 
void SetStepMax (double m_step_max)
 Sets the upper limit for time step (only needed if using integration methods which support time step adaption).
 
double GetStepMax () const
 Gets the upper limit for time step.
 
void SetTimestepperType (ChTimestepper::Type type)
 Set the method for time integration (time stepper type). More...
 
ChTimestepper::Type GetTimestepperType () const
 Get the current method for time integration (time stepper type).
 
void SetTimestepper (std::shared_ptr< ChTimestepper > mstepper)
 Set the timestepper object to be used for time integration.
 
std::shared_ptr< ChTimestepperGetTimestepper () const
 Get the timestepper currently used for time integration.
 
void SetMaxiter (int m_maxiter)
 Sets outer iteration limit for assembly constraints. More...
 
int GetMaxiter () const
 Gets iteration limit for assembly constraints.
 
void SetMaterialCompositionStrategy (std::unique_ptr< ChMaterialCompositionStrategy< float >> &&strategy)
 Change the default composition laws for contact surface materials (coefficient of friction, cohesion, compliance, etc.)
 
const ChMaterialCompositionStrategy< float > & GetMaterialCompositionStrategy () const
 Accessor for the current composition laws for contact surface material.
 
void SetMinBounceSpeed (double mval)
 For elastic collisions, with objects that have nonzero restitution coefficient: objects will rebounce only if their relative colliding speed is above this threshold. More...
 
double GetMinBounceSpeed () const
 Objects will rebounce only if their relative colliding speed is above this threshold.
 
void SetMaxPenetrationRecoverySpeed (double mval)
 For the default stepper, you can limit the speed of exiting from penetration situations. More...
 
double GetMaxPenetrationRecoverySpeed () const
 Get the limit on the speed for exiting from penetration situations (for Anitescu stepper)
 
virtual void SetSolver (std::shared_ptr< ChSolver > newsolver)
 Attach a solver (derived from ChSolver) for use by this system.
 
virtual std::shared_ptr< ChSolverGetSolver ()
 Access the solver currently associated with this system.
 
virtual void SetSolverType (ChSolver::Type type)
 Choose the solver type, to be used for the simultaneous solution of the constraints in dynamical simulations (as well as in kinematics, statics, etc.) More...
 
ChSolver::Type GetSolverType () const
 Gets the current solver type.
 
void SetSolverMaxIterations (int max_iters)
 Set the maximum number of iterations, if using an iterative solver. More...
 
int GetSolverMaxIterations () const
 Get the current maximum number of iterations, if using an iterative solver. More...
 
void SetSolverTolerance (double tolerance)
 Set the solver tolerance threshold (used with iterative solvers only). More...
 
double GetSolverTolerance () const
 Get the current tolerance value (used with iterative solvers only).
 
void SetSolverForceTolerance (double tolerance)
 Set a solver tolerance threshold at force level (default: not specified). More...
 
double GetSolverForceTolerance () const
 Get the current value of the force-level tolerance (used with iterative solvers only).
 
void SetSystemDescriptor (std::shared_ptr< ChSystemDescriptor > newdescriptor)
 Instead of using the default 'system descriptor', you can create your own custom descriptor (inherited from ChSystemDescriptor) and plug it into the system using this function.
 
std::shared_ptr< ChSystemDescriptorGetSystemDescriptor ()
 Access directly the 'system descriptor'.
 
void Set_G_acc (const ChVector<> &m_acc)
 Sets the G (gravity) acceleration vector, affecting all the bodies in the system.
 
const ChVectorGet_G_acc () const
 Gets the G (gravity) acceleration vector affecting all the bodies in the system.
 
void Clear ()
 Removes all bodies/marker/forces/links/contacts, also resets timers and events.
 
virtual ChMaterialSurface::ContactMethod GetContactMethod () const =0
 Return the contact method supported by this system. More...
 
virtual ChBodyNewBody ()=0
 Create and return the pointer to a new body. More...
 
virtual ChBodyAuxRefNewBodyAuxRef ()=0
 Create and return the pointer to a new body with auxiliary reference frame. More...
 
virtual void SetContactContainer (std::shared_ptr< ChContactContainer > container)
 Replace the contact container.
 
std::shared_ptr< ChContactContainerGetContactContainer ()
 Get the contact container.
 
void Reference_LM_byID ()
 Given inserted markers and links, restores the pointers of links to markers given the information about the marker IDs. More...
 
int GetNcontacts ()
 Gets the number of contacts.
 
virtual double GetTimerStep () const
 Return the time (in seconds) spent for computing the time step.
 
virtual double GetTimerAdvance () const
 Return the time (in seconds) for time integration, within the time step.
 
virtual double GetTimerSolver () const
 Return the time (in seconds) for the solver, within the time step. More...
 
virtual double GetTimerSetup () const
 Return the time (in seconds) for the solver Setup phase, within the time step.
 
virtual double GetTimerJacobian () const
 Return the time (in seconds) for calculating/loading Jacobian information, within the time step.
 
virtual double GetTimerCollision () const
 Return the time (in seconds) for runnning the collision detection step, within the time step.
 
virtual double GetTimerUpdate () const
 Return the time (in seconds) for updating auxiliary data, within the time step.
 
double GetTimerCollisionBroad () const
 Return the time (in seconds) for broadphase collision detection, within the time step.
 
double GetTimerCollisionNarrow () const
 Return the time (in seconds) for narrowphase collision detection, within the time step.
 
void ResetTimers ()
 Resets the timers.
 
virtual void Setup () override
 Counts the number of bodies and links. More...
 
virtual void Update (bool update_assets=true) override
 Updates all the auxiliary data and children of bodies, forces, links, given their current state.
 
void ForceUpdate ()
 In normal usage, no system update is necessary at the beginning of a new dynamics step (since an update is performed at the end of a step). More...
 
virtual void IntStateGather (const unsigned int off_x, ChState &x, const unsigned int off_v, ChStateDelta &v, double &T) override
 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) override
 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) override
 From item's state acceleration to global acceleration vector. More...
 
virtual void IntStateScatterAcceleration (const unsigned int off_a, const ChStateDelta &a) override
 From global acceleration vector to item's state acceleration. More...
 
virtual void IntStateGatherReactions (const unsigned int off_L, ChVectorDynamic<> &L) override
 From item's reaction forces to global reaction vector. More...
 
virtual void IntStateScatterReactions (const unsigned int off_L, const ChVectorDynamic<> &L) override
 From global reaction vector to item's reaction forces. More...
 
virtual void IntStateIncrement (const unsigned int off_x, ChState &x_new, const ChState &x, const unsigned int off_v, const ChStateDelta &Dv) override
 Computes x_new = x + Dt , using vectors at specified offsets. More...
 
virtual void IntLoadResidual_F (const unsigned int off, ChVectorDynamic<> &R, const double c) override
 Takes the F force term, scale and adds to R at given offset: R += c*F. More...
 
virtual void IntLoadResidual_Mv (const unsigned int off, ChVectorDynamic<> &R, const ChVectorDynamic<> &w, const double c) override
 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 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 InjectVariables (ChSystemDescriptor &mdescriptor) override
 Tell to a system descriptor that there are variables of type ChVariables in this object (for further passing it to a solver) Basically does nothing, but maybe that inherited classes may specialize this.
 
virtual void InjectConstraints (ChSystemDescriptor &mdescriptor) override
 Tell to a system descriptor that there are constraints of type ChConstraint in this object (for further passing it to a solver) Basically does nothing, but maybe that inherited classes may specialize this.
 
virtual void ConstraintsLoadJacobians () override
 Adds the current jacobians in encapsulated ChConstraints.
 
virtual void InjectKRMmatrices (ChSystemDescriptor &mdescriptor) override
 Tell to a system descriptor that there are items of type ChKblock in this object (for further passing it to a solver) Basically does nothing, but maybe that inherited classes may specialize this.
 
virtual void KRMmatricesLoad (double Kfactor, double Rfactor, double Mfactor) override
 Adds the current stiffness K and damping R and mass M matrices in encapsulated ChKblock item(s), if any. More...
 
virtual void VariablesFbReset () override
 Sets the 'fb' part (the known term) of the encapsulated ChVariables to zero.
 
virtual void VariablesFbLoadForces (double factor=1) override
 Adds the current forces (applied to item) into the encapsulated ChVariables, in the 'fb' part: qf+=forces*factor.
 
virtual void VariablesQbLoadSpeed () override
 Initialize the 'qb' part of the ChVariables with the current value of speeds. More...
 
virtual void VariablesFbIncrementMq () override
 Adds M*q (masses multiplied current 'qb') to Fb, ex. More...
 
virtual void VariablesQbSetSpeed (double step=0) override
 Fetches the item speed (ex. More...
 
virtual void VariablesQbIncrementPosition (double step) override
 Increment item positions by the 'qb' part of the ChVariables, multiplied by a 'step' factor. More...
 
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 ConstraintsFbLoadForces (double factor=1) override
 Adds the current link-forces, if any, (caused by springs, etc.) to the 'fb' vectors of the ChVariables referenced by encapsulated ChConstraints.
 
virtual void ConstraintsFetch_react (double factor=1) override
 Fetches the reactions from the lagrangian multiplier (l_i) of encapsulated ChConstraints. More...
 
virtual int GetNcoords_x () override
 Tells the number of position coordinates x in y = {x, v}.
 
virtual int GetNcoords_v () override
 Tells the number of speed coordinates of v in y = {x, v} and dy/dt={v, a}.
 
virtual int GetNconstr () override
 Tells the number of lagrangian multipliers (constraints)
 
virtual void StateGather (ChState &x, ChStateDelta &v, double &T) override
 From system to state y={x,v}.
 
virtual void StateScatter (const ChState &x, const ChStateDelta &v, const double T) override
 From state Y={x,v} to system.
 
virtual void StateGatherAcceleration (ChStateDelta &a) override
 From system to state derivative (acceleration), some timesteppers might need last computed accel.
 
virtual void StateScatterAcceleration (const ChStateDelta &a) override
 From state derivative (acceleration) to system, sometimes might be needed.
 
virtual void StateGatherReactions (ChVectorDynamic<> &L) override
 From system to reaction forces (last computed) - some timestepper might need this.
 
virtual void StateScatterReactions (const ChVectorDynamic<> &L) override
 From reaction forces to system, ex. store last computed reactions in ChLink objects for plotting etc.
 
virtual void StateIncrementX (ChState &x_new, const ChState &x, const ChStateDelta &Dx) override
 Perform x_new = x + dx, for x in Y = {x, dx/dt}. More...
 
virtual bool StateSolveCorrection (ChStateDelta &Dv, ChVectorDynamic<> &L, const ChVectorDynamic<> &R, const ChVectorDynamic<> &Qc, const double c_a, const double c_v, const double c_x, const ChState &x, const ChStateDelta &v, const double T, bool force_state_scatter=true, bool force_setup=true) override
 Assuming a DAE of the form. More...
 
virtual void LoadResidual_F (ChVectorDynamic<> &R, const double c) override
 Increment a vector R with the term c*F: R += c*F. More...
 
virtual void LoadResidual_Mv (ChVectorDynamic<> &R, const ChVectorDynamic<> &w, const double c) override
 Increment a vector R with a term that has M multiplied a given vector w: R += c*M*w. More...
 
virtual void LoadResidual_CqL (ChVectorDynamic<> &R, const ChVectorDynamic<> &L, const double c) override
 Increment a vectorR with the term Cq'*L: R += c*Cq'*L. More...
 
virtual void LoadConstraint_C (ChVectorDynamic<> &Qc, const double c, const bool do_clamp=false, const double mclam=1e30) override
 Increment a vector Qc with the term C: Qc += c*C. More...
 
virtual void LoadConstraint_Ct (ChVectorDynamic<> &Qc, const double c) override
 Increment a vector Qc with the term Ct = partial derivative dC/dt: Qc += c*Ct. More...
 
virtual void CustomEndOfStep ()
 Executes custom processing at the end of step. More...
 
void SynchronizeLastCollPositions ()
 All bodies with collision detection data are requested to store the current position as "last position collision-checked".
 
double ComputeCollisions ()
 Perform the collision detection. More...
 
void RegisterCustomCollisionCallback (CustomCollisionCallback *mcallb)
 Specify a callback object to be invoked at each collision detection step. More...
 
void SetCollisionSystem (std::shared_ptr< collision::ChCollisionSystem > newcollsystem)
 For higher performance (ex. More...
 
std::shared_ptr< collision::ChCollisionSystemGetCollisionSystem () const
 Access the collision system, the engine which computes the contact points (usually you don't need to access it, since it is automatically handled by the client ChSystem object).
 
void SetUseSleeping (bool ms)
 Turn on this feature to let the system put to sleep the bodies whose motion has almost come to a rest. More...
 
bool GetUseSleeping () const
 Tell if the system will put to sleep the bodies whose motion has almost come to a rest.
 
int DoStepDynamics (double m_step)
 Advances the dynamical simulation for a single step, of length m_step. More...
 
bool DoFrameDynamics (double m_endtime)
 Performs integration until the m_endtime is exactly reached, but current time step may be automatically "retouched" to meet exactly the m_endtime after n steps. More...
 
bool DoEntireDynamics ()
 Given the current state, the sw simulates the dynamical behavior of the system, until the end time is reached, repeating many steps (maybe the step size will be automatically changed if the integrator method supports step size adaption).
 
bool DoEntireUniformDynamics (double frame_step)
 Like "DoEntireDynamics", but results are provided at uniform steps "frame_step", using the DoFrameDynamics() many times.
 
size_t GetStepcount () const
 Return the total number of time steps taken so far.
 
void ResetStepcount ()
 Reset to 0 the total number of time steps.
 
int GetSolverCallsCount () const
 Return the number of calls to the solver's Solve() function. More...
 
int GetSolverSetupCount () const
 Return the number of calls to the solver's Setup() function. More...
 
void SetDumpSolverMatrices (bool md)
 Set this to "true" to enable automatic saving of solver matrices at each time step, for debugging purposes. More...
 
bool GetDumpSolverMatrices () const
 
void DumpSystemMatrices (bool save_M, bool save_K, bool save_R, bool save_Cq, const char *path)
 Dump the current M mass matrix, K damping matrix, R damping matrix, Cq constraint jacobian matrix (at the current configuration). More...
 
void GetMassMatrix (ChSparseMatrix *M)
 Compute the system-level mass matrix. More...
 
void GetStiffnessMatrix (ChSparseMatrix *K)
 Compute the system-level stiffness matrix, i.e. More...
 
void GetDampingMatrix (ChSparseMatrix *R)
 Compute the system-level damping matrix, i.e. More...
 
void GetConstraintJacobianMatrix (ChSparseMatrix *Cq)
 Compute the system-level constraint jacobian matrix, i.e. More...
 
bool DoStepKinematics (double m_step)
 Advances the kinematic simulation for a single step, of length m_step. More...
 
bool DoFrameKinematics (double m_endtime)
 Performs kinematics until the m_endtime is exactly reached, but current time step may be automatically "retouched" to meet exactly the m_endtime after n steps.
 
bool DoEntireKinematics ()
 Given the current state, this kinematic simulation satisfies all the constraints with the "DoStepKinematics" procedure for each time step, from the current time to the end time.
 
bool DoAssembly (int action)
 Given the current time and state, attempt to satisfy all constraints, using a Newton-Raphson iteration loop. More...
 
bool DoFullAssembly ()
 Shortcut for full position/velocity/acceleration assembly.
 
bool DoStaticLinear ()
 Solve the position of static equilibrium (and the reactions). More...
 
bool DoStaticNonlinear (int nsteps=10, bool verbose=false)
 Solve the position of static equilibrium (and the reactions). More...
 
bool DoStaticNonlinear (std::shared_ptr< ChStaticNonLinearAnalysis > analysis)
 Solve the position of static equilibrium (and the reactions). More...
 
bool DoStaticRelaxing (int nsteps=10)
 Finds the position of static equilibrium (and the reactions) starting from the current position. More...
 
virtual void ArchiveOUT (ChArchiveOut &marchive) override
 Method to allow serialization of transient data to archives.
 
virtual void ArchiveIN (ChArchiveIn &marchive) override
 Method to allow deserialization of transient data from archives.
 
int FileProcessChR (ChStreamInBinary &m_file)
 Process a ".chr" binary file containing the full system object hierarchy as exported -for example- by the R3D modeler, with chrono plug-in version, or by using the FileWriteChR() function.
 
int FileWriteChR (ChStreamOutBinary &m_file)
 Write a ".chr" binary file containing the full system object hierarchy (bodies, forces, links, etc.) (deprecated function - obsolete)
 
- Public Member Functions inherited from chrono::ChAssembly
 ChAssembly (const ChAssembly &other)
 
virtual ChAssemblyClone () const override
 "Virtual" copy constructor (covariant return type).
 
void Clear ()
 Removes all inserted items: bodies, links, etc.
 
virtual void AddBody (std::shared_ptr< ChBody > body)
 Attach a body to this assembly.
 
virtual void AddLink (std::shared_ptr< ChLinkBase > link)
 Attach a link to this assembly.
 
virtual void AddMesh (std::shared_ptr< fea::ChMesh > mesh)
 Attach a mesh to this assembly.
 
virtual void AddOtherPhysicsItem (std::shared_ptr< ChPhysicsItem > item)
 Attach a ChPhysicsItem object that is not a body, link, or mesh.
 
void Add (std::shared_ptr< ChPhysicsItem > item)
 Attach an arbitrary ChPhysicsItem (e.g. More...
 
void AddBatch (std::shared_ptr< ChPhysicsItem > item)
 Items added in this way are added like in the Add() method, but not instantly, they are simply queued in a batch of 'to add' items, that are added automatically at the first Setup() call. More...
 
void FlushBatch ()
 If some items are queued for addition in the assembly, using AddBatch(), this will effectively add them and clean the batch. More...
 
virtual void RemoveBody (std::shared_ptr< ChBody > body)
 Remove a body from this assembly.
 
virtual void RemoveLink (std::shared_ptr< ChLinkBase > link)
 Remove a link from this assembly.
 
virtual void RemoveMesh (std::shared_ptr< fea::ChMesh > mesh)
 Remove a mesh from the assembly.
 
virtual void RemoveOtherPhysicsItem (std::shared_ptr< ChPhysicsItem > item)
 Remove a ChPhysicsItem object that is not a body or a link.
 
void Remove (std::shared_ptr< ChPhysicsItem > item)
 Remove arbitrary ChPhysicsItem that was added to the assembly.
 
void RemoveAllBodies ()
 Remove all bodies from this assembly.
 
void RemoveAllLinks ()
 Remove all links from this assembly.
 
void RemoveAllMeshes ()
 Remove all meshes from this assembly.
 
void RemoveAllOtherPhysicsItems ()
 Remove all physics items not in the body, link, or mesh lists.
 
const std::vector< std::shared_ptr< ChBody > > & Get_bodylist () const
 Get the list of bodies.
 
const std::vector< std::shared_ptr< ChLinkBase > > & Get_linklist () const
 Get the list of links.
 
const std::vector< std::shared_ptr< fea::ChMesh > > & Get_meshlist () const
 Get the list of meshes.
 
const std::vector< std::shared_ptr< ChPhysicsItem > > & Get_otherphysicslist () const
 Get the list of physics items that are not in the body or link lists.
 
std::shared_ptr< ChBodySearchBody (const char *name)
 Search a body by its name.
 
std::shared_ptr< ChLinkBaseSearchLink (const char *name)
 Search a link by its name.
 
std::shared_ptr< fea::ChMeshSearchMesh (const char *name)
 Search a mesh by its name.
 
std::shared_ptr< ChPhysicsItemSearchOtherPhysicsItem (const char *name)
 Search from other ChPhysics items (not bodies, links, or meshes) by name.
 
std::shared_ptr< ChPhysicsItemSearch (const char *name)
 Search an item (body, link or other ChPhysics items) by name.
 
std::shared_ptr< ChBodySearchBodyID (int markID)
 Search a body by its ID.
 
std::shared_ptr< ChMarkerSearchMarker (const char *name)
 Search a marker by its name.
 
std::shared_ptr< ChMarkerSearchMarker (int markID)
 Search a marker by its unique ID.
 
int GetNbodies () const
 Get the number of active bodies (so, excluding those that are sleeping or are fixed to ground).
 
int GetNbodiesSleeping () const
 Get the number of bodies that are in sleeping mode (excluding fixed bodies).
 
int GetNbodiesFixed () const
 Get the number of bodies that are fixed to ground.
 
int GetNbodiesTotal () const
 Get the total number of bodies added to the assembly, including the grounded and sleeping bodies.
 
int GetNlinks () const
 Get the number of links.
 
int GetNmeshes () const
 Get the number of meshes.
 
int GetNphysicsItems () const
 Get the number of other physics items (other than bodies, links, or meshes).
 
int GetNcoords () const
 Get the number of coordinates (considering 7 coords for rigid bodies because of the 4 dof of quaternions).
 
int GetNdof () const
 Get the number of degrees of freedom of the assembly.
 
int GetNdoc () const
 Get the number of scalar constraints added to the assembly, including constraints on quaternion norms.
 
int GetNsysvars () const
 Get the number of system variables (coordinates plus the constraint multipliers, in case of quaternions).
 
int GetNcoords_w () const
 Get the number of coordinates (considering 6 coords for rigid bodies, 3 transl.+3rot.)
 
int GetNdoc_w () const
 Get the number of scalar constraints added to the assembly.
 
int GetNdoc_w_C () const
 Get the number of scalar constraints added to the assembly (only bilaterals).
 
int GetNdoc_w_D () const
 Get the number of scalar constraints added to the assembly (only unilaterals).
 
int GetNsysvars_w () const
 Get the number of system variables (coordinates plus the constraint multipliers).
 
virtual void SetSystem (ChSystem *m_system) override
 Set the pointer to the parent ChSystem() and also add to new collision system / remove from old coll.system.
 
virtual void SyncCollisionModels () override
 If this physical item contains one or more collision models, synchronize their coordinates and bounding boxes to the state of the item.
 
virtual void Update (double mytime, bool update_assets=true) override
 Updates all the auxiliary data and children of bodies, forces, links, given their current state.
 
virtual void SetNoSpeedNoAcceleration () override
 Set zero speed (and zero accelerations) in state, without changing the position.
 
virtual int GetDOF () override
 Get the number of scalar coordinates (ex. dim of position vector)
 
virtual int GetDOF_w () override
 Get the number of scalar coordinates of variables derivatives (ex. dim of speed vector)
 
virtual int GetDOC () override
 Get the number of scalar constraints, if any, in this item.
 
virtual int GetDOC_c () override
 Get the number of scalar constraints, if any, in this item (only bilateral constr.)
 
virtual int GetDOC_d () override
 Get the number of scalar constraints, if any, in this item (only unilateral constr.)
 
void ShowHierarchy (ChStreamOutAscii &m_file, int level=0)
 Writes the hierarchy of contained bodies, markers, etc. More...
 
- Public Member Functions inherited from chrono::ChPhysicsItem
 ChPhysicsItem (const ChPhysicsItem &other)
 
ChSystemGetSystem () const
 Get the pointer to the parent ChSystem()
 
void AddAsset (std::shared_ptr< ChAsset > masset)
 Add an optional asset (it can be used to define visualization shapes, es ChSphereShape, or textures, or custom attached properties that the user can define by creating his class inherited from ChAsset)
 
std::vector< std::shared_ptr< ChAsset > > & GetAssets ()
 Access to the list of optional assets.
 
std::shared_ptr< ChAssetGetAssetN (unsigned int num)
 Access the Nth asset in the list of optional assets.
 
virtual ChFrame GetAssetsFrame (unsigned int nclone=0)
 Get the master coordinate system for assets that have some geometric meaning. More...
 
virtual unsigned int GetAssetsFrameNclones ()
 Optionally, a ChPhysicsItem can return multiple asset coordinate systems; this can be helpful if, for example, when a ChPhysicsItem contains 'clones' with the same assets (ex. More...
 
virtual bool GetCollide () const
 Tell if the object is subject to collision. More...
 
virtual void AddCollisionModelsToSystem ()
 If this physical item contains one or more collision models, add them to the system's collision engine.
 
virtual void RemoveCollisionModelsFromSystem ()
 If this physical item contains one or more collision models, remove them from the system's collision engine.
 
virtual void GetTotalAABB (ChVector<> &bbmin, ChVector<> &bbmax)
 Get the entire AABB axis-aligned bounding box of the object. More...
 
virtual void GetCenter (ChVector<> &mcenter)
 Get a symbolic 'center' of the object. More...
 
virtual void StreamINstate (ChStreamInBinary &mstream)
 Method to deserialize only the state (position, speed) Must be implemented by child classes.
 
virtual void StreamOUTstate (ChStreamOutBinary &mstream)
 Method to serialize only the state (position, speed) Must be implemented by child classes.
 
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.
 
- Public Member Functions inherited from chrono::ChObj
 ChObj (const ChObj &other)
 
int GetIdentifier () const
 Gets the numerical identifier of the object.
 
void SetIdentifier (int id)
 Sets the numerical identifier of the object.
 
double GetChTime () const
 Gets the simulation time of this object.
 
void SetChTime (double m_time)
 Sets the simulation time of this object.
 
const char * GetName () const
 Gets the name of the object as C Ascii null-terminated string -for reading only!
 
void SetName (const char myname[])
 Sets the name of this object, as ascii string.
 
std::string GetNameString () const
 Gets the name of the object as C Ascii null-terminated string.
 
void SetNameString (const std::string &myname)
 Sets the name of this object, as std::string.
 
void MFlagsSetAllOFF (int &mflag)
 
void MFlagsSetAllON (int &mflag)
 
void MFlagSetON (int &mflag, int mask)
 
void MFlagSetOFF (int &mflag, int mask)
 
int MFlagGet (int &mflag, int mask)
 
virtual std::string & ArchiveContainerName ()
 
- Public Member Functions inherited from chrono::ChIntegrableIIorder
virtual int GetNcoords_a ()
 Return the number of acceleration coordinates of a in dy/dt={v, a} This is a default implementation that works in almost all cases, as dim(a) = dim(v),.
 
virtual void StateSetup (ChState &x, ChStateDelta &v, ChStateDelta &a)
 Set up the system state with separate II order components x, v, a for y = {x, v} and dy/dt={v, a}.
 
virtual bool StateSolveA (ChStateDelta &Dvdt, ChVectorDynamic<> &L, const ChState &x, const ChStateDelta &v, const double T, const double dt, bool force_state_scatter=true)
 Solve for accelerations: a = f(x,v,t) Given current state y={x,v} , computes acceleration a in the state derivative dy/dt={v,a} and lagrangian multipliers L (if any). More...
 
virtual int GetNcoords_y () override
 Return the number of coordinates in the state Y. More...
 
virtual int GetNcoords_dy () override
 Return the number of coordinates in the state increment. More...
 
virtual void StateGather (ChState &y, double &T) override
 Gather system state in specified array. More...
 
virtual void StateScatter (const ChState &y, const double T) override
 Scatter the states from the provided array to the system. More...
 
virtual void StateGatherDerivative (ChStateDelta &Dydt) override
 Gather from the system the state derivatives in specified array. More...
 
virtual void StateScatterDerivative (const ChStateDelta &Dydt) override
 Scatter the state derivatives from the provided array to the system. More...
 
virtual void StateIncrement (ChState &y_new, const ChState &y, const ChStateDelta &Dy) override
 Increment state array: y_new = y + Dy. More...
 
virtual bool StateSolve (ChStateDelta &dydt, ChVectorDynamic<> &L, const ChState &y, const double T, const double dt, bool force_state_scatter=true) override
 Solve for state derivatives: dy/dt = f(y,t). More...
 
virtual bool StateSolveCorrection (ChStateDelta &Dy, ChVectorDynamic<> &L, const ChVectorDynamic<> &R, const ChVectorDynamic<> &Qc, const double a, const double b, const ChState &y, const double T, const double dt, bool force_state_scatter=true, bool force_setup=true) override
 This was for Ist order implicit integrators, but here we disable it.
 
- Public Member Functions inherited from chrono::ChIntegrable
virtual void StateSetup (ChState &y, ChStateDelta &dy)
 Set up the system state.
 
virtual void LoadResidual_Hv (ChVectorDynamic<> &R, const ChVectorDynamic<> &v, const double c)
 Increment a vector R (usually the residual in a Newton Raphson iteration for solving an implicit integration step) with a term that has H multiplied a given vector w: R += c*H*w. More...
 

Protected Member Functions

virtual void DescriptorPrepareInject (ChSystemDescriptor &mdescriptor)
 Pushes all ChConstraints and ChVariables contained in links, bodies, etc. into the system descriptor.
 

Protected Attributes

std::shared_ptr< ChContactContainercontact_container
 the container of contacts
 
ChVector G_acc
 gravitational acceleration
 
bool is_initialized
 if false, an initial setup is required (i.e. a call to SetupInitial)
 
bool is_updated
 if false, a new update is required (i.e. a call to Update)
 
double end_time
 end of simulation
 
double step
 time step
 
double step_min
 min time step
 
double step_max
 max time step
 
double tol_force
 tolerance for forces (used to obtain a tolerance for impulses)
 
int maxiter
 max iterations for nonlinear convergence in DoAssembly()
 
bool use_sleeping
 if true, put to sleep objects that come to rest
 
std::shared_ptr< ChSystemDescriptordescriptor
 system descriptor
 
std::shared_ptr< ChSolversolver
 solver for DVI or DAE problem
 
double min_bounce_speed
 minimum speed for rebounce after impacts. Lower speeds are clamped to 0
 
double max_penetration_recovery_speed
 limit for the speed of penetration recovery (positive, speed of exiting)
 
size_t stepcount
 internal counter for steps
 
int setupcount
 number of calls to the solver's Setup()
 
int solvecount
 number of StateSolveCorrection (reset to 0 at each timestep of static analysis)
 
bool dump_matrices
 for debugging
 
int ncontacts
 total number of contacts
 
std::shared_ptr< collision::ChCollisionSystemcollision_system
 collision engine
 
std::vector< CustomCollisionCallback * > collision_callbacks
 
std::unique_ptr< ChMaterialCompositionStrategy< float > > composition_strategy
 
ChTimer< double > timer_step
 material composition strategy More...
 
ChTimer< double > timer_advance
 timer for time integration
 
ChTimer< double > timer_solver
 timer for solver (excluding setup phase)
 
ChTimer< double > timer_setup
 timer for solver setup
 
ChTimer< double > timer_jacobian
 timer for computing/loading Jacobian information
 
ChTimer< double > timer_collision
 timer for collision detection
 
ChTimer< double > timer_update
 timer for system update
 
std::shared_ptr< ChTimesteppertimestepper
 time-stepper object
 
bool last_err
 indicates error over the last kinematic/dynamics/statics
 
- Protected Attributes inherited from chrono::ChAssembly
std::vector< std::shared_ptr< ChBody > > bodylist
 list of rigid bodies
 
std::vector< std::shared_ptr< ChLinkBase > > linklist
 list of joints (links)
 
std::vector< std::shared_ptr< fea::ChMesh > > meshlist
 list of meshes
 
std::vector< std::shared_ptr< ChPhysicsItem > > otherphysicslist
 list of other physics objects
 
std::vector< std::shared_ptr< ChPhysicsItem > > batch_to_insert
 list of items to insert at once
 
int nbodies
 number of bodies (currently active)
 
int nlinks
 number of links
 
int nmeshes
 number of meshes
 
int nphysicsitems
 number of other physics items
 
int ncoords
 number of scalar coordinates (including 4th dimension of quaternions) for all active bodies
 
int ndoc
 number of scalar constraints (including constr. on quaternions)
 
int nsysvars
 number of variables (coords+lagrangian mult.), i.e. = ncoords+ndoc for all active bodies
 
int ncoords_w
 number of scalar coordinates when using 3 rot. dof. per body; for all active bodies
 
int ndoc_w
 number of scalar constraints when using 3 rot. dof. per body; for all active bodies
 
int nsysvars_w
 number of variables when using 3 rot. dof. per body; i.e. = ncoords_w+ndoc_w
 
int ndof
 number of degrees of freedom, = ncoords-ndoc = ncoords_w-ndoc_w ,
 
int ndoc_w_C
 number of scalar constraints C, when using 3 rot. dof. per body (excluding unilaterals)
 
int ndoc_w_D
 number of scalar constraints D, when using 3 rot. dof. per body (only unilaterals)
 
int nbodies_sleep
 number of bodies that are sleeping
 
int nbodies_fixed
 number of bodies that are fixed
 
- Protected Attributes inherited from chrono::ChPhysicsItem
ChSystemsystem
 parent system
 
std::vector< std::shared_ptr< ChAsset > > assets
 set of assets
 
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
 the time of simulation for the object
 

Friends

class ChAssembly
 
class ChBody
 
class fea::ChMesh
 
template<class Ta , class Tb >
class ChContactNSC
 
template<class Ta , class Tb >
class ChContactNSCrolling
 
template<class Ta , class Tb >
class ChContactSMC
 

Member Function Documentation

◆ ComputeCollisions()

double chrono::ChSystem::ComputeCollisions ( )

Perform the collision detection.

New contacts are inserted in the ChContactContainer object(s), and old ones are removed. This is mostly called automatically by time integration.

◆ ConstraintsFetch_react()

void chrono::ChSystem::ConstraintsFetch_react ( double  factor = 1)
overridevirtual

Fetches the reactions from the lagrangian multiplier (l_i) of encapsulated ChConstraints.

Mostly used after the solver provided the solution in ChConstraints. Also, should convert the reactions obtained from dynamical simulation, from link space to intuitive react_force and react_torque.

Reimplemented from chrono::ChAssembly.

◆ CustomEndOfStep()

virtual void chrono::ChSystem::CustomEndOfStep ( )
inlinevirtual

Executes custom processing at the end of step.

By default it does nothing, but if you inherit a special ChSystem you can implement this.

◆ DoAssembly()

bool chrono::ChSystem::DoAssembly ( int  action)

Given the current time and state, attempt to satisfy all constraints, using a Newton-Raphson iteration loop.

Used iteratively in inverse kinematics. Action can be one of AssemblyLevel::POSITION, AssemblyLevel::VELOCITY, or AssemblyLevel::ACCELERATION (or a combination of these) Returns true if no errors and false if an error occurred (impossible assembly?)

◆ DoFrameDynamics()

bool chrono::ChSystem::DoFrameDynamics ( double  m_endtime)

Performs integration until the m_endtime is exactly reached, but current time step may be automatically "retouched" to meet exactly the m_endtime after n steps.

Useful when you want to advance the simulation in a simulations (3d modeling software etc.) which needs updates of the screen at a fixed rate (ex.30th of second) while the integration must use more steps.

◆ DoStaticLinear()

bool chrono::ChSystem::DoStaticLinear ( )

Solve the position of static equilibrium (and the reactions).

This is a one-step only approach that solves the linear equilibrium. Appropriate mostly for FEM problems with small deformations.

◆ DoStaticNonlinear() [1/2]

bool chrono::ChSystem::DoStaticNonlinear ( int  nsteps = 10,
bool  verbose = false 
)

Solve the position of static equilibrium (and the reactions).

This function solves the equilibrium for the nonlinear problem (large displacements). This version uses a nonlinear static analysis solver with default parameters.

◆ DoStaticNonlinear() [2/2]

bool chrono::ChSystem::DoStaticNonlinear ( std::shared_ptr< ChStaticNonLinearAnalysis analysis)

Solve the position of static equilibrium (and the reactions).

This function solves the equilibrium for the nonlinear problem (large displacements). This version uses the provided nonlinear static analysis solver.

◆ DoStaticRelaxing()

bool chrono::ChSystem::DoStaticRelaxing ( int  nsteps = 10)

Finds the position of static equilibrium (and the reactions) starting from the current position.

Since a truncated iterative method is used, you may need to call this method multiple times in case of large nonlinearities before coming to the precise static solution.

◆ DoStepDynamics()

int chrono::ChSystem::DoStepDynamics ( double  m_step)

Advances the dynamical simulation for a single step, of length m_step.

You can call this function many times in order to simulate up to a desired end time. This is the most important function for analysis, you can use it, for example, once per screen refresh in VR and interactive realtime applications, etc.

◆ DoStepKinematics()

bool chrono::ChSystem::DoStepKinematics ( double  m_step)

Advances the kinematic simulation for a single step, of length m_step.

You can call this function many times in order to simulate up to a desired end time.

◆ DumpSystemMatrices()

void chrono::ChSystem::DumpSystemMatrices ( bool  save_M,
bool  save_K,
bool  save_R,
bool  save_Cq,
const char *  path 
)

Dump the current M mass matrix, K damping matrix, R damping matrix, Cq constraint jacobian matrix (at the current configuration).

These can be later used for linearized motion, modal analysis, buckling analysis, etc. The name of the files will be [path]_M.dat [path]_K.dat [path]_R.dat [path]_Cq.dat Might throw ChException if file can't be saved.

◆ ForceUpdate()

void chrono::ChSystem::ForceUpdate ( )

In normal usage, no system update is necessary at the beginning of a new dynamics step (since an update is performed at the end of a step).

However, this is not the case if external changes to the system are made. Most such changes are discovered automatically (addition/removal of items, input of mesh loads). For special cases, this function allows the user to trigger a system update at the beginning of the step immediately following this call.

◆ GetConstraintJacobianMatrix()

void chrono::ChSystem::GetConstraintJacobianMatrix ( ChSparseMatrix Cq)

Compute the system-level constraint jacobian matrix, i.e.

the jacobian Cq=-dC/dq where C are constraints (the lower left part of the KKT matrix). This function has a small overhead, because it must assembly the sparse matrix -which is used only for the purpose of this function. fill this system damping matrix

◆ GetContactMethod()

virtual ChMaterialSurface::ContactMethod chrono::ChSystem::GetContactMethod ( ) const
pure virtual

Return the contact method supported by this system.

Bodies added to this system must be compatible.

Implemented in chrono::ChSystemParallelSMC, chrono::ChSystemParallelNSC, chrono::ChSystemSMC, and chrono::ChSystemNSC.

◆ GetDampingMatrix()

void chrono::ChSystem::GetDampingMatrix ( ChSparseMatrix R)

Compute the system-level damping matrix, i.e.

the jacobian -dF/dv where F are stiff loads. Note that not all loads provide a jacobian, as this is optional in their implementation. This function has a small overhead, because it must assembly the sparse matrix -which is used only for the purpose of this function. fill this system damping matrix

◆ GetMassMatrix()

void chrono::ChSystem::GetMassMatrix ( ChSparseMatrix M)

Compute the system-level mass matrix.

This function has a small overhead, because it must assembly the sparse matrix -which is used only for the purpose of this function. fill this system mass matrix

◆ GetSolverCallsCount()

int chrono::ChSystem::GetSolverCallsCount ( ) const
inline

Return the number of calls to the solver's Solve() function.

This counter is reset at each timestep.

◆ GetSolverMaxIterations()

int chrono::ChSystem::GetSolverMaxIterations ( ) const

Get the current maximum number of iterations, if using an iterative solver.

Deprecated:
Prefer using GetSolver and accessing solver statistics directly.

◆ GetSolverSetupCount()

int chrono::ChSystem::GetSolverSetupCount ( ) const
inline

Return the number of calls to the solver's Setup() function.

This counter is reset at each timestep.

◆ GetStiffnessMatrix()

void chrono::ChSystem::GetStiffnessMatrix ( ChSparseMatrix K)

Compute the system-level stiffness matrix, i.e.

the jacobian -dF/dq where F are stiff loads. Note that not all loads provide a jacobian, as this is optional in their implementation. This function has a small overhead, because it must assembly the sparse matrix -which is used only for the purpose of this function. fill this system stiffness matrix

◆ GetTimerSolver()

virtual double chrono::ChSystem::GetTimerSolver ( ) const
inlinevirtual

Return the time (in seconds) for the solver, within the time step.

Note that this time excludes any calls to the solver's Setup function.

Reimplemented in chrono::ChSystemParallel.

◆ IntFromDescriptor()

void chrono::ChSystem::IntFromDescriptor ( const unsigned int  off_v,
ChStateDelta v,
const unsigned int  off_L,
ChVectorDynamic<> &  L 
)
overridevirtual

After a solver solution, fetch values from variables and constraints into vectors:

Parameters
off_voffset for v
vvector to where the q 'unknowns' term of the variables will be copied
off_Loffset for L
Lvector to where L 'lagrangian ' term of the constraints will be copied

Reimplemented from chrono::ChAssembly.

◆ IntLoadConstraint_C()

void chrono::ChSystem::IntLoadConstraint_C ( const unsigned int  off,
ChVectorDynamic<> &  Qc,
const double  c,
bool  do_clamp,
double  recovery_clamp 
)
overridevirtual

Takes the term C, scale and adds to Qc at given offset: Qc += c*C.

Parameters
offoffset in Qc residual
Qcresult: the Qc residual, Qc += c*C
ca scaling factor
do_clampapply clamping to c*C?
recovery_clampvalue for min/max clamping of c*C

Reimplemented from chrono::ChAssembly.

◆ IntLoadConstraint_Ct()

void chrono::ChSystem::IntLoadConstraint_Ct ( const unsigned int  off,
ChVectorDynamic<> &  Qc,
const double  c 
)
overridevirtual

Takes the term Ct, scale and adds to Qc at given offset: Qc += c*Ct.

Parameters
offoffset in Qc residual
Qcresult: the Qc residual, Qc += c*Ct
ca scaling factor

Reimplemented from chrono::ChAssembly.

◆ IntLoadResidual_CqL()

void chrono::ChSystem::IntLoadResidual_CqL ( const unsigned int  off_L,
ChVectorDynamic<> &  R,
const ChVectorDynamic<> &  L,
const double  c 
)
overridevirtual

Takes the term Cq'*L, scale and adds to R at given offset: R += c*Cq'*L.

Parameters
off_Loffset in L multipliers
Rresult: the R residual, R += c*Cq'*L
Lthe L vector
ca scaling factor

Reimplemented from chrono::ChAssembly.

◆ IntLoadResidual_F()

void chrono::ChSystem::IntLoadResidual_F ( const unsigned int  off,
ChVectorDynamic<> &  R,
const double  c 
)
overridevirtual

Takes the F force term, scale and adds to R at given offset: R += c*F.

Parameters
offoffset in R residual
Rresult: the R residual, R += c*F
ca scaling factor

Reimplemented from chrono::ChAssembly.

◆ IntLoadResidual_Mv()

void chrono::ChSystem::IntLoadResidual_Mv ( const unsigned int  off,
ChVectorDynamic<> &  R,
const ChVectorDynamic<> &  w,
const double  c 
)
overridevirtual

Takes the M*v term, multiplying mass by a vector, scale and adds to R at given offset: R += c*M*w.

Parameters
offoffset in R residual
Rresult: the R residual, R += c*M*v
wthe w vector
ca scaling factor

Reimplemented from chrono::ChAssembly.

◆ IntStateGather()

void chrono::ChSystem::IntStateGather ( const unsigned int  off_x,
ChState x,
const unsigned int  off_v,
ChStateDelta v,
double &  T 
)
overridevirtual

From item's state to global state vectors y={x,v} pasting the states at the specified offsets.

Parameters
off_xoffset in x state vector
xstate vector, position part
off_voffset in v state vector
vstate vector, speed part
Ttime

Reimplemented from chrono::ChAssembly.

◆ IntStateGatherAcceleration()

void chrono::ChSystem::IntStateGatherAcceleration ( const unsigned int  off_a,
ChStateDelta a 
)
overridevirtual

From item's state acceleration to global acceleration vector.

Parameters
off_aoffset in a accel. vector
aacceleration part of state vector derivative

Reimplemented from chrono::ChAssembly.

◆ IntStateGatherReactions()

void chrono::ChSystem::IntStateGatherReactions ( const unsigned int  off_L,
ChVectorDynamic<> &  L 
)
overridevirtual

From item's reaction forces to global reaction vector.

Parameters
off_Loffset in L vector
LL vector of reaction forces

Reimplemented from chrono::ChAssembly.

◆ IntStateIncrement()

void chrono::ChSystem::IntStateIncrement ( const unsigned int  off_x,
ChState x_new,
const ChState x,
const unsigned int  off_v,
const ChStateDelta Dv 
)
overridevirtual

Computes x_new = x + Dt , using vectors at specified offsets.

By default, when DOF = DOF_w, it does just the sum, but in some cases (ex when using quaternions for rotations) it could do more complex stuff, and children classes might overload it.

Parameters
off_xoffset in x state vector
x_newstate vector, position part, incremented result
xstate vector, initial position part
off_voffset in v state vector
Dvstate vector, increment

Reimplemented from chrono::ChAssembly.

◆ IntStateScatter()

void chrono::ChSystem::IntStateScatter ( const unsigned int  off_x,
const ChState x,
const unsigned int  off_v,
const ChStateDelta v,
const double  T 
)
overridevirtual

From global state vectors y={x,v} to item's state (and update) fetching the states at the specified offsets.

Parameters
off_xoffset in x state vector
xstate vector, position part
off_voffset in v state vector
vstate vector, speed part
Ttime

Reimplemented from chrono::ChAssembly.

◆ IntStateScatterAcceleration()

void chrono::ChSystem::IntStateScatterAcceleration ( const unsigned int  off_a,
const ChStateDelta a 
)
overridevirtual

From global acceleration vector to item's state acceleration.

Parameters
off_aoffset in a accel. vector
aacceleration part of state vector derivative

Reimplemented from chrono::ChAssembly.

◆ IntStateScatterReactions()

void chrono::ChSystem::IntStateScatterReactions ( const unsigned int  off_L,
const ChVectorDynamic<> &  L 
)
overridevirtual

From global reaction vector to item's reaction forces.

Parameters
off_Loffset in L vector
LL vector of reaction forces

Reimplemented from chrono::ChAssembly.

◆ IntToDescriptor()

void chrono::ChSystem::IntToDescriptor ( const unsigned int  off_v,
const ChStateDelta v,
const ChVectorDynamic<> &  R,
const unsigned int  off_L,
const ChVectorDynamic<> &  L,
const ChVectorDynamic<> &  Qc 
)
overridevirtual

Prepare variables and constraints to accommodate a solution:

Parameters
off_voffset for v and R
vvector that will be copied into the q 'unknowns' term of the variables (for warm starting)
Rvector that will be copied into the F 'force' term of the variables
off_Loffset for L and Qc
Lvector that will be copied into the L 'lagrangian ' term of the constraints (for warm starting)
Qcvector that will be copied into the Qb 'constraint' term of the constraints

Reimplemented from chrono::ChAssembly.

◆ KRMmatricesLoad()

void chrono::ChSystem::KRMmatricesLoad ( double  Kfactor,
double  Rfactor,
double  Mfactor 
)
overridevirtual

Adds the current stiffness K and damping R and mass M matrices in encapsulated ChKblock item(s), if any.

The K, R, M matrices are added with scaling values Kfactor, Rfactor, Mfactor. NOTE: signs are flipped respect to the ChTimestepper dF/dx terms: K = -dF/dq, R = -dF/dv

Reimplemented from chrono::ChAssembly.

◆ LoadConstraint_C()

void chrono::ChSystem::LoadConstraint_C ( ChVectorDynamic<> &  Qc,
const double  c,
const bool  do_clamp = false,
const double  mclam = 1e30 
)
overridevirtual

Increment a vector Qc with the term C: Qc += c*C.

Parameters
Qcresult: the Qc residual, Qc += c*C
ca scaling factor
do_clampenable optional clamping of Qc
mclamclamping value

Reimplemented from chrono::ChIntegrableIIorder.

◆ LoadConstraint_Ct()

void chrono::ChSystem::LoadConstraint_Ct ( ChVectorDynamic<> &  Qc,
const double  c 
)
overridevirtual

Increment a vector Qc with the term Ct = partial derivative dC/dt: Qc += c*Ct.

Parameters
Qcresult: the Qc residual, Qc += c*Ct
ca scaling factor

Reimplemented from chrono::ChIntegrableIIorder.

◆ LoadResidual_CqL()

void chrono::ChSystem::LoadResidual_CqL ( ChVectorDynamic<> &  R,
const ChVectorDynamic<> &  L,
const double  c 
)
overridevirtual

Increment a vectorR with the term Cq'*L: R += c*Cq'*L.

Parameters
Rresult: the R residual, R += c*Cq'*L
Lthe L vector
ca scaling factor

Reimplemented from chrono::ChIntegrableIIorder.

◆ LoadResidual_F()

void chrono::ChSystem::LoadResidual_F ( ChVectorDynamic<> &  R,
const double  c 
)
overridevirtual

Increment a vector R with the term c*F: R += c*F.

Parameters
Rresult: the R residual, R += c*F
ca scaling factor

Reimplemented from chrono::ChIntegrableIIorder.

◆ LoadResidual_Mv()

void chrono::ChSystem::LoadResidual_Mv ( ChVectorDynamic<> &  R,
const ChVectorDynamic<> &  w,
const double  c 
)
overridevirtual

Increment a vector R with a term that has M multiplied a given vector w: R += c*M*w.

Parameters
Rresult: the R residual, R += c*M*v
wthe w vector
ca scaling factor

Reimplemented from chrono::ChIntegrableIIorder.

◆ NewBody()

virtual ChBody* chrono::ChSystem::NewBody ( )
pure virtual

Create and return the pointer to a new body.

The returned body is created with a contact model consistent with the type of this ChSystem and with the collision system currently associated with this ChSystem. Note that the body is not attached to this system.

Implemented in chrono::ChSystemParallelSMC, chrono::ChSystemParallelNSC, chrono::ChSystemDistributed, chrono::ChSystemSMC, and chrono::ChSystemNSC.

◆ NewBodyAuxRef()

virtual ChBodyAuxRef* chrono::ChSystem::NewBodyAuxRef ( )
pure virtual

Create and return the pointer to a new body with auxiliary reference frame.

The returned body is created with a contact model consistent with the type of this ChSystem and with the collision system currently associated with this ChSystem. Note that the body is not attached to this system.

Implemented in chrono::ChSystemParallelSMC, chrono::ChSystemParallelNSC, chrono::ChSystemDistributed, chrono::ChSystemSMC, and chrono::ChSystemNSC.

◆ Reference_LM_byID()

void chrono::ChSystem::Reference_LM_byID ( )

Given inserted markers and links, restores the pointers of links to markers given the information about the marker IDs.

Will be made obsolete in future with new serialization systems.

◆ RegisterCustomCollisionCallback()

void chrono::ChSystem::RegisterCustomCollisionCallback ( CustomCollisionCallback mcallb)
inline

Specify a callback object to be invoked at each collision detection step.

Multiple such callback objects can be registered with a system. If present, their OnCustomCollision() method is invoked Use this if you want that some specific callback function is executed at each collision detection step (ex. all the times that ComputeCollisions() is automatically called by the integration method). For example some other collision engine could add further contacts using this callback.

◆ SetCollisionSystem()

void chrono::ChSystem::SetCollisionSystem ( std::shared_ptr< collision::ChCollisionSystem newcollsystem)

For higher performance (ex.

when GPU coprocessors are available) you can create your own custom collision engine (inherited from ChCollisionSystem) and plug it into the system using this function. Note: use only before you start adding colliding bodies to the system!

◆ SetDumpSolverMatrices()

void chrono::ChSystem::SetDumpSolverMatrices ( bool  md)
inline

Set this to "true" to enable automatic saving of solver matrices at each time step, for debugging purposes.

Note that matrices will be saved in the working directory of the exe, with format 0001_01_H.dat 0002_01_H.dat (if the timestepper requires multiple solves, also 0001_01. 0001_02.. etc.) The matrices being saved are: dump_Z.dat has the assembled optimization matrix (Matlab sparse format) dump_rhs.dat has the assembled RHS dump_H.dat has usually H=M (mass), but could be also H=a*M+b*K+c*R or such. (Matlab sparse format) dump_Cq.dat has the jacobians (Matlab sparse format) dump_E.dat has the constr.compliance (Matlab sparse format) dump_f.dat has the applied loads dump_b.dat has the constraint rhs as passed to the solver in the problem

 | H -Cq'|*|q|- | f|= |0|
 | Cq -E | |l|  |-b|  |c|

where l \(\in Y, c \in Ny\), normal cone to Y

◆ SetMaxiter()

void chrono::ChSystem::SetMaxiter ( int  m_maxiter)
inline

Sets outer iteration limit for assembly constraints.

When trying to keep constraints together, the iterative process is stopped if this max.number of iterations (or tolerance) is reached.

◆ SetMaxPenetrationRecoverySpeed()

void chrono::ChSystem::SetMaxPenetrationRecoverySpeed ( double  mval)
inline

For the default stepper, you can limit the speed of exiting from penetration situations.

Usually set a positive value, about 0.1 .. 2 . (as exiting speed, in m/s)

◆ SetMinBounceSpeed()

void chrono::ChSystem::SetMinBounceSpeed ( double  mval)
inline

For elastic collisions, with objects that have nonzero restitution coefficient: objects will rebounce only if their relative colliding speed is above this threshold.

Default 0.15 m/s. If this is too low, aliasing problems can happen with small high frequency rebounces, and settling to static stacking might be more difficult.

◆ SetSolverForceTolerance()

void chrono::ChSystem::SetSolverForceTolerance ( double  tolerance)
inline

Set a solver tolerance threshold at force level (default: not specified).

Specify this value only if solving the problem at velocity level (e.g. solving a DVI problem). If this tolerance is specified, it is multiplied by the current integration stepsize and overwrites the current solver tolerance. By default, this tolerance is invalid and hence the solver's own tolerance threshold is used.

◆ SetSolverMaxIterations()

void chrono::ChSystem::SetSolverMaxIterations ( int  max_iters)

Set the maximum number of iterations, if using an iterative solver.

Deprecated:
Prefer using SetSolver and setting solver parameters directly.

◆ SetSolverTolerance()

void chrono::ChSystem::SetSolverTolerance ( double  tolerance)

Set the solver tolerance threshold (used with iterative solvers only).

Note that the stopping criteria differs from solver to solver.

◆ SetSolverType()

void chrono::ChSystem::SetSolverType ( ChSolver::Type  type)
virtual

Choose the solver type, to be used for the simultaneous solution of the constraints in dynamical simulations (as well as in kinematics, statics, etc.)

  • Suggested solver for speed, but lower precision: PSOR
  • Suggested solver for higher precision: BARZILAIBORWEIN or APGD
  • For problems that involve a stiffness matrix: GMRES, MINRES

Notes:

  • This function is a shortcut, internally equivalent to a call to SetSolver().
  • Only a subset of available Chrono solvers can be set through this mechanism.
  • Prefer explicitly creating a solver, setting solver parameters, and then attaching the solver with SetSolver.
Deprecated:
This function does not support all available Chrono solvers. Prefer using SetSolver.

◆ SetStep()

void chrono::ChSystem::SetStep ( double  m_step)
inline

Sets the time step used for integration (dynamical simulation).

The lower this value, the more precise the simulation. Usually, values about 0.01 s are enough for simple simulations. It may be modified automatically by integration methods, if they support automatic time adaption.

◆ SetTimestepperType()

void chrono::ChSystem::SetTimestepperType ( ChTimestepper::Type  type)

Set the method for time integration (time stepper type).

  • Suggested for fast dynamics with hard (NSC) contacts: EULER_IMPLICIT_LINEARIZED
  • Suggested for fast dynamics with hard (NSC) contacts and low inter-penetration: EULER_IMPLICIT_PROJECTED
  • Suggested for finite element smooth dynamics: HHT, EULER_IMPLICIT_LINEARIZED

Notes:

  • for more advanced customization, use SetTimestepper()
  • old methods ANITESCU and TASORA were replaced by EULER_IMPLICIT_LINEARIZED and EULER_IMPLICIT_PROJECTED, respectively

◆ Setup()

void chrono::ChSystem::Setup ( )
overridevirtual

Counts the number of bodies and links.

Computes the offsets of object states in the global state. Assumes that offset_x, offset_w, and offset_L are already set as starting point for offsetting all the contained sub objects.

Reimplemented from chrono::ChAssembly.

Reimplemented in chrono::ChSystemParallelSMC, and chrono::ChSystemParallel.

◆ SetUseSleeping()

void chrono::ChSystem::SetUseSleeping ( bool  ms)
inline

Turn on this feature to let the system put to sleep the bodies whose motion has almost come to a rest.

This feature will allow faster simulation of large scenarios for real-time purposes, but it will affect the precision! This functionality can be turned off selectively for specific ChBodies.

◆ StateIncrementX()

void chrono::ChSystem::StateIncrementX ( ChState x_new,
const ChState x,
const ChStateDelta Dx 
)
overridevirtual

Perform x_new = x + dx, for x in Y = {x, dx/dt}.


It takes care of the fact that x has quaternions, dx has angular vel etc. NOTE: the system is not updated automatically after the state increment, so one might need to call StateScatter() if needed.

Parameters
x_newresulting x_new = x + Dx
xinitial state x
Dxstate increment Dx

Reimplemented from chrono::ChIntegrableIIorder.

◆ StateSolveCorrection()

bool chrono::ChSystem::StateSolveCorrection ( ChStateDelta Dv,
ChVectorDynamic<> &  L,
const ChVectorDynamic<> &  R,
const ChVectorDynamic<> &  Qc,
const double  c_a,
const double  c_v,
const double  c_x,
const ChState x,
const ChStateDelta v,
const double  T,
bool  force_state_scatter = true,
bool  force_setup = true 
)
overridevirtual

Assuming a DAE of the form.

      M*a = F(x,v,t) + Cq'*L
      C(x,t) = 0

this function computes the solution of the change Du (in a or v or x) for a Newton iteration within an implicit integration scheme.

 |Du| = [ G   Cq' ]^-1 * | R |
 |DL|   [ Cq  0   ]      | Qc|

for residual R and G = [ c_a*M + c_v*dF/dv + c_x*dF/dx ].
This function returns true if successful and false otherwise.

Parameters
Dvresult: computed Dv
Lresult: computed lagrangian multipliers, if any
Rthe R residual
Qcthe Qc residual
c_athe factor in c_a*M
c_vthe factor in c_v*dF/dv
c_xthe factor in c_x*dF/dv
xcurrent state, x part
vcurrent state, v part
Tcurrent time T
force_state_scatterif false, x,v and T are not scattered to the system
force_setupif true, call the solver's Setup() function

Reimplemented from chrono::ChIntegrableIIorder.

◆ VariablesFbIncrementMq()

void chrono::ChSystem::VariablesFbIncrementMq ( )
overridevirtual

Adds M*q (masses multiplied current 'qb') to Fb, ex.

if qb is initialized with v_old using VariablesQbLoadSpeed, this method can be used in timestepping schemes that do: M*v_new = M*v_old + forces*dt

Reimplemented from chrono::ChAssembly.

◆ VariablesQbIncrementPosition()

void chrono::ChSystem::VariablesQbIncrementPosition ( double  step)
overridevirtual

Increment item positions by the 'qb' part of the ChVariables, multiplied by a 'step' factor.

pos+=qb*step If qb is a speed, this behaves like a single step of 1-st order numerical integration (Eulero integration).

Reimplemented from chrono::ChAssembly.

◆ VariablesQbLoadSpeed()

void chrono::ChSystem::VariablesQbLoadSpeed ( )
overridevirtual

Initialize the 'qb' part of the ChVariables with the current value of speeds.

Note: since 'qb' is the unknown, this function seems unnecessary, unless used before VariablesFbIncrementMq()

Reimplemented from chrono::ChAssembly.

◆ VariablesQbSetSpeed()

void chrono::ChSystem::VariablesQbSetSpeed ( double  step = 0)
overridevirtual

Fetches the item speed (ex.

linear and angular vel.in rigid bodies) from the 'qb' part of the ChVariables and sets it as the current item speed. If 'step' is not 0, also should compute the approximate acceleration of the item using backward differences, that is accel=(new_speed-old_speed)/step. Mostly used after the solver provided the solution in ChVariables.

Reimplemented from chrono::ChAssembly.

Member Data Documentation

◆ timer_step

ChTimer<double> chrono::ChSystem::timer_step
protected

material composition strategy

timer for integration step


The documentation for this class was generated from the following files:
  • /builds/uwsbel/chrono/src/chrono/physics/ChSystem.h
  • /builds/uwsbel/chrono/src/chrono/physics/ChSystem.cpp