Description

This is the main user interface for Chrono::Distributed Add bodies and set all settings through the system.

The simulation runs on all ranks given in the world parameter.

#include <ChSystemDistributed.h>

Inheritance diagram for chrono::ChSystemDistributed:
Collaboration diagram for chrono::ChSystemDistributed:

Classes

struct  BodyState
 Stores all data needed to fully update the state of a body. More...
 
struct  TriData
 Structure of vertex data for a triangle in the bodies existing local frame. More...
 

Public Types

typedef struct chrono::ChSystemDistributed::BodyState BodyState
 Stores all data needed to fully update the state of a body.
 
typedef struct chrono::ChSystemDistributed::TriData TriData
 Structure of vertex data for a triangle in the bodies existing local frame.
 

Public Member Functions

 ChSystemDistributed (MPI_Comm communicator, double ghostlayer, unsigned int maxobjects)
 Construct a distributed Chrono system using the specified MPI communicator.
 
MPI_Comm GetCommunicator () const
 Return the system's MPI intra-communicator.
 
int GetCommSize () const
 Return the size of the group associated with the system's intra-communicator.
 
int GetCommRank () const
 Return the rank of the calling process in the system's intra-communicator.
 
void SetMaster ()
 Set the calling process as 'master' in the intra-communicator used by this system. More...
 
int GetMasterRank () const
 Return the rank (in the system's intra-communicator) of the process marked as 'master'. More...
 
bool OnMaster () const
 Return true if the calling process is the one marked as 'master'.
 
void SetGhostLayer (double ghostlayer)
 Set the distance into the neighboring sub-domain that is considered shared.
 
double GetGhostLayer () const
 Return the distance into the neighboring sub-domain that is considered shared.
 
unsigned int GetNumBodiesGlobal () const
 Return the current global number of bodies in the system.
 
bool InSub (const ChVector< double > &pos) const
 Return true if pos is within this rank's sub-domain.
 
virtual ChBodyNewBody () override
 Create a new body, consistent with the contact method and collision model used by this system. More...
 
virtual ChBodyAuxRefNewBodyAuxRef () override
 Create a new body with non-centroidal reference frame, consistent with the contact method and collision model used by this system. More...
 
virtual void AddBody (std::shared_ptr< ChBody > newbody) override
 Add a body to the system. More...
 
void AddBodyAllRanks (std::shared_ptr< ChBody > body)
 Add a body to the system on all ranks, regardless of its location. More...
 
virtual void RemoveBody (std::shared_ptr< ChBody > body) override
 Remove a body from the simulation based on the ID of the body (not based on object comparison between ChBodys). More...
 
virtual bool Integrate_Y () override
 Wraps the super-class Integrate_Y call and introduces a call that carries out all inter-rank communication.
 
virtual void UpdateRigidBodies () override
 Wraps super-class UpdateRigidBodies and adds a gid update.
 
void RemoveBodyExchange (int index)
 Internal call for removing deactivating a body. More...
 
ChDomainDistributedGetDomain () const
 Returns the ChDomainDistributed object associated with the system.
 
ChCommDistributedGetComm () const
 Returns the ChCommDistributed object associated with the system.
 
void ErrorAbort (std::string msg)
 Prints msg to the user and ends execution with an MPI abort.
 
void PrintBodyStatus ()
 Prints out all valid body data. Should only be used for debugging.
 
void PrintShapeData ()
 Prints out all valid shape data. Should only be used for debugging.
 
void PrintEfficiency ()
 Prints measures for computing efficiency.
 
double GetLowestZ (uint *gid)
 Debugging function.
 
double GetHighestZ ()
 Returns the highest z coordinate in the system.
 
void CheckIds ()
 Checks for consistency in IDs in the system. More...
 
int RemoveBodiesBelow (double z)
 Removes all bodies below the given height - initial implementation of a deactivating boundary condition.
 
void SanityCheck ()
 Checks structures added by chrono_distributed. More...
 
void SetBodyStates (const std::vector< uint > &gids, const std::vector< BodyState > &states)
 Updates the states of all bodies listed in the gids parameter Must be called on all system ranks and inputs must be complete and valid on each rank. More...
 
void SetBodyState (uint gid, const BodyState &state)
 
void SetSphereShapes (const std::vector< uint > &gids, const std::vector< int > &shape_idx, const std::vector< double > &radii)
 Updates each sphere shape associated with bodies with global ids gids. More...
 
void SetSphereShape (uint gid, int shape_idx, double radius)
 
void SetTriangleShapes (const std::vector< uint > &gids, const std::vector< int > &shape_idx, const std::vector< TriData > &new_shapes)
 Updates triangle shapes associated with bodies identified by gids. More...
 
void SetTriangleShape (uint gid, int shape_idx, const TriData &new_shape)
 
std::vector< std::pair< uint, ChVector<> > > GetBodyContactForces (const std::vector< uint > &gids) const
 Get contact forces experienced by any of the bodies specified through their global IDs. More...
 
virtual real3 GetBodyContactForce (uint gid) const override
 Get the contact force experienced by the body with given global ID. More...
 
- Public Member Functions inherited from chrono::ChSystemMulticoreSMC
 ChSystemMulticoreSMC (const ChSystemMulticoreSMC &other)
 
virtual ChSystemMulticoreSMCClone () const override
 "Virtual" copy constructor (covariant return type).
 
virtual ChContactMethod GetContactMethod () const override
 Return the contact method supported by this system. More...
 
virtual void AddMaterialSurfaceData (std::shared_ptr< ChBody > newbody) override
 
virtual void UpdateMaterialSurfaceData (int index, ChBody *body) override
 
virtual void Setup () override
 Counts the number of bodies and links. More...
 
virtual void SetCollisionSystemType (ChCollisionSystemType type) override
 Change the underlying collision detection system to the specified type. More...
 
virtual void SetContactContainer (ChCollisionSystemType type) override
 Change the underlying contact container given the specified type of the collision detection system. More...
 
virtual void SetContactContainer (std::shared_ptr< ChContactContainer > container) override
 Change the underlying contact container. More...
 
virtual real3 GetBodyContactTorque (uint body_id) const override
 Get the contact torque on the body with specified id. More...
 
virtual void PrintStepStats () override
 
double GetTimerProcessContact () const
 
virtual real3 GetBodyContactForce (uint body_id) const=0
 Get the contact force on the body with specified id. More...
 
real3 GetBodyContactForce (std::shared_ptr< ChBody > body) const
 Get the contact force on the specified body. More...
 
virtual real3 GetBodyContactTorque (uint body_id) const=0
 Get the contact torque on the body with specified id. More...
 
real3 GetBodyContactTorque (std::shared_ptr< ChBody > body) const
 Get the contact torque on the specified body. More...
 
- Public Member Functions inherited from chrono::ChSystemMulticore
 ChSystemMulticore (const ChSystemMulticore &other)
 
virtual void AddShaft (std::shared_ptr< ChShaft > shaft) override
 Attach a shaft to the underlying assembly.
 
virtual void AddLink (std::shared_ptr< ChLinkBase > link) override
 Attach a link to the underlying assembly.
 
virtual void AddOtherPhysicsItem (std::shared_ptr< ChPhysicsItem > newitem) override
 Attach a ChPhysicsItem object that is not a body, link, or mesh.
 
void ClearForceVariables ()
 
virtual void Update ()
 
virtual void UpdateBilaterals ()
 
virtual void UpdateLinks ()
 
virtual void UpdateOtherPhysics ()
 
virtual void UpdateShafts ()
 
virtual void UpdateMotorLinks ()
 
virtual void Update3DOFBodies ()
 
void RecomputeThreads ()
 
virtual void SetMaterialCompositionStrategy (std::unique_ptr< ChMaterialCompositionStrategy > &&strategy) override
 Change the default composition laws for contact surface materials (coefficient of friction, cohesion, compliance, etc.).
 
unsigned int GetNumBodies ()
 
unsigned int GetNumShafts ()
 
unsigned int GetNumContacts ()
 
unsigned int GetNumBilaterals ()
 
virtual double GetTimerStep () const override
 Return the time (in seconds) spent for computing the time step.
 
virtual double GetTimerAdvance () const override
 Return the time (in seconds) for time integration, within the time step.
 
virtual double GetTimerLSsolve () const override
 Return the time (in seconds) for the solver, within the time step. More...
 
virtual double GetTimerLSsetup () const override
 Return the time (in seconds) for the solver Setup phase, within the time step.
 
virtual double GetTimerJacobian () const override
 Return the time (in seconds) for calculating/loading Jacobian information, within the time step.
 
virtual double GetTimerCollision () const override
 Return the time (in seconds) for runnning the collision detection step, within the time step.
 
virtual double GetTimerSetup () const override
 Return the time (in seconds) for system setup, within the time step.
 
virtual double GetTimerUpdate () const override
 Return the time (in seconds) for updating auxiliary data, within the time step.
 
void CalculateBodyAABB ()
 Calculate current body AABBs.
 
virtual void CalculateContactForces ()
 Calculate cummulative contact forces for all bodies in the system. More...
 
virtual ChVector GetBodyAppliedForce (ChBody *body) override
 Return the resultant applied force on the specified body. More...
 
virtual ChVector GetBodyAppliedTorque (ChBody *body) override
 Return the resultant applied torque on the specified body. More...
 
real3 GetBodyContactForce (std::shared_ptr< ChBody > body) const
 Get the contact force on the specified body. More...
 
real3 GetBodyContactTorque (std::shared_ptr< ChBody > body) const
 Get the contact torque on the specified body. More...
 
settings_containerGetSettings ()
 
virtual void SetNumThreads (int num_threads_chrono, int num_threads_collision=0, int num_threads_eigen=0) override
 Set the number of OpenMP threads used by Chrono itself, Eigen, and the collision detection system. More...
 
void EnableThreadTuning (int min_threads, int max_threads)
 Enable dynamic adjustment of number of threads between the specified limits. More...
 
double CalculateConstraintViolation (std::vector< double > &cvec)
 Calculate the (linearized) bilateral constraint violations. More...
 
- Public Member Functions inherited from chrono::ChSystem
 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 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.
 
const ChMaterialCompositionStrategyGetMaterialCompositionStrategy () 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.
 
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)
 Set the G (gravity) acceleration vector, affecting all the bodies in the system.
 
const ChVectorGet_G_acc () const
 Get the G (gravity) acceleration vector affecting all the bodies in the system.
 
double GetChTime () const
 Get the simulation time of this system.
 
void SetChTime (double time)
 Set (overwrite) the simulation time of this system.
 
int RemoveRedundantConstraints (bool remove_zero_constr=false, double qr_tol=1e-6, bool verbose=false)
 Remove redundant constraints present in ChSystem through QR decomposition of constraints Jacobian matrix. More...
 
int GetNumThreadsChrono () const
 
int GetNumthreadsCollision () const
 
int GetNumthreadsEigen () const
 
const ChAssemblyGetAssembly () const
 Get the underlying assembly containing all physics items.
 
virtual void AddMesh (std::shared_ptr< fea::ChMesh > mesh)
 Attach a mesh to the underlying assembly.
 
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 RemoveShaft (std::shared_ptr< ChShaft > shaft)
 Remove a shaft 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 underlying assembly.
 
void RemoveAllBodies ()
 Remove all bodies from the underlying assembly.
 
void RemoveAllShafts ()
 Remove all shafts from the underlying assembly.
 
void RemoveAllLinks ()
 Remove all links from the underlying assembly.
 
void RemoveAllMeshes ()
 Remove all meshes from the underlying 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< ChShaft > > & Get_shaftlist () const
 Get the list of shafts.
 
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 std::string &name) const
 Search a body by its name.
 
std::shared_ptr< ChBodySearchBodyID (int id) const
 Search a body by its ID.
 
std::shared_ptr< ChShaftSearchShaft (const std::string &name) const
 Search a shaft by its name.
 
std::shared_ptr< ChLinkBaseSearchLink (const std::string &name) const
 Search a link by its name.
 
std::shared_ptr< fea::ChMeshSearchMesh (const std::string &name) const
 Search a mesh by its name.
 
std::shared_ptr< ChPhysicsItemSearchOtherPhysicsItem (const std::string &name) const
 Search from other ChPhysics items (not bodies, links, or meshes) by name.
 
std::shared_ptr< ChMarkerSearchMarker (const std::string &name) const
 Search a marker by its name.
 
std::shared_ptr< ChMarkerSearchMarker (int id) const
 Search a marker by its unique ID.
 
std::shared_ptr< ChPhysicsItemSearch (const std::string &name) const
 Search an item (body, link or other ChPhysics items) by name.
 
int GetNbodies () const
 Get the number of active bodies (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 in the assembly, including the grounded and sleeping bodies.
 
int GetNshafts () const
 Get the number of shafts.
 
int GetNshaftsSleeping () const
 Get the number of shafts that are in sleeping mode (excluding fixed shafts).
 
int GetNshaftsFixed () const
 Get the number of shafts that are fixed to ground.
 
int GetNshaftsTotal () const
 Get the total number of shafts added to the assembly, including the grounded and sleeping shafts.
 
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).
 
int GetDOF () const
 Get the number of scalar coordinates (ex. dim of position vector)
 
int GetDOF_w () const
 Get the number of scalar coordinates of variables derivatives (ex. dim of speed vector)
 
int GetDOC () const
 Get the number of scalar constraints, if any, in this item.
 
int GetDOC_c () const
 Get the number of scalar constraints, if any, in this item (only bilateral constr.)
 
int GetDOC_d () const
 Get the number of scalar constraints, if any, in this item (only unilateral constr.)
 
void ShowHierarchy (ChStreamOutAscii &m_file, int level=0) const
 Write the hierarchy of contained bodies, markers, etc. More...
 
void Clear ()
 Removes all bodies/marker/forces/links/contacts, also resets timers and events.
 
int GetNcontacts ()
 Gets the number of contacts.
 
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.
 
double GetRTF () const
 Get current estimated RTF (real time factor).
 
void SetRTF (double rtf)
 Set (overwrite) the RTF value for this system (if calculated externally).
 
void ResetTimers ()
 Resets the timers.
 
void Update (double mytime, bool update_assets=true)
 Updates all the auxiliary data and children of bodies, forces, links, given their current state.
 
void Update (bool update_assets=true)
 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...
 
void IntToDescriptor (const unsigned int off_v, const ChStateDelta &v, const ChVectorDynamic<> &R, const unsigned int off_L, const ChVectorDynamic<> &L, const ChVectorDynamic<> &Qc)
 
void IntFromDescriptor (const unsigned int off_v, ChStateDelta &v, const unsigned int off_L, ChVectorDynamic<> &L)
 
void InjectVariables (ChSystemDescriptor &mdescriptor)
 
void InjectConstraints (ChSystemDescriptor &mdescriptor)
 
void ConstraintsLoadJacobians ()
 
void InjectKRMmatrices (ChSystemDescriptor &mdescriptor)
 
void KRMmatricesLoad (double Kfactor, double Rfactor, double Mfactor)
 
void VariablesFbReset ()
 
void VariablesFbLoadForces (double factor=1)
 
void VariablesQbLoadSpeed ()
 
void VariablesFbIncrementMq ()
 
void VariablesQbSetSpeed (double step=0)
 
void VariablesQbIncrementPosition (double step)
 
void ConstraintsBiReset ()
 
void ConstraintsBiLoad_C (double factor=1, double recovery_clamp=0.1, bool do_clamp=false)
 
void ConstraintsBiLoad_Ct (double factor=1)
 
void ConstraintsBiLoad_Qc (double factor=1)
 
void ConstraintsFbLoadForces (double factor=1)
 
void ConstraintsFetch_react (double factor=1)
 
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, bool full_update) override
 From state Y={x,v} to system. This also triggers an update operation.
 
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, bool full_update, bool force_setup) 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 clamp=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...
 
double ComputeCollisions ()
 Perform the collision detection. More...
 
void RegisterCustomCollisionCallback (std::shared_ptr< CustomCollisionCallback > callback)
 Specify a callback object to be invoked at each collision detection step. More...
 
void UnregisterCustomCollisionCallback (std::shared_ptr< CustomCollisionCallback > callback)
 Remove the given collision callback from this system.
 
virtual void SetCollisionSystem (std::shared_ptr< ChCollisionSystem > coll_sys)
 Change the underlying collision system. More...
 
std::shared_ptr< ChCollisionSystemGetCollisionSystem () const
 Access the underlying collision system. More...
 
std::shared_ptr< ChContactContainerGetContactContainer () const
 Access the underlying contact container. More...
 
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 step_size)
 Advances the dynamical simulation for a single step, of length step_size. More...
 
bool DoFrameDynamics (double end_time)
 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 (double end_time)
 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 end_time, 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 EnableSolverMatrixWrite (bool val, const std::string &out_dir=".")
 Set this to "true" to enable automatic saving of solver matrices at each time step, for debugging purposes. More...
 
bool IsSolverMatrixWriteEnabled () 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 step_size)
 Advances the kinematic simulation for a single step of given length.
 
bool DoFrameKinematics (double end_time)
 Performs kinematics until the end time is exactly reached. More...
 
bool DoEntireKinematics (double end_time)
 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 DoStaticAnalysis (ChStaticAnalysis &analysis)
 Perform a generic static analysis. More...
 
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 DoStaticNonlinearRheonomic (int nsteps=10, bool verbose=false, std::shared_ptr< ChStaticNonLinearRheonomicAnalysis::IterationCallback > callback=nullptr)
 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)
 Method to allow serialization of transient data to archives.
 
virtual void ArchiveIn (ChArchiveIn &marchive)
 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::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, bool full_update)
 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, bool full_update) 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, bool full_update) 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, bool full_update, bool force_setup) override final
 Override of method for Ist order implicit integrators. More...
 
- 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...
 

Public Attributes

ChDistributedDataManagerddm
 Central data storages for chrono_distributed. More...
 
char node_name [50]
 Name of the node being run on.
 
- Public Attributes inherited from chrono::ChSystemMulticore
ChMulticoreDataManagerdata_manager
 
int current_threads
 

Protected Member Functions

void AddBodyExchange (std::shared_ptr< ChBody > newbody, distributed::COMM_STATUS status)
 Internal function for adding a body from communication. More...
 
- Protected Member Functions inherited from chrono::ChSystem
virtual void DescriptorPrepareInject (ChSystemDescriptor &mdescriptor)
 Pushes all ChConstraints and ChVariables contained in links, bodies, etc. into the system descriptor.
 
void SetupInitial ()
 Initial system setup before analysis. More...
 

Protected Attributes

int num_ranks
 Number of MPI ranks.
 
int my_rank
 MPI rank.
 
int master_rank
 Master MPI rank.
 
double ghost_layer
 Length into the neighboring sub-domain which is considered shared.
 
unsigned int num_bodies_global
 Number of bodies in the whole global simulation. More...
 
MPI_Comm world
 Communicator of MPI ranks for the simulation.
 
ChDomainDistributeddomain
 Class for domain decomposition.
 
ChCommDistributedcomm
 Class for MPI communication.
 
MPI_Datatype InternalForceType
 Type for internally sending contact forces.
 
- Protected Attributes inherited from chrono::ChSystemMulticore
double old_timer
 
double old_timer_cd
 
bool detect_optimal_threads
 
int detect_optimal_bins
 
std::vector< double > timer_accumulator
 
std::vector< double > cd_accumulator
 
uint frame_threads
 
uint frame_bins
 
uint counter
 
std::vector< ChLink * >::iterator it
 
- Protected Attributes inherited from chrono::ChSystem
ChAssembly assembly
 
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)
 
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)
 
double ch_time
 simulation time of the system
 
double step
 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 write_matrix
 write current system matrix to file(s); for debugging
 
std::string output_dir
 output directory for writing system matrices
 
int ncontacts
 total number of contacts
 
ChCollisionSystemType collision_system_type
 type of the collision engine
 
std::shared_ptr< ChCollisionSystemcollision_system
 collision engine
 
std::vector< std::shared_ptr< CustomCollisionCallback > > collision_callbacks
 user-defined collision callbacks
 
std::unique_ptr< ChMaterialCompositionStrategycomposition_strategy
 
ChVisualSystemvisual_system
 material composition strategy More...
 
int nthreads_chrono
 
int nthreads_eigen
 
int nthreads_collision
 
ChTimer timer_step
 timer for integration step
 
ChTimer timer_advance
 timer for time integration
 
ChTimer timer_ls_solve
 timer for solver (excluding setup phase)
 
ChTimer timer_ls_setup
 timer for solver setup
 
ChTimer timer_jacobian
 timer for computing/loading Jacobian information
 
ChTimer timer_collision
 timer for collision detection
 
ChTimer timer_setup
 timer for system setup
 
ChTimer timer_update
 timer for system update
 
double m_RTF
 real-time factor (simulation time / simulated time)
 
std::shared_ptr< ChTimesteppertimestepper
 time-stepper object
 
bool last_err
 indicates error over the last kinematic/dynamics/statics
 
ChVectorDynamic applied_forces
 system-wide vector of applied forces (lazy evaluation)
 
bool applied_forces_current
 indicates if system-wide vector of forces is up-to-date
 

Friends

class ChCommDistributed
 
class ChDomainDistributed
 

Member Function Documentation

◆ AddBody()

void ChSystemDistributed::AddBody ( std::shared_ptr< ChBody newbody)
overridevirtual

Add a body to the system.

This function should be called on all ranks. AddBody classifies the body and decides whether or not to keep it on each rank.

Reimplemented from chrono::ChSystemMulticore.

◆ AddBodyAllRanks()

void ChSystemDistributed::AddBodyAllRanks ( std::shared_ptr< ChBody body)

Add a body to the system on all ranks, regardless of its location.

This body should not have associated collision geometry. NOTE: A body crossing multiple sub-domains will not be correctly advanced.

◆ AddBodyExchange()

void ChSystemDistributed::AddBodyExchange ( std::shared_ptr< ChBody newbody,
distributed::COMM_STATUS  status 
)
protected

Internal function for adding a body from communication.

Should not be called by the user.

◆ CheckIds()

void ChSystemDistributed::CheckIds ( )

Checks for consistency in IDs in the system.

Should only be used for debugging.

◆ GetBodyContactForce()

real3 ChSystemDistributed::GetBodyContactForce ( uint  gid) const
overridevirtual

Get the contact force experienced by the body with given global ID.

Must be called on all system ranks; return value valid only on 'master' rank.

Reimplemented from chrono::ChSystemMulticoreSMC.

◆ GetBodyContactForces()

std::vector< std::pair< uint, ChVector<> > > ChSystemDistributed::GetBodyContactForces ( const std::vector< uint > &  gids) const

Get contact forces experienced by any of the bodies specified through their global IDs.

Must be called on all system ranks; return value valid only on 'master' rank. Returns a vector of pairs of global IDs and corresponding contact forces.

◆ GetMasterRank()

int chrono::ChSystemDistributed::GetMasterRank ( ) const
inline

Return the rank (in the system's intra-communicator) of the process marked as 'master'.

Certain functions return information only on this process.

◆ NewBody()

ChBody * ChSystemDistributed::NewBody ( )
overridevirtual

Create a new body, consistent with the contact method and collision model used by this system.

The returned body is not added to the system.

Reimplemented from chrono::ChSystemMulticore.

◆ NewBodyAuxRef()

ChBodyAuxRef * ChSystemDistributed::NewBodyAuxRef ( )
overridevirtual

Create a new body with non-centroidal reference frame, consistent with the contact method and collision model used by this system.

The returned body is not added to the system.

Reimplemented from chrono::ChSystemMulticore.

◆ RemoveBody()

void ChSystemDistributed::RemoveBody ( std::shared_ptr< ChBody body)
overridevirtual

Remove a body from the simulation based on the ID of the body (not based on object comparison between ChBodys).

Should be called on all ranks to ensure that the correct body is found and removed where it exists.

Reimplemented from chrono::ChSystem.

◆ RemoveBodyExchange()

void ChSystemDistributed::RemoveBodyExchange ( int  index)

Internal call for removing deactivating a body.

Should not be called by the user.

◆ SanityCheck()

void ChSystemDistributed::SanityCheck ( )

Checks structures added by chrono_distributed.

Prints ERROR messages at inconsistencies.

◆ SetBodyStates()

void ChSystemDistributed::SetBodyStates ( const std::vector< uint > &  gids,
const std::vector< BodyState > &  states 
)

Updates the states of all bodies listed in the gids parameter Must be called on all system ranks and inputs must be complete and valid on each rank.

NOTE: The change in position should be small in comparison to the ghost layer of this system. NOTE: The new states will reach the data_manager at the beginning of the next time step.

◆ SetMaster()

void chrono::ChSystemDistributed::SetMaster ( )
inline

Set the calling process as 'master' in the intra-communicator used by this system.

For efficiency, certain functions report information only on this single rank. This saves a potentially unnecessary scatter operation (if needed, such an operation should be performed in user code). By default this is rank 0 in the system's intra-communicator.

◆ SetSphereShapes()

void ChSystemDistributed::SetSphereShapes ( const std::vector< uint > &  gids,
const std::vector< int > &  shape_idx,
const std::vector< double > &  radii 
)

Updates each sphere shape associated with bodies with global ids gids.

shape_idx identifies the index of the shape within its body's collisionsystem model. Must be called on all system ranks and inputs must be complete and valid on each rank.

◆ SetTriangleShapes()

void ChSystemDistributed::SetTriangleShapes ( const std::vector< uint > &  gids,
const std::vector< int > &  shape_idx,
const std::vector< TriData > &  new_shapes 
)

Updates triangle shapes associated with bodies identified by gids.

shape_idx identifies the index of the shape within its body's collisionsystem model. Must be called on all system ranks and inputs must be complete and valid on each rank.

Member Data Documentation

◆ ddm

ChDistributedDataManager* chrono::ChSystemDistributed::ddm

Central data storages for chrono_distributed.

Adds scaffolding data around ChDataManager used by Chrono::Multicore in order to maintain a consistent and correct view of all valid data.

◆ num_bodies_global

unsigned int chrono::ChSystemDistributed::num_bodies_global
protected

Number of bodies in the whole global simulation.

Important for maintaining unique global IDs


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