chrono::gpu::ChSystemGpuMesh Class Reference

Description

Interface to a Chrono::Gpu mesh system.

#include <ChSystemGpu.h>

Inheritance diagram for chrono::gpu::ChSystemGpuMesh:
Collaboration diagram for chrono::gpu::ChSystemGpuMesh:

Public Member Functions

 ChSystemGpuMesh (float sphere_rad, float density, const ChVector3f &boxDims, ChVector3f O=ChVector3f(0))
 Construct system with given sphere radius, density, big domain dimensions and center.
 
 ChSystemGpuMesh (const std::string &checkpoint)
 Construct system with a checkpoint file.
 
unsigned int AddMesh (std::shared_ptr< ChTriangleMeshConnected > mesh, float mass)
 Add a trimesh to the granular system. More...
 
unsigned int AddMesh (const std::string &filename, const ChVector3f &translation, const ChMatrix33< float > &rotscale, float mass)
 Add a trimesh from the specified Wavefront OBJ file to the granular system. More...
 
std::vector< unsigned int > AddMeshes (const std::vector< std::string > &objfilenames, const std::vector< ChVector3f > &translations, const std::vector< ChMatrix33< float >> &rotscales, const std::vector< float > &masses)
 Add a set of trimeshes from Wavefront OBJ files into granular system. More...
 
void EnableMeshCollision (bool val)
 Enable/disable mesh collision (for all defined meshes).
 
void UseMeshNormals (bool val)
 Enable/disable mesh normal-based orientation correction.
 
void ApplyMeshMotion (unsigned int mesh_id, const ChVector3d &pos, const ChQuaternion<> &rot, const ChVector3d &lin_vel, const ChVector3d &ang_vel)
 Apply rigid body motion to specified mesh.
 
unsigned int GetNumMeshes () const
 Return the number of meshes in the system.
 
std::shared_ptr< ChTriangleMeshConnectedGetMesh (unsigned int mesh_id) const
 Return the specified mesh in the system. More...
 
float GetMeshMass (unsigned int mesh_id) const
 Return the mass of the specified mesh. More...
 
void SetStaticFrictionCoeff_SPH2MESH (float mu)
 Set sphere-to-mesh static friction coefficient.
 
void SetRollingCoeff_SPH2MESH (float mu)
 Set sphere-to-mesh rolling friction coefficient.
 
void SetSpinningCoeff_SPH2MESH (float mu)
 Set sphere-to-mesh spinning friction coefficient.
 
void SetKn_SPH2MESH (double someValue)
 Set sphere-to-mesh normal contact stiffness.
 
void SetGn_SPH2MESH (double someValue)
 Set sphere-to-mesh normal damping coefficient.
 
void SetKt_SPH2MESH (double someValue)
 Set sphere-to-mesh tangential contact stiffness.
 
void SetGt_SPH2MESH (double someValue)
 Set sphere-to-mesh tangential damping coefficient.
 
void UseMaterialBasedModel (bool val)
 
void SetYoungModulus_MESH (double someValue)
 Set material-based contact model parameters.
 
void SetPoissonRatio_MESH (double someValue)
 
void SetRestitution_MESH (double someValue)
 
void SetAdhesionRatio_SPH2MESH (float someValue)
 Set the ratio of adhesion force to sphere weight for sphere to mesh.
 
void SetMeshVerbosity (CHGPU_MESH_VERBOSITY level)
 Set verbosity level of mesh operations.
 
virtual void Initialize () override
 Initialize simulation so that it can be advanced. More...
 
void InitializeMeshes ()
 Initialize only the trimeshes (assumes the granular material was already initialized). More...
 
virtual double AdvanceSimulation (float duration) override
 Advance simulation by duration in user units, return actual duration elapsed. More...
 
void CollectMeshContactForces (std::vector< ChVector3d > &forces, std::vector< ChVector3d > &torques)
 Collect contact forces exerted on all meshes by the granular system.
 
void CollectMeshContactForces (int mesh, ChVector3d &force, ChVector3d &torque)
 Collect contact forces exerted on the specified meshe by the granular system.
 
void ReadCheckpointFile (const std::string &infilename, bool overwrite=false)
 GpuMesh version of checkpoint loading from a file.
 
void WriteCheckpointFile (const std::string &outfilename)
 GpuMesh version of checkpoint generating subroutine. Has a bit more content than parent.
 
void WriteMesh (const std::string &outfilename, unsigned int i) const
 Write the i-th mesh cached in m_meshes, with the current position.
 
void WriteMeshes (const std::string &outfilename) const
 Write all the meshes cached in m_meshes into a combined file, with their current positions.
 
- Public Member Functions inherited from chrono::gpu::ChSystemGpu
 ChSystemGpu (float sphere_rad, float density, const ChVector3f &boxDims, ChVector3f O=ChVector3f(0))
 Construct system with given sphere radius, density, big domain dimensions and center.
 
 ChSystemGpu (const std::string &checkpoint)
 Construct system with a checkpoint file.
 
void SetGravitationalAcceleration (const ChVector3f &g)
 Set gravitational acceleration vector.
 
void SetParticles (const std::vector< ChVector3f > &points, const std::vector< ChVector3f > &vels=std::vector< ChVector3f >(), const std::vector< ChVector3f > &ang_vels=std::vector< ChVector3f >())
 Set particle positions, velocities and angular velocities.
 
void ReadParticleFile (const std::string &infilename)
 Set particle positions, velocities and angular velocities from a file.
 
void ReadContactHistoryFile (const std::string &infilename)
 Set particle contact friction history from a file.
 
void ReadCheckpointFile (const std::string &infilename, bool overwrite=false)
 
void SetBDFixed (bool fixed)
 Set the big domain to be fixed or not. More...
 
void SetBDCenter (const ChVector3f &O)
 Set the center of the big box domain, relative to the origin of the coordinate system (default: [0,0,0]). More...
 
void SetParticleFixed (const std::vector< bool > &fixed)
 Set flags indicating whether or not a particle is fixed. More...
 
void SetParticleOutputMode (CHGPU_OUTPUT_MODE mode)
 Set the output mode of the simulation.
 
void SetParticleOutputFlags (unsigned int flags)
 Set output settings bit flags by bitwise ORing settings in CHGPU_OUTPUT_FLAGS.
 
void SetFixedStepSize (float size_UU)
 Set timestep size.
 
void SetDefragmentOnInitialize (bool defragment)
 If yes, on Initialize(), particles will have their order re-arranged so that those in the same SD are close together. More...
 
void EnableMinLength (bool useMinLen)
 Ensure that the deformation-based length unit is used.
 
void DisableMinLength ()
 
void SetTimeIntegrator (CHGPU_TIME_INTEGRATOR new_integrator)
 Set the time integration scheme for the system.
 
void SetFrictionMode (CHGPU_FRICTION_MODE new_mode)
 Set friction formulation. More...
 
void SetRollingMode (CHGPU_ROLLING_MODE new_mode)
 Set rolling resistence formulation. More...
 
void SetStaticFrictionCoeff_SPH2SPH (float mu)
 Set sphere-to-sphere static friction coefficient.
 
void SetStaticFrictionCoeff_SPH2WALL (float mu)
 Set sphere-to-wall static friction coefficient.
 
void SetRollingCoeff_SPH2SPH (float mu)
 Set sphere-to-sphere rolling friction coefficient – units and use vary by rolling friction mode.
 
void SetRollingCoeff_SPH2WALL (float mu)
 Set sphere-to-wall rolling friction coefficient – units and use vary by rolling friction mode.
 
void SetSpinningCoeff_SPH2SPH (float mu)
 Set sphere-to-sphere spinning friction coefficient – units and use vary by spinning friction mode.
 
void SetSpinningCoeff_SPH2WALL (float mu)
 Set sphere-to-wall spinning friction coefficient – units and use vary by spinning friction mode.
 
void SetKn_SPH2SPH (double someValue)
 Set sphere-to-sphere normal contact stiffness.
 
void SetKn_SPH2WALL (double someValue)
 Set sphere-to-wall normal contact stiffness.
 
void SetGn_SPH2SPH (double someValue)
 Set sphere-to-sphere normal damping coefficient.
 
void SetGn_SPH2WALL (double someValue)
 Set sphere-to-wall normal damping coefficient.
 
void SetKt_SPH2SPH (double someValue)
 Set sphere-to-sphere tangential contact stiffness.
 
void SetGt_SPH2SPH (double someValue)
 Set sphere-to-sphere tangential damping coefficient.
 
void SetKt_SPH2WALL (double someValue)
 Set sphere-to-wall tangential contact stiffness.
 
void SetGt_SPH2WALL (double someValue)
 Set sphere-to-wall tangential damping coefficient.
 
void SetCohesionRatio (float someValue)
 Set the ratio of cohesion to gravity for monodisperse spheres. Assumes a constant cohesion model.
 
void SetAdhesionRatio_SPH2WALL (float someValue)
 Set the ratio of adhesion to gravity for sphere to wall. Assumes a constant cohesion model.
 
void UseMaterialBasedModel (bool val)
 
void SetYoungModulus_SPH (double someValue)
 Set youngs modulus of spheres.
 
void SetYoungModulus_WALL (double someValue)
 Set youngs modulus of boundary.
 
void SetPoissonRatio_SPH (double someValue)
 Set poisson ratio of sphere.
 
void SetPoissonRatio_WALL (double someValue)
 Set poisson ratio of boundary.
 
void SetRestitution_SPH (double someValue)
 Set coefficient of restitution of spheres.
 
void SetRestitution_WALL (double someValue)
 Set coefficient of restitution of spheres.
 
void SetMaxSafeVelocity_SU (float max_vel)
 Safety check velocity to ensure the simulation is still stable.
 
void SetPsiFactors (unsigned int psi_T, unsigned int psi_L, float psi_R=1.f)
 Set tuning psi factors for tuning the non-dimensionalization.
 
void SetPsiT (unsigned int psi_T)
 
void SetPsiL (unsigned int psi_L)
 
void SetPsiR (float psi_R=1.f)
 
void SetRecordingContactInfo (bool record)
 Enable/disable recording of contact info.
 
void SetSimTime (float time)
 Manually set the simulation time (mainly used for restarted simulation).
 
void SetVerbosity (CHGPU_VERBOSITY level)
 Set simualtion verbosity level.
 
size_t CreateBCSphere (const ChVector3f &center, float radius, bool outward_normal, bool track_forces, float mass)
 Create an axis-aligned sphere boundary condition.
 
size_t CreateBCConeZ (const ChVector3f &tip, float slope, float hmax, float hmin, bool outward_normal, bool track_forces)
 Create a Z-axis aligned cone boundary condition.
 
size_t CreateBCPlane (const ChVector3f &pos, const ChVector3f &normal, bool track_forces)
 Create a plane boundary condition.
 
size_t CreateCustomizedPlate (const ChVector3f &pos_center, const ChVector3f &normal, float hdim_y)
 create a plate boundary condition
 
size_t CreateBCCylinderZ (const ChVector3f &center, float radius, bool outward_normal, bool track_forces)
 Create a Z-axis aligned cylinder boundary condition.
 
bool DisableBCbyID (size_t BC_id)
 Disable a boundary condition by its ID, returns false if the BC does not exist.
 
bool EnableBCbyID (size_t BC_id)
 Enable a boundary condition by its ID, returns false if the BC does not exist.
 
bool SetBCOffsetFunction (size_t BC_id, const GranPositionFunction &offset_function)
 Enable a boundary condition by its ID, returns false if the BC does not exist.
 
void setBDWallsMotionFunction (const GranPositionFunction &pos_fn)
 Prescribe the motion of the big domain, allows wavetank-style simulations.
 
float GetSimTime () const
 Return current simulation time.
 
size_t GetNumParticles () const
 Return the total number of particles in the system.
 
double GetMaxParticleZ () const
 Return the maximum Z position over all particles.
 
double GetMinParticleZ () const
 Return the minimum Z position over all particles.
 
unsigned int GetNumParticleAboveZ (float ZValue) const
 Return the number of particles that are higher than a given Z coordinate.
 
unsigned int GetNumParticleAboveX (float XValue) const
 Return the number of particles that are higher than a given X coordinate.
 
float GetParticleRadius () const
 Return the radius of a spherical particle.
 
ChVector3f GetParticlePosition (int nSphere) const
 Return particle position.
 
void SetParticlePosition (int nSphere, const ChVector3d pos)
 Set particle position.
 
void SetParticleDensity (float density)
 Set particle density.
 
void SetParticleRadius (float rad)
 Set particle radius.
 
void SetParticleVelocity (int nSphere, const ChVector3d velo)
 Set particle velocity.
 
ChVector3f GetParticleAngVelocity (int nSphere) const
 Return particle angular velocity.
 
ChVector3f GetParticleLinAcc (int nSphere) const
 return particle acc
 
bool IsFixed (int nSphere) const
 Return whether or not the particle is fixed.
 
ChVector3f GetParticleVelocity (int nSphere) const
 Return particle linear velocity.
 
float GetParticlesKineticEnergy () const
 Return the total kinetic energy of all particles.
 
ChVector3f GetBCPlanePosition (size_t plane_id) const
 Return position of BC plane.
 
ChVector3f GetBCSpherePosition (size_t sphere_id) const
 Return position of BC sphere.
 
void SetBCSpherePosition (size_t sphere_bc_id, const ChVector3f &pos)
 Set position of BC spheres.
 
ChVector3f GetBCSphereVelocity (size_t sphere_id) const
 Return velocity of BC sphere.
 
void SetBCSphereVelocity (size_t sphere_bc_id, const ChVector3f &velo)
 Set velocity of BC spheres.
 
void SetBCPlaneRotation (size_t plane_id, ChVector3d center, ChVector3d omega)
 Set BC plane rotation.
 
bool GetBCReactionForces (size_t BC_id, ChVector3f &force) const
 Get the reaction forces on a boundary by ID, returns false if the forces are invalid (bad BC ID)
 
unsigned int GetNumContacts () const
 Return number of particle-particle contacts.
 
unsigned int GetNumSDs () const
 Return number of subdomains in the big domain.
 
void WriteCheckpointFile (const std::string &outfilename)
 Write a one-stop checkpoint file for Chrono::Gpu. More...
 
void WriteParticleFile (const std::string &outfilename) const
 Write particle positions according to the system output mode.
 
void WriteContactHistoryFile (const std::string &outfilename) const
 Write contact pair history to a file.
 
void WriteContactInfoFile (const std::string &outfilename) const
 Write contact force and torque to a file.
 
size_t EstimateMemUsage () const
 Roughly estimate of the total amount of memory used by the system.
 
ChVector3f getRollingFrictionTorque (unsigned int i, unsigned int j)
 Get rolling friction torque between body i and j, return 0 if not in contact.
 
ChVector3f getSlidingFrictionForce (unsigned int i, unsigned int j)
 Get tangential friction force between body i and j, return 0 if not in contact.
 
ChVector3f getNormalForce (unsigned int i, unsigned int j)
 Get normal friction force between body i and j, return 0 if not in contact.
 
ChVector3f getRollingVrot (unsigned int i, unsigned int j)
 Get v_rot for rolling friction.
 
float getRollingCharContactTime (unsigned int i, unsigned int j)
 get contact char time
 
void getNeighbors (unsigned int ID, std::vector< unsigned int > &neighborList)
 get index list of neighbors
 
float GetRTF () const
 Get current estimated RTF (real time factor).
 

Additional Inherited Members

- Protected Member Functions inherited from chrono::gpu::ChSystemGpu
 ChSystemGpu ()
 Protected default constructor. Derived class must create m_sys.
 
void ReadCsvParticles (std::ifstream &ifile, unsigned int totRow=UINT_MAX)
 Set particle positions, velocities and angular velocities from a CSV ifstream. More...
 
void ReadHstHistory (std::ifstream &ifile, unsigned int totItem=UINT_MAX)
 Set particle contact friction history from a hst ifstream. More...
 
unsigned int ReadDatParams (std::ifstream &ifile, bool overwrite)
 Set simulation params from a DAT checkpoint file stream. More...
 
void WriteCheckpointParams (std::ofstream &cpFile) const
 Write simulation params to a stream. WriteCheckpointFile() is its wrapper.
 
void WriteCsvParticles (std::ofstream &ptFile) const
 Write particle position, velocity and ang. More...
 
void WriteRawParticles (std::ofstream &ptFile) const
 
void WriteChPFParticles (std::ofstream &ptFile) const
 
void WriteHstHistory (std::ofstream &histFile) const
 Write contact pair/history to a stream. More...
 
void SetGravitationalAcceleration (const float3 g)
 Set gravitational acceleration as a float3 vector.
 
- Protected Attributes inherited from chrono::gpu::ChSystemGpu
ChSystemGpu_impl * m_sys
 underlying system implementation
 
ChTimer m_timer
 
float m_RTF
 

Member Function Documentation

◆ AddMesh() [1/2]

unsigned int chrono::gpu::ChSystemGpuMesh::AddMesh ( const std::string &  filename,
const ChVector3f translation,
const ChMatrix33< float > &  rotscale,
float  mass 
)

Add a trimesh from the specified Wavefront OBJ file to the granular system.

The return value is a mesh identifier which can be used during the simulation to apply rigid body motion to the mesh; see ApplyMeshMotion(). This function must be called before Initialize().

◆ AddMesh() [2/2]

unsigned int chrono::gpu::ChSystemGpuMesh::AddMesh ( std::shared_ptr< ChTriangleMeshConnected mesh,
float  mass 
)

Add a trimesh to the granular system.

The return value is a mesh identifier which can be used during the simulation to apply rigid body motion to the mesh; see ApplyMeshMotion(). This function must be called before Initialize().

◆ AddMeshes()

std::vector< unsigned int > chrono::gpu::ChSystemGpuMesh::AddMeshes ( const std::vector< std::string > &  objfilenames,
const std::vector< ChVector3f > &  translations,
const std::vector< ChMatrix33< float >> &  rotscales,
const std::vector< float > &  masses 
)

Add a set of trimeshes from Wavefront OBJ files into granular system.

The return value is a vector of mesh identifiers which can be used during the simulation to apply rigid body motion to the mesh; see ApplyMeshMotion(). This function must be called before Initialize().

◆ AdvanceSimulation()

double chrono::gpu::ChSystemGpuMesh::AdvanceSimulation ( float  duration)
overridevirtual

Advance simulation by duration in user units, return actual duration elapsed.

Requires Initialize() to have been called.

Reimplemented from chrono::gpu::ChSystemGpu.

◆ GetMesh()

std::shared_ptr<ChTriangleMeshConnected> chrono::gpu::ChSystemGpuMesh::GetMesh ( unsigned int  mesh_id) const
inline

Return the specified mesh in the system.

The mesh is assumed to have been added with one of the AddMesh() functions.

◆ GetMeshMass()

float chrono::gpu::ChSystemGpuMesh::GetMeshMass ( unsigned int  mesh_id) const
inline

Return the mass of the specified mesh.

The mesh is assumed to have been added with one of the AddMesh() functions.

◆ Initialize()

void chrono::gpu::ChSystemGpuMesh::Initialize ( )
overridevirtual

Initialize simulation so that it can be advanced.

Must be called before AdvanceSimulation and after simulation parameters are set. This function initializes both the granular material and any existing trimeshes.

Reimplemented from chrono::gpu::ChSystemGpu.

◆ InitializeMeshes()

void chrono::gpu::ChSystemGpuMesh::InitializeMeshes ( )

Initialize only the trimeshes (assumes the granular material was already initialized).

Must be called before AdvanceSimulation and after simulation parameters are set.


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