yade.utils module¶
Heap of functions that don’t (yet) fit anywhere else.
Devs: please DO NOT ADD more functions here, it is getting too crowded!
- yade.utils.NormalRestitution2DampingRate(en)[source]¶
Compute the normal damping rate as a function of the normal coefficient of restitution \(e_n\). For \(e_n\in\langle0,1\rangle\) damping rate equals
\[-\frac{\log e_n}{\sqrt{e_n^2+\pi^2}}\]
- yade.utils.SpherePWaveTimeStep(radius, density, young)[source]¶
Compute P-wave critical timestep for a single (presumably representative) sphere, using formula for P-Wave propagation speed \(\Delta t_{c}=\frac{r}{\sqrt{E/\rho}}\). If you want to compute minimum critical timestep for all spheres in the simulation, use utils.PWaveTimeStep instead.
>>> SpherePWaveTimeStep(1e-3,2400,30e9) 2.8284271247461903e-07
- class yade.utils.TableParamReader(inherits object)[source]¶
Class for reading simulation parameters from text file.
Each parameter is represented by one column, each parameter set by one line. Colums are separated by blanks (no quoting).
First non-empty line contains column titles (without quotes). You may use special column named ‘description’ to describe this parameter set; if such colum is absent, description will be built by concatenating column names and corresponding values (
param1=34,param2=12.22,param4=foo
)from columns ending in
!
(the!
is not included in the column name)from all columns, if no columns end in
!
.
Empty lines within the file are ignored (although counted);
#
starts comment till the end of line. Number of blank-separated columns must be the same for all non-empty lines.A special value
=
can be used instead of parameter value; value from the previous non-empty line will be used instead (works recursively).This class is used by utils.readParamsFromTable.
- paramDict()[source]¶
Return dictionary containing data from file given to constructor. Keys are line numbers (which might be non-contiguous and refer to real line numbers that one can see in text editors), values are dictionaries mapping parameter names to their values given in the file. The special value ‘=’ has already been interpreted,
!
(bangs) (if any) were already removed from column titles,description
column has already been added (if absent).
- class yade.utils.YadeColorStyle(inherits object)[source]¶
Parameters for default colors and 3D view parameters. Switch between styles with colorStyle.setStyle(“styleName”). See also the rendering section of user manual.
- __init__(bgColor=(0.2, 0.2, 0.2), rgbMin=Vector3(0.4050000000000000266, 0.3599999999999999867, 0.1350000000000000089), rgbRange=Vector3(0.2399999999999999911, 0.2399999999999999911, 0.3599999999999999867), uniScale=False, wallColor=Vector3(0.8000000000000000444, 0.8000000000000000444, 0.5999999999999999778), stripes=True, quality=1)[source]¶
Generic data class for defining color styles. rgbRange is the length of interval [min,max] for each (rgb) color. If uniScale=True the random color is rgbMin+random*rgbRange, else each component is generated randomly.
- yade.utils.aabbDim(cutoff=0.0, centers=False)[source]¶
Return dimensions of the axis-aligned bounding box, optionally with relative part cutoff cut away.
- yade.utils.aabbWalls(extrema=None, thickness=0, oversizeFactor=1.5, **kw)[source]¶
Return 6 boxes that will wrap existing packing as walls from all sides.
- Parameters:
extrema – extremal points of the Aabb of the packing, as a list of two Vector3, or any equivalent type (will be calculated if not specified)
thickness (float) – is wall thickness (will be 1/10 of the X-dimension if not specified)
oversizeFactor (float) – factor to enlarge walls in their plane.
- Returns:
a list of 6 wall Bodies enclosing the packing, in the order minX,maxX,minY,maxY,minZ,maxZ.
- yade.utils.avgNumInteractions(cutoff=0.0, skipFree=False, considerClumps=False)[source]¶
Return average numer of interactions per particle, also known as coordination number \(Z\). This number is defined as
\[Z=2C/N\]where \(C\) is number of contacts and \(N\) is number of particles. When clumps are present, number of particles is the sum of standalone spheres plus the sum of clumps. Clumps are considered in the calculation if cutoff != 0 or skipFree = True. If cutoff=0 (default) and skipFree=False (default) one needs to set considerClumps=True to consider clumps in the calculation.
With skipFree, particles not contributing to stable state of the packing are skipped, following equation (8) given in [Thornton2000]:
\[Z_m=\frac{2C-N_1}{N-N_0-N_1}\]- Parameters:
cutoff – cut some relative part of the sample’s bounding box away.
skipFree – see above.
considerClumps – also consider clumps if cutoff=0 and skipFree=False; for further explanation see above.
- yade.utils.box(center, extents, orientation=Quaternion((1, 0, 0), 0), dynamic=None, fixed=False, wire=False, color=Vector3(0.8000000000000000444, 0.8000000000000000444, 0.5999999999999999778), highlight=False, material=-1, mask=1)[source]¶
Create box (cuboid) with given parameters.
- Parameters:
extents (Vector3) – half-sizes along x,y,z axes. Use can be made of orientation parameter in case those box-related axes do not conform the simulation axes
orientation (Quaternion) – assigned to the body’s orientation, which corresponds to rotating the extents axes
See utils.sphere’s documentation for meaning of other parameters.
- class yade.utils.clumpTemplate(inherits object)[source]¶
Create a clump template by a list of relative radii and a list of relative positions. Both lists must have the same length.
- yade.utils.defaultMaterial()[source]¶
Return default material, when creating bodies with utils.sphere and friends, material is unspecified and there is no shared material defined yet. By default, this function returns
FrictMat(density=1e3,young=1e7,poisson=.3,frictionAngle=.5,label='defaultMat')
- yade.utils.facet(vertices, dynamic=None, fixed=True, wire=True, color=Vector3(0.8000000000000000444, 0.8000000000000000444, 0.5999999999999999778), highlight=False, noBound=False, material=-1, mask=1)[source]¶
Create a Facet-shaped body with given parameters. Body center is chosen as the center of the inscribed circle of the vertices triangle
- Parameters:
vertices ([Vector3,Vector3,Vector3]) – coordinates of vertices in the global coordinate system.
wire (bool) – if
True
, facets are shown as skeleton; otherwise facets are fillednoBound (bool) – set Body.bounded
color (Vector3-or-None) – color of the facet; random color will be assigned if
None
.
See utils.sphere’s documentation for meaning of other parameters.
- yade.utils.fractionalBox(fraction=1.0, minMax=None)[source]¶
Return (min,max) that is the original minMax box (or aabb of the whole simulation if not specified) linearly scaled around its center to the fraction factor
- yade.utils.levelSetBody(shape='', center=Vector3(0, 0, 0), radius=0, extents=Vector3(0, 0, 0), epsilons=Vector2(0, 0), clump=None, spacing=0.1, grid=None, distField=[], smearCoeff=1.5, nSurfNodes=102, nodesPath=2, nodesTol=50, orientation=Quaternion((1, 0, 0), 0), hasAABE=False, axesAABE=Vector3(0, 0, 0), dynamic=True, material=-1)[source]¶
Creates a LevelSet shaped body through various workflows: one can choose among pre-defined shapes (through shape and related attributes), or to mimick a Clump instance (clump attribute, for comparison purposes), or directly assign the discrete distance field on some grid (distField and grid attributes)
- Parameters:
shape (string) – use this argument to enjoy predefined shapes among ‘sphere’, ‘box’ (for a rectangular parallelepiped), ‘disk’ (for a 2D analysis in (x,y) plane), or ‘superellipsoid’; in conjunction with extents or radius attributes. Superellipsoid surfaces are defined in local axes (inertial frame) by the following equation: \(f(x,y,z) = ( |x/r_x|^{2/\epsilon_e} + |y/r_y|^{2/\epsilon_e} )^{\epsilon_e/\epsilon_n} + |z/r_z|^{2/\epsilon_n} = 1\) and their distance field is obtained thanks to a Fast Marching Method.
center (Vector3) – (initial) position of that body
clump (Clump) – pass here a multi-sphere instance to mimick, if desired
radius (Real) – imposed radius in case shape = ‘sphere’ or ‘disk’
extents (Vector3) – half extents along the local axes in case shape = ‘box’ or ‘superellipsoid’ (\(r_x,r_y,r_z\) for the latter)
epsilons (Vector2) – in case shape = ‘superellipsoid’, the (\(\epsilon_e,\epsilon_n\)) exponents
spacing (Real) – spatial increment of the level set grid, if you picked a pre-defined shape or a clump
distField (list) – the discrete distance field on grid (if given) as a list (of list of list; use .tolist() if working initially with 3D numpy arrays), where distField[i][j][k] is the distance value at grid.gridPoint(i,j,k)
grid (RegularGrid) – the grid carrying the distance field, when the latter is directly assigned through distField
smearCoeff (Real) – passed to LevelSet.smearCoeff
nSurfNodes (int) – number of boundary nodes, passed to LevelSet.nSurfNodes
nodesPath (int) – path for the boundary nodes, passed to LevelSet.nodesPath
nodesTol (Real) – tolerance while ray tracing boundary nodes, passed to LevelSet.nodesTol
orientation (Quaternion) – the initial orientation of the body
hasAABE (bool) – flag indicating if the axis-aligned bounding ellipsoid (AABE) was set, passed to LevelSet.hasAABE
axesAABE (Vector3) – principal half-axes of the axis aligned bounding ellipsoid (AABE) when hasAABE, passed to LevelSet.axesAABE
dynamic (bool) – passed to Body.dynamic
material (Material) – passed to Body.material
- Returns:
a corresponding body instance
- yade.utils.loadVars(mark=None)[source]¶
Load variables from utils.saveVars, which are saved inside the simulation. If
mark==None
, all save variables are loaded. Otherwise only those with the mark passed.
- yade.utils.makeVideo(frameSpec, out, renameNotOverwrite=True, fps=24, kbps=6000, bps=None)[source]¶
Create a video from external image files using mencoder. Two-pass encoding using the default mencoder codec (mpeg4) is performed, running multi-threaded with number of threads equal to number of OpenMP threads allocated for Yade.
- Parameters:
frameSpec – wildcard | sequence of filenames. If list or tuple, filenames to be encoded in given order; otherwise wildcard understood by mencoder’s mf:// URI option (shell wildcards such as
/tmp/snap-*.png
or and printf-style pattern like/tmp/snap-%05d.png
)out (str) – file to save video into
renameNotOverwrite (bool) – if True, existing same-named video file will have -number appended; will be overwritten otherwise.
fps (int) – Frames per second (
-mf fps=…
)kbps (int) – Bitrate (
-lavcopts vbitrate=…
) in kb/s
- yade.utils.perpendicularArea(axis)[source]¶
Return area perpendicular to given axis (0=x,1=y,2=z) generated by bodies for which the function consider returns True (defaults to returning True always) and which is of the type Sphere.
- yade.utils.phiIniPy(ioPyFn, grid)[source]¶
Returns a 3D discrete field appropriate to serve as FastMarchingMethod.phiIni (LS_DEM feature required), applying a user-made Python function ioPyFn
- Parameters:
ioPyFn – an existing inside-outside Python function that takes three numbers (cartesian coordinates) as arguments
grid (RegularGrid) – the RegularGrid instance to operate on
- Return list:
an appropriate 3D discrete field to pass at FastMarchingMethod.phiIni
- yade.utils.plotDirections(aabb=(), mask=0, bins=20, numHist=True, noShow=False, sphSph=False)[source]¶
Plot 3 histograms for distribution of interaction directions, in yz,xz and xy planes and (optional but default) histogram of number of interactions per body. If sphSph only sphere-sphere interactions are considered for the 3 directions histograms.
- Returns:
If noShow is
False
, displays the figure and returns nothing. If noShow, the figure object is returned without being displayed (works the same way as plot.plot).
- yade.utils.plotNumInteractionsHistogram(cutoff=0.0)[source]¶
Plot histogram with number of interactions per body, optionally cutting away cutoff relative axis-aligned box from specimen margin.
- yade.utils.polyhedron(vertices, fixed=False, wire=True, color=None, highlight=False, noBound=False, material=-1, mask=1)[source]¶
Create polyhedron with given parameters.
- Parameters:
vertices ([Vector3]) – coordinates of vertices in the global coordinate system.
See utils.sphere’s documentation for meaning of other parameters.
- yade.utils.psd(bins=5, mass=True, mask=-1)[source]¶
Calculates particle size distribution.
- Parameters:
bins (int) – number of bins
mass (bool) – if true, the mass-PSD will be calculated
mask (int) – Body.mask for the body
- Returns:
binsSizes: list of bin’s sizes
binsProc: how much material (in percents) are in the bin, cumulative
binsSumCum: how much material (in units) are in the bin, cumulative
binsSizes, binsProc, binsSumCum
- yade.utils.randomOrientation()[source]¶
Returns (uniformly distributed) random orientation. Taken from Eigen::Quaternion::UnitRandom() source code. Uses standard Python random.random() function(s), you can
random.seed()
it
- yade.utils.randomizeColors(onlyDynamic=False)[source]¶
Assign random colors to Shape::color.
If onlyDynamic is true, only dynamic bodies will have the color changed.
- yade.utils.readParamsFromTable(tableFileLine=None, noTableOk=True, unknownOk=False, **kw)[source]¶
Read parameters from a file and assign them to __builtin__ variables.
The format of the file is as follows (commens starting with # and empty lines allowed):
# commented lines allowed anywhere name1 name2 … # first non-blank line are column headings # empty line is OK, with or without comment val1 val2 … # 1st parameter set val2 val2 … # 2nd …
Assigned tags (the
description
column is synthesized if absent,see utils.TableParamReader);O.tags[‘description’]=… # assigns the description column; might be synthesized O.tags[‘params’]=”name1=val1,name2=val2,…” # all explicitly assigned parameters O.tags[‘defaultParams’]=”unassignedName1=defaultValue1,…” # parameters that were left at their defaults O.tags[‘d.id’]=O.tags[‘id’]+’.’+O.tags[‘description’] O.tags[‘id.d’]=O.tags[‘description’]+’.’+O.tags[‘id’]
All parameters (default as well as settable) are saved using utils.saveVars
('table')
.- Parameters:
tableFileLine – string attribute to define which line number (as seen in a text editor) from wich text file (with one value per blank-separated columns) to get the values from. A ‘:’ should appear between the two informations, e.g. ‘file.table:4’ to read the 4th line from file.table file
noTableOk (bool) – if False, raise exception if the file cannot be open; use default values otherwise
unknownOk (bool) – do not raise exception if unknown column name is found in the file, and assign it as well
- Returns:
number of assigned parameters
- yade.utils.replaceCollider(colliderEngine)[source]¶
Replaces collider (Collider) engine with the engine supplied. Raises error if no collider is in engines.
- yade.utils.saveVars(mark='', loadNow=True, **kw)[source]¶
Save passed variables into the simulation so that it can be recovered when the simulation is loaded again.
For example, variables a, b and c are defined. To save them, use:
>>> saveVars('something',a=1,b=2,c=3) >>> from yade.params.something import * >>> a,b,c (1, 2, 3)
those variables will be save in the .xml file, when the simulation itself is saved. To recover those variables once the .xml is loaded again, use
loadVars('something')
and they will be defined in the yade.params.mark module. The loadNow parameter calls utils.loadVars after saving automatically. If ‘something’ already exists, given variables will be inserted.
- yade.utils.sphere(center, radius, dynamic=None, fixed=False, wire=False, color=None, highlight=False, material=-1, mask=1)[source]¶
Create sphere with given parameters; mass and inertia computed automatically.
Last assigned material is used by default (material = -1), and utils.defaultMaterial() will be used if no material is defined at all.
- Parameters:
center (Vector3) – center
radius (float) – radius
dynamic (float) – deprecated, see “fixed”
fixed (float) – generate the body with all DOFs blocked?
material –
- specify Body.material; different types are accepted:
int: O.materials[material] will be used; as a special case, if material==-1 and there is no shared materials defined, utils.defaultMaterial() will be assigned to O.materials[0]
string: label of an existing material that will be used
Material instance: this instance will be used
callable: will be called without arguments; returned Material value will be used (Material factory object, if you like)
mask (int) – Body.mask for the body
wire – display as wire sphere?
highlight – highlight this body in the viewer?
Vector3-or-None – body’s color, as normalized RGB; random color will be assigned if
None
.
- Returns:
A Body instance with desired characteristics.
Creating default shared material if none exists neither is given:
>>> O.reset() >>> from yade import utils >>> len(O.materials) 0 >>> s0=utils.sphere([2,0,0],1) >>> len(O.materials) 1
Instance of material can be given:
>>> s1=utils.sphere([0,0,0],1,wire=False,color=(0,1,0),material=ElastMat(young=30e9,density=2e3)) >>> s1.shape.wire False >>> s1.shape.color Vector3(0,1,0) >>> s1.mat.density 2000.0
Material can be given by label:
>>> O.materials.append(FrictMat(young=10e9,poisson=.11,label='myMaterial')) 1 >>> s2=utils.sphere([0,0,2],1,material='myMaterial') >>> s2.mat.label 'myMaterial' >>> s2.mat.poisson 0.11
Finally, material can be a callable object (taking no arguments), which returns a Material instance. Use this if you don’t call this function directly (for instance, through yade.pack.randomDensePack), passing only 1 material parameter, but you don’t want material to be shared.
For instance, randomized material properties can be created like this:
>>> import random >>> def matFactory(): return ElastMat(young=1e10*random.random(),density=1e3+1e3*random.random()) ... >>> s3=utils.sphere([0,2,0],1,material=matFactory) >>> s4=utils.sphere([1,2,0],1,material=matFactory)
- yade.utils.tetra(vertices, strictCheck=True, fixed=False, wire=True, color=None, highlight=False, noBound=False, material=-1, mask=1)[source]¶
Create tetrahedron with given parameters.
- Parameters:
See utils.sphere’s documentation for meaning of other parameters.
- yade.utils.tetraPoly(vertices, fixed=False, wire=True, color=None, highlight=False, noBound=False, material=-1, mask=1)[source]¶
Create tetrahedron (actually simple Polyhedra) with given parameters.
- Parameters:
vertices ([Vector3,Vector3,Vector3,Vector3]) – coordinates of vertices in the global coordinate system.
See utils.sphere’s documentation for meaning of other parameters.
- yade.utils.trackPerfomance(updateTime=5)[source]¶
Track perfomance of a simulation. (Experimental) Will create new thread to produce some plots. Useful for track perfomance of long run simulations (in bath mode for example).
- yade.utils.typedEngine(name)[source]¶
Return first engine from current O.engines, identified by its type (as string). For example:
>>> from yade import utils >>> O.engines=[InsertionSortCollider(),NewtonIntegrator(),GravityEngine()] >>> utils.typedEngine("NewtonIntegrator") == O.engines[1] True
- yade.utils.uniaxialTestFeatures(filename=None, areaSections=10, axis=-1, distFactor=2.2, **kw)[source]¶
Get some data about the current packing useful for uniaxial test:
Find the dimensions that is the longest (uniaxial loading axis)
Find the minimum cross-section area of the specimen by examining several (areaSections) sections perpendicular to axis, computing area of the convex hull for each one. This will work also for non-prismatic specimen.
Find the bodies that are on the negative/positive boundary, to which the straining condition should be applied.
- Parameters:
filename – if given, spheres will be loaded from this file (ASCII format); if not, current simulation will be used.
areaSection (float) – number of section that will be used to estimate cross-section
axis (∈{0,1,2}) – if given, force strained axis, rather than computing it from predominant length
- Returns:
dictionary with keys
negIds
,posIds
,axis
,area
.
Warning
The function utils.approxSectionArea uses convex hull algorithm to find the area, but the implementation is reported to be buggy (bot works in some cases). Always check this number, or fix the convex hull algorithm (it is documented in the source, see py/_utils.cpp).
- yade.utils.voxelPorosityTriaxial(triax, resolution=200, offset=0)[source]¶
Calculate the porosity of a sample, given the TriaxialCompressionEngine.
A function utils.voxelPorosity is invoked, with the volume of a box enclosed by TriaxialCompressionEngine walls. The additional parameter offset allows using a smaller volume inside the box, where each side of the volume is at offset distance from the walls. By this way it is possible to find a more precise porosity of the sample, since at walls’ contact the porosity is usually reduced.
A recommended value of offset is bigger or equal to the average radius of spheres inside.
The value of resolution depends on size of spheres used. It can be calibrated by invoking voxelPorosityTriaxial with offset=0 and comparing the result with TriaxialCompressionEngine.porosity. After calibration, the offset can be set to radius, or a bigger value, to get the result.
- Parameters:
triax – the TriaxialCompressionEngine handle
resolution – voxel grid resolution
offset – offset distance
- Returns:
the porosity of the sample inside given volume
Example invocation:
from yade import utils rAvg=0.03 TriaxialTest(numberOfGrains=200,radiusMean=rAvg).load() O.dt=-1 O.run(1000) O.engines[4].porosity 0.44007807740143889 utils.voxelPorosityTriaxial(O.engines[4],200,0) 0.44055412500000002 utils.voxelPorosityTriaxial(O.engines[4],200,rAvg) 0.36798199999999998
- yade.utils.waitIfBatch()[source]¶
Block the simulation if running inside a batch. Typically used at the end of script so that it does not finish prematurely in batch mode (the execution would be ended in such a case).
- yade.utils.wall(position, axis, sense=0, color=Vector3(0.8000000000000000444, 0.8000000000000000444, 0.5999999999999999778), material=-1, mask=1)[source]¶
Return ready-made wall body.
- Parameters:
position (float-or-Vector3) – center of the wall. If float, it is the position along given axis, the other 2 components being zero
axis (∈{0,1,2}) – orientation of the wall normal (0,1,2) for x,y,z (sc. planes yz, xz, xy)
sense (∈{-1,0,1}) – sense in which to interact (0: both, -1: negative, +1: positive; see Wall)
See utils.sphere’s documentation for meaning of other parameters.
- yade.utils.xMirror(half)[source]¶
Mirror a sequence of 2d points around the x axis (changing sign on the y coord). The sequence should start up and then it will wrap from y downwards (or vice versa). If the last point’s x coord is zero, it will not be duplicated.
- yade._utils.PWaveTimeStep() float ¶
Get timestep accoring to the velocity of P-Wave propagation; computed for spheres and/or polyhedra based on their sizes, rigidities and masses.
- yade._utils.RayleighWaveTimeStep() float ¶
Determination of time step according to Rayleigh wave speed of force propagation.
- yade._utils.TetrahedronSignedVolume((object)arg1) float ¶
TODO
- yade._utils.TetrahedronVolume((object)arg1) float ¶
TODO
- yade._utils.TetrahedronWithLocalAxesPrincipal((Body)arg1) Quaternion ¶
TODO
- yade._utils.aabbExtrema([(float)cutoff=0.0[, (bool)centers=False]]) tuple ¶
Return coordinates of box enclosing all spherical bodies
- Parameters:
centers (bool) – do not take sphere radii in account, only their centroids
cutoff (float∈〈0…1〉) – relative dimension by which the box will be cut away at its boundaries.
- Returns:
[lower corner, upper corner] as [Vector3,Vector3]
- yade._utils.approxSectionArea((float)arg1, (int)arg2) float ¶
Compute area of convex hull when when taking (swept) spheres crossing the plane at coord, perpendicular to axis.
- yade._utils.bodyNumInteractionsHistogram((tuple)aabb) tuple ¶
- yade._utils.bodyStressTensors() list ¶
Compute and return a table with per-particle stress tensors. Each tensor represents the average stress in one particle, obtained from the contour integral of applied load as detailed below. This definition is considering each sphere as a continuum. It can be considered exact in the context of spheres at static equilibrium, interacting at contact points with negligible volume changes of the solid phase (this last assumption is not restricting possible deformations and volume changes at the packing scale).
Proof:
First, we remark the identity: \(\sigma_{ij}=\delta_{ik}\sigma_{kj}=x_{i,k}\sigma_{kj}=(x_{i}\sigma_{kj})_{,k}-x_{i}\sigma_{kj,k}\).
At equilibrium, the divergence of stress is null: \(\sigma_{kj,k}=\vec{0}\). Consequently, after divergence theorem: \(\frac{1}{V}\int_V \sigma_{ij}dV = \frac{1}{V}\int_V (x_{i}\sigma_{kj})_{,k}dV = \frac{1}{V}\int_{\partial V}x_i\sigma_{kj}n_kdS = \frac{1}{V}\sum_bx_i^bf_j^b\).
The last equality is implicitely based on the representation of external loads as Dirac distributions whose zeros are the so-called contact points: 0-sized surfaces on which the contact forces are applied, located at \(x_i\) in the deformed configuration.
A weighted average of per-body stresses will give the average stress inside the solid phase. There is a simple relation between the stress inside the solid phase and the stress in an equivalent continuum in the absence of fluid pressure. For porosity \(n\), the relation reads: \(\sigma_{ij}^{equ.}=(1-n)\sigma_{ij}^{solid}\).
This last relation may not be very useful if porosity is not homogeneous. If it happens, one can define the equivalent bulk stress a the particles scale by assigning a volume to each particle. This volume can be obtained from TesselationWrapper (see e.g. [Catalano2014a])
- yade._utils.calm([(int)mask=-1]) None ¶
Set translational and rotational velocities of bodies to zero. Applied to all dynamic bodies by default. To calm only some of them, use mask parameter, it will calm only dynamic bodies with groupMask compatible to given value
- yade._utils.cart2spher((Vector3)vec) Vector3 ¶
Converts cartesian coordinates to spherical ones.
- Parameters:
vec (Vector3) – the \((x,y,z)\) cartesian coordinates
- Returns:
a \((r,\theta,\phi)\) Vector3 of spherical coordinates, with \(\theta = (\vec{e_z},\vec{e_r}) \in [0;\pi]\) and \(\phi \in [0;2 \pi]\) measured in \((x,y)\) plane from \(x\)-axis
- yade._utils.coordsAndDisplacements((int)axis[, (tuple)Aabb=()]) tuple ¶
Return tuple of 2 same-length lists for coordinates and displacements (coordinate minus reference coordinate) along given axis (1st arg); if the Aabb=((x_min,y_min,z_min),(x_max,y_max,z_max)) box is given, only bodies within this box will be considered.
- yade._utils.createInteraction((int)id1, (int)id2[, (bool)virtualI=False]) Interaction ¶
Create interaction between given bodies by hand.
If virtualI=False, current engines are searched for IGeomDispatcher and IPhysDispatcher (might be both hidden in InteractionLoop). Geometry is created using
force
parameter of the geometry dispatcher, wherefore the interaction will exist even if bodies do not spatially overlap and the functor would returnfalse
under normal circumstances.If virtualI=True the interaction is left in a virtual state.
Warning
This function will very likely behave incorrectly for periodic simulations (though it could be extended it to handle it farily easily).
- yade._utils.distApproxRose((Vector3)pt) float ¶
An approximate distance value to a rose-like flaky surface defined in spherical coordinates as \(r = 3+1.5 \\sin(5 \\theta) \\sin(4\\phi)\) (see cart2spher function for spherical <→ cartesian convention).
- Parameters:
pt (Vector3) – the pt of interest given in \((x,y,z)\) cartesian coordinates.
- Returns:
a 0-approximation distance value.
- yade._utils.distApproxSE((Vector3)pt, (Vector3)radii, (Vector2)epsilons) float ¶
An approximate distance value to a superellipsoid surface defined (in local axes) as \(f(x,y,z) = ( |x/r_x|^{2/\epsilon_e} + |y/r_y|^{2/\epsilon_e} )^{\epsilon_e/\epsilon_n} + |z/r_z|^{2/\epsilon_n} = 1\).
- yade._utils.distIniClump((Clump)clump, (RegularGrid)grid) object ¶
An appropriate discrete field to serve as a Fast Marching Method input in FastMarchingMethod.phiIni in order to compute distance to a clump.
- Parameters:
clump (Clump) – considered clump instance
grid (RegularGrid) – the RegularGrid instance to consider
- Returns:
an appropriate 3D discrete field for FastMarchingMethod.phiIni.
- yade._utils.distIniSE((Vector3)radii, (Vector2)epsilons, (RegularGrid)grid) object ¶
An appropriate discrete field to serve as a Fast Marching Method input in FastMarchingMethod.phiIni in order to compute distance to a superellipsoid.
- Parameters:
radii (Vector3) – the \((r_x,r_y,r_z)\)
epsilons (Vector2) – the \((\epsilon_e,\epsilon_n)\) exponents
grid (RegularGrid) – the RegularGrid instance to consider
- Returns:
an appropriate 3D discrete field for FastMarchingMethod.phiIni.
- yade._utils.fabricTensor([(float)cutoff=0.0[, (bool)splitTensor=False[, (float)thresholdForce=nan[, (object)extrema=[]]]]]) tuple ¶
Computes the fabric tensor \(F_{ij}=\frac{1}{n_c}\sum_c n_i n_j\) [Satake1982], for all interactions \(c\).
- Parameters:
cutoff (Real) – intended to disregard boundary effects: to define in [0;1] to focus on the interactions located in the centered inner (1-cutoff)^3*\(V\) part of the spherical packing \(V\).
splitTensor (bool) – split the fabric tensor into two parts related to the strong (greatest compressive normal forces) and weak contact forces respectively.
thresholdForce (Real) – if the fabric tensor is split into two parts, a threshold value can be specified otherwise the mean contact force is considered by default. Use negative signed values for compressive states. To note that this value could be set to zero if one wanted to make distinction between compressive and tensile forces.
extrema (list) – defines through a two-Vector3-list (min,max) an axis aligned box that restricts the interactions to consider. A value has to be given for the function to be effective with non-spherical particles.
- yade._utils.flipCell() Matrix3 ¶
utils.flipCell is deprecated, use O.cell.flipCell or O.cell.flipFlippable
- yade._utils.forcesOnPlane((Vector3)planePt, (Vector3)normal) Vector3 ¶
Find all interactions deriving from NormShearPhys that cross given plane and sum forces (both normal and shear) on them.
- yade._utils.getBodyIdsContacts([(int)bodyID=0]) list ¶
Get a list of body-ids, which contacts the given body.
- yade._utils.getCapillaryStress([(float)volume=0[, (bool)mindlin=False]]) Matrix3 ¶
Compute and return Love-Weber capillary stress tensor:
\(\sigma^{cap}_{ij}=\frac{1}{V}\sum_b l_i^b f^{cap,b}_j\), where the sum is over all interactions, with \(l\) the branch vector (joining centers of the bodies) and \(f^{cap}\) is the capillary force. \(V\) can be passed to the function. If it is not, it will be equal to one in non-periodic cases, or equal to the volume of the cell in periodic cases. Only the CapillaryPhys interaction type is supported presently. Using this function with physics MindlinCapillaryPhys needs to pass True as second argument.
- yade._utils.getDepthProfiles((float)volume, (int)nCell, (float)dz, (float)zRef[, (bool)activateCond=False[, (float)radiusPy=0[, (int)direction=2]]]) tuple ¶
Compute and return the particle velocity and solid volume fraction (porosity) depth profile along the direction specified (default is z; 0=>x,1=>y,2=>z). For each defined cell z, the k component of the average particle velocity reads:
\(<v_k>^z= \sum_p V^p v_k^p/\sum_p V^p\),
where the sum is made over the particles contained in the cell, \(v_k^p\) is the k component of the velocity associated to particle p, and \(V^p\) is the part of the volume of the particle p contained inside the cell. This definition allows to smooth the averaging, and is equivalent to taking into account the center of the particles only when there is a lot of particles in each cell. As for the solid volume fraction, it is evaluated in the same way: for each defined cell z, it reads:
- \(<\phi>^z= \frac{1}{V_{cell}}\sum_p V^p\), where \(V_{cell}\) is the volume of the cell considered, and \(V^p\) is the volume of particle p contained in cell z.
This function gives depth profiles of average velocity and solid volume fraction, returning the average quantities in each cell of height dz, from the reference horizontal plane at elevation zRef (input parameter) until the plane of elevation zRef+nCell*dz (input parameters). If the argument activateCond is set to true, do the average only on particles of radius equal to radiusPy (input parameter)
- yade._utils.getDepthProfiles_center((float)volume, (int)nCell, (float)dz, (float)zRef[, (bool)activateCond=False[, (float)radiusPy=0]]) tuple ¶
Same as getDepthProfiles but taking into account particles as points located at the particle center.
- yade._utils.getDynamicStress() list ¶
Compute the dynamic stress tensor for each body: \(\sigma^p_D= - \frac{1}{V^p} m^p u'^p \otimes u'^p\)
- yade._utils.getSlicedProfiles((float)vCell, (int)nCell, (float)dP, (object)sliceCenters, (object)sliceWidths, (float)refP, (float)refS[, (int)dirP=2[, (int)dirS=1[, (bool)activateCond=False[, (float)radiusPy=0[, (float)nSimpson=50]]]]]) tuple ¶
Compute and return the particle solid volume fraction (porosity) and velocity profiles along a specific direction dirP and for a given subdomain. In the direction dirP, the subdomain is divided into nCell of size dP. For each cell, the averaged solid volume fraction reads:
\(<\phi>= \frac{1}{V_{cell}}\sum_p V^p\)
and the averaged particle velocity reads:
\(<v_k>= \sum_p V^p v_k^p/\sum_p V^p\),
where the sum is made over the particles p contained in the cell, \(v_k^p\) is the k component of the velocity associated to particle p, \(V^p\) is the part of the volume of the particle p contained inside the cell, and \(V_{cell}\) is the volume of the cell (all subdomain slices combined). The volume of the sliced particle \(V^p\) is computed analytically when the particle is not sliced by the subdomain boundaries. Otherwise, \(V^p\) is computed using a Simpson integration of the sliced area of the sliced sphere.
This function allows to define a discontinuous subdomain made of different slices in direction dirS. This can be useful to exclude specific zones from the averaging procedure or to target similar zones like symmetric boundaries.
Arguments are: vCell : volume of a cell, all slices combined. (e.g. dP*length*(slicewidth1+slicewidth2)) nCell : number of cells in the profile direction dP : discretisation interval in the Profile direction, sliceCenters : array containing the position of the center of each slice from refS in the S direction, sliceWidths : array containing the width of each slice, refP : reference position in the Profile direction, refS : reference position in the slice direction, dirP : direction of the profile (0:x, 1:y, 2:z), (default:2), dirS : direction of the slices (0:x, 1:y, 2:z), must be different from dirP, (default:1), activateCond : if true, will only consider particle of radius equal radiusPy, (default:false), nSimpson : number of intervals per particle radius for the Simpson integration, (default:50),
- yade._utils.getSpheresMass([(int)mask=-1]) float ¶
Compute the total mass of spheres in the simulation, mask parameter is considered
- yade._utils.getSpheresVolume([(int)mask=-1]) float ¶
Compute the total volume of spheres in the simulation, mask parameter is considered
- yade._utils.getSpheresVolume2D([(int)mask=-1]) float ¶
Compute the total volume of discs in the simulation, mask parameter is considered
- yade._utils.getStress([(float)volume=0]) Matrix3 ¶
Compute and return Love-Weber stress tensor:
\(\sigma_{ij}=\frac{1}{V}\sum_b f_i^b l_j^b\), where the sum is over all interactions, with \(f\) the contact force and \(l\) the branch vector (joining centers of the bodies). Stress is negativ for repulsive contact forces, i.e. compression. \(V\) can be passed to the function. If it is not, it will be equal to the volume of the cell in periodic cases, or to the one deduced from utils.aabbDim() in non-periodic cases.
- yade._utils.getStressAndTangent([(float)volume=0[, (bool)symmetry=True]]) tuple ¶
Compute overall stress of periodic cell using the same equation as function getStress. In addition, the tangent operator is calculated using the equation published in [Kruyt and Rothenburg1998]_:
\[S_{ijkl}=\frac{1}{V}\sum_{c}(k_n n_i l_j n_k l_l + k_t t_i l_j t_k l_l)\]- Parameters:
volume (float) – same as in function getStress
symmetry (bool) – make the tensors symmetric.
- Returns:
macroscopic stress tensor and tangent operator as py::tuple
- yade._utils.getStressProfile((float)volume, (int)nCell, (float)dz, (float)zRef, (object)vPartAverageX, (object)vPartAverageY, (object)vPartAverageZ) tuple ¶
Compute and return the stress tensor depth profile, including the contribution from Love-Weber stress tensor and the dynamic stress tensor taking into account the effect of particles inertia. For each defined cell z, the stress tensor reads:
\(\sigma_{ij}^z= \frac{1}{V}\sum_c f_i^c l_j^{c,z} - \frac{1}{V}\sum_p m^p u'^p_i u'^p_j\),
where the first sum is made over the contacts which are contained or cross the cell z, f^c is the contact force from particle 1 to particle 2, and l^{c,z} is the part of the branch vector from particle 2 to particle 1, contained in the cell. The second sum is made over the particles, and u’^p is the velocity fluctuations of the particle p with respect to the spatial averaged particle velocity at this point (given as input parameters). The expression of the stress tensor is the same as the one given in getStress plus the inertial contribution. Apart from that, the main difference with getStress stands in the fact that it gives a depth profile of stress tensor, i.e. from the reference horizontal plane at elevation zRef (input parameter) until the plane of elevation zRef+nCell*dz (input parameters), it is computing the stress tensor for each cell of height dz. For the love-Weber stress contribution, the branch vector taken into account in the calculations is only the part of the branch vector contained in the cell considered. To validate the formulation, it has been checked that activating only the Love-Weber stress tensor, and suming all the contributions at the different altitude, we recover the same stress tensor as when using getStress. For my own use, I have troubles with strong overlap between fixed object, so that I made a condition to exclude the contribution to the stress tensor of the fixed objects, this can be desactivated easily if needed (and should be desactivated for the comparison with getStress).
- yade._utils.getStressProfile_contact((float)volume, (int)nCell, (float)dz, (float)zRef) tuple ¶
same as getStressProfile, only contact contribution.
- yade._utils.getTotalDynamicStress([(float)volume=0]) Matrix3 ¶
Compute the total dynamic stress tensor : \(\sigma_D= - \frac{1}{V}\sum_p m^p u'^p \otimes u'^p\). The volume have to be provided for non-periodic simulations. It is computed from cell volume for periodic simulations.
- yade._utils.getViscoelasticFromSpheresInteraction((float)tc, (float)en, (float)es) dict ¶
Attention! The function is deprecated! Compute viscoelastic interaction parameters from analytical solution of a pair spheres collision problem:
\[\begin{split}k_n=\frac{m}{t_c^2}\left(\pi^2+(\ln e_n)^2\right) \\ c_n=-\frac{2m}{t_c}\ln e_n \\ k_t=\frac{2}{7}\frac{m}{t_c^2}\left(\pi^2+(\ln e_t)^2\right) \\ c_t=-\frac{2}{7}\frac{m}{t_c}\ln e_t \end{split}\]where \(k_n\), \(c_n\) are normal elastic and viscous coefficients and \(k_t\), \(c_t\) shear elastic and viscous coefficients. For details see [Pournin2001].
- Parameters:
m (float) – sphere mass \(m\)
tc (float) – collision time \(t_c\)
en (float) – normal restitution coefficient \(e_n\)
es (float) – tangential restitution coefficient \(e_s\)
- Returns:
dictionary with keys
kn
(the value of \(k_n\)),cn
(\(c_n\)),kt
(\(k_t\)),ct
(\(c_t\)).
- yade._utils.growParticle((int)bodyID, (float)multiplier[, (bool)updateMass=True]) None ¶
Change the size of a single sphere (to be implemented: single clump). If updateMass=True, then the mass is updated.
- yade._utils.growParticles((float)multiplier[, (bool)updateMass=True[, (bool)dynamicOnly=True]]) None ¶
Change the size of spheres and clumps of spheres by the multiplier. If updateMass=True, then the mass and inertia are updated. dynamicOnly=True will select dynamic bodies.
- yade._utils.initMPI() None ¶
Initialize MPI communicator, for Foam Coupling
- yade._utils.inscribedCircleCenter((Vector3)v1, (Vector3)v2, (Vector3)v3) Vector3 ¶
Return center of inscribed circle for triangle given by its vertices v1, v2, v3.
- yade._utils.insideClump((Vector3)pt, (Clump)clump) bool ¶
Tells whether some point is inside or outside a clump
- yade._utils.interactionAnglesHistogram((int)axis[, (int)mask=0[, (int)bins=20[, (tuple)aabb=()[, (bool)sphSph=0[, (float)minProjLen=1e-06]]]]]) tuple ¶
- yade._utils.intrsOfEachBody() list ¶
returns list of lists of interactions of each body
- yade._utils.kineticEnergy([(bool)findMaxId=False]) object ¶
Compute overall kinetic energy of the simulation as
\[\sum\frac{1}{2}\left(m_i\vec{v}_i^2+\vec{\omega}(\mat{I}\vec{\omega}^T)\right).\]For aspherical bodies, necessary frame transformations are applied to the inertia tensor \(\mat{I}\) as stored in state.inertia.
- yade._utils.lsSimpleShape((int)shape, (AlignedBox3)aabb[, (float)step=0.1[, (float)smearCoeff=1.5[, (Vector2)epsilons=Vector2(0, 0)[, (Clump)clump=<Clump instance at 0x224a420>]]]]) LevelSet ¶
Creates a LevelSet shape among pre-defined ones. Not intended to be used directly, see levelSetBody() instead.
- Parameters:
shape (int) – a shape index among supported choices
aabb (AlignedBox3) – the axis-aligned surrounding box of the body
step (Real) – the LevelSet grid step size
smearCoeff (Real) – passed to LevelSet.smearCoeff
epsilons (Vector2) – the epsilon exponents in case shape = 3 (superellipsoid)
clump (Clump) – the Clump instance to mimick in case shape = 4
- Returns:
a LevelSet instance.
- yade._utils.maxOverlapRatio() float ¶
Return maximum overlap ration in interactions (with ScGeom) of two spheres. The ratio is computed as \(\frac{u_N}{2(r_1 r_2)/r_1+r_2}\), where \(u_N\) is the current overlap distance and \(r_1\), \(r_2\) are radii of the two spheres in contact.
- yade._utils.nGP((float)min, (float)max, (float)step) int ¶
Defines how many gridpoints are necessary to go from min to (at least) max, by step increments, eg when constructing a RegularGrid
- param Real min:
lowest grid extremity as (min,min,min) in case you just give a number, or as (min[0],min[1],min[2]) in case you give a tuple/list/Vector3
- param Real max:
highest gridpoint as (max,max,max) in case you give a number, or as (max[0],max[1],max[2]) in case you give a tuple/list/Vector3. The actual highest point of the grid may be beyond max by something like step.
- param Real step:
the distance between two consecutive grid points (the same along each axis).
- return:
either an integer, or a Vector3 of, depending on usage
- nGP( (Vector3)min, (Vector3)max, (float)step) → Vector3i :
Type-overloaded version of the above, to allow for both types of max/min attributes.
- yade._utils.negPosExtremeIds((int)axis, (float)distFactor) tuple ¶
Return list of ids for spheres (only) that are on extremal ends of the specimen along given axis; distFactor multiplies their radius so that sphere that do not touch the boundary coordinate can also be returned.
- yade._utils.normalShearStressTensors([(bool)compressionPositive=False[, (bool)splitNormalTensor=False[, (float)thresholdForce=nan]]]) tuple ¶
Compute overall stress tensor of the periodic cell decomposed in 2 parts, one contributed by normal forces, the other by shear forces. The formulation can be found in [Thornton2000], eq. (3):
\[\tens{\sigma}_{ij}=\frac{2}{V}\sum R N \vec{n}_i \vec{n}_j+\frac{2}{V}\sum R T \vec{n}_i\vec{t}_j\]where \(V\) is the cell volume, \(R\) is “contact radius” (in our implementation, current distance between particle centroids), \(\vec{n}\) is the normal vector, \(\vec{t}\) is a vector perpendicular to \(\vec{n}\), \(N\) and \(T\) are norms of normal and shear forces.
- Parameters:
splitNormalTensor (bool) – if true the function returns normal stress tensor split into two parts according to the two subnetworks of strong an weak forces.
thresholdForce (Real) – threshold value according to which the normal stress tensor can be split (e.g. a zero value would make distinction between tensile and compressive forces).
- yade._utils.numIntrsOfEachBody() list ¶
returns list of number of interactions of each body
- yade._utils.phiIniCppPy((RegularGrid)grid) object ¶
A possibly handy function to construct a FastMarchingMethod.phiIni after applying on grid an inside-outside Python function. The latter necessarily names ioFn and takes three floating numbers (cartesian coordinates) as arguments. Code source of the present function is both C++ and Python, and execution should be faster and heavier in memory than the pure Python version utils.phiIniPy, both being under the second and few MB for grids with ~ \(10^4\) gridpoints.
- Parameters:
grid (RegularGrid) – the yref:RegularGrid instance to operate on with a preexisting ioFn Python function
- Returns:
an appropriate 3D discrete field for FastMarchingMethod.phiIni
- yade._utils.pointInsidePolygon((tuple)arg1, (object)arg2) bool ¶
- yade._utils.porosity([(float)volume=-1]) float ¶
Compute packing porosity \(\frac{V-V_s}{V}\) where \(V\) is overall volume and \(V_s\) is volume of spheres.
- Parameters:
volume (float) – overall volume \(V\). For periodic simulations, current volume of the Cell is used. For aperiodic simulations, the value deduced from utils.aabbDim() is used. For compatibility reasons, positive values passed by the user are also accepted in this case.
- yade._utils.ptInAABB((Vector3)arg1, (Vector3)arg2, (Vector3)arg3) bool ¶
Return True/False whether the point p is within box given by its min and max corners
- yade._utils.scalarOnColorScale((float)x[, (float)xmin=0[, (float)xmax=1]]) Vector3 ¶
Map scalar variable to color scale.
- Parameters:
x (float) – scalar value which the function applies to.
xmin (float) – minimum value for the color scale, with a return value of (0,0,1) for x \(\leq\) xmin, i.e. blue color in RGB.
xmax (float) – maximum value, with a return value of (1,0,0) for x \(\geq\) xmax, i.e. red color in RGB.
- Returns:
a Vector3 depending on the relative position of x on a [xmin;*xmax*] scale.
- yade._utils.setBodyAngularVelocity((int)id, (Vector3)angVel) None ¶
Set a body angular velocity from its id and a new Vector3r.
- Parameters:
id (int) – the body id.
angVel (Vector3) – the desired updated angular velocity.
- yade._utils.setBodyColor((int)id, (Vector3)color) None ¶
Set a body color from its id and a new Vector3r.
- Parameters:
id (int) – the body id.
color (Vector3) – the desired updated color.
- yade._utils.setBodyOrientation((int)id, (Quaternion)ori) None ¶
Set a body orientation from its id and a new Quaternionr.
- Parameters:
id (int) – the body id.
ori (Quaternion) – the desired updated orientation.
- yade._utils.setBodyPosition((int)id, (Vector3)pos[, (str)axis='xyz']) None ¶
Set a body position from its id and a new vector3r.
- Parameters:
id (int) – the body id.
pos (Vector3) – the desired updated position.
axis (str) – the axis along which the position has to be updated (ex: if axis==”xy” and pos==Vector3r(r0,r1,r2), r2 will be ignored and the position along z will not be updated).
- yade._utils.setBodyVelocity((int)id, (Vector3)vel[, (str)axis='xyz']) None ¶
Set a body velocity from its id and a new vector3r.
- Parameters:
id (int) – the body id.
vel (Vector3) – the desired updated velocity.
axis (str) – the axis along which the velocity has to be updated (ex: if axis==”xy” and vel==Vector3r(r0,r1,r2), r2 will be ignored and the velocity along z will not be updated).
- yade._utils.setContactFriction((float)angleRad) None ¶
Modify the friction angle (in radians) inside the material classes and existing contacts. The friction for non-dynamic bodies is not modified.
- yade._utils.setNewVerticesOfFacet((Body)b, (Vector3)v1, (Vector3)v2, (Vector3)v3) None ¶
Sets new vertices (in global coordinates) to given facet.
- yade._utils.setRefSe3() None ¶
Set reference positions and orientations of all bodies equal to their current positions and orientations.
- yade._utils.shiftBodies((list)ids, (Vector3)shift) float ¶
Shifts bodies listed in ids without updating their velocities.
- yade._utils.spher2cart((Vector3)vec) Vector3 ¶
Converts spherical coordinates to cartesian ones.
- Parameters:
vec (Vector3) – the \((r,\theta,\phi)\) spherical coordinates, see cart2spher function for conventions
- Returns:
a \((x,y,z)\) Vector3 of cartesian coordinates
- yade._utils.spiralProject((Vector3)pt, (float)dH_dTheta[, (int)axis=2[, (float)periodStart=nan[, (float)theta0=0]]]) tuple ¶
- yade._utils.sumFacetNormalForces((object)ids[, (int)axis=-1]) float ¶
Sum force magnitudes on given bodies (must have shape of the Facet type), considering only part of forces perpendicular to each facet’s face; if axis has positive value, then the specified axis (0=x, 1=y, 2=z) will be used instead of facet’s normals.
- yade._utils.sumForces((list)ids, (Vector3)direction) float ¶
Return summary force on bodies with given ids, projected on the direction vector.
- yade._utils.sumTorques((list)ids, (Vector3)axis, (Vector3)axisPt) float ¶
Sum forces and torques on bodies given in ids with respect to axis specified by a point axisPt and its direction axis.
- yade._utils.totalForceInVolume() tuple ¶
Return summed forces on all interactions and average isotropic stiffness, as tuple (Vector3,float)
- yade._utils.unbalancedForce([(bool)useMaxForce=False]) float ¶
Compute the ratio of mean (or maximum, if useMaxForce) summary force on bodies and mean force magnitude on interactions. For perfectly static equilibrium, summary force on all bodies is zero (since forces from interactions cancel out and induce no acceleration of particles); this ratio will tend to zero as simulation stabilizes, though zero is never reached because of finite precision computation. Sufficiently small value can be e.g. 1e-2 or smaller, depending on how much equilibrium it should be.
- yade._utils.voidratio2D([(float)zlen=1]) float ¶
Compute 2D packing void ratio \(\frac{V-V_s}{V_s}\) where \(V\) is overall volume and \(V_s\) is volume of disks.
- Parameters:
zlen (float) – length in the third direction.
- yade._utils.voxelPorosity([(int)resolution=200[, (Vector3)start=Vector3(0, 0, 0)[, (Vector3)end=Vector3(0, 0, 0)]]]) float ¶
Compute packing porosity \(\frac{V-V_v}{V}\) where \(V\) is a specified volume (from start to end) and \(V_v\) is volume of voxels that fall inside any sphere. The calculation method is to divide whole volume into a dense grid of voxels (at given resolution), and count the voxels that fall inside any of the spheres. This method allows one to calculate porosity in any given sub-volume of a whole sample. It is properly excluding part of a sphere that does not fall inside a specified volume.
- yade._utils.wireAll() None ¶
Set Shape::wire on all bodies to True, rendering them with wireframe only.
- yade._utils.wireNoSpheres() None ¶
Set Shape::wire to True on non-spherical bodies (Facets, Walls).
- yade._utils.wireNone() None ¶
Set Shape::wire on all bodies to False, rendering them as solids.