yade-dev team mailing list archive
-
yade-dev team
-
Mailing list archive
-
Message #06418
[Branch ~yade-dev/yade/trunk] Rev 2588: 1. Fix L3Geom, add Sphere+Wall interactions, plus some benchmark scripts
------------------------------------------------------------
revno: 2588
committer: Václav Šmilauer <eu@xxxxxxxx>
branch nick: yade
timestamp: Sun 2010-12-05 18:10:06 +0100
message:
1. Fix L3Geom, add Sphere+Wall interactions, plus some benchmark scripts
2. Add NewtonIntegrator.kinSplit, to track translational and rotational energy separately
3. Add --randomize option to batch, for running jobs in arbitrary order
4. Make Body::setDynamic() (un)block State.blockedDOFs (for future compat)
5. Add Serializable::cast<Type> static casting method
6. Several fixes in utils, plot etc
renamed:
scripts/test/periodic-triax-velgrad.py => scripts/test/periodic-geom-compare.py
modified:
core/Body.hpp
core/main/yade-batch.in
examples/simple-scene/simple-scene.py
gui/qt4/__init__.py
lib/serialization/Serializable.hpp
pkg/dem/DomainLimiter.cpp
pkg/dem/L3Geom.cpp
pkg/dem/L3Geom.hpp
pkg/dem/NewtonIntegrator.cpp
pkg/dem/NewtonIntegrator.hpp
pkg/dem/Shop.cpp
pkg/dem/SimpleShear.cpp
py/plot.py
py/utils.py
py/wrapper/yadeWrapper.cpp
scripts/test/energy.py
scripts/test/law-test.py
scripts/test/periodic-geom-compare.py
--
lp:yade
https://code.launchpad.net/~yade-dev/yade/trunk
Your team Yade developers is subscribed to branch lp:yade.
To unsubscribe from this branch go to https://code.launchpad.net/~yade-dev/yade/trunk/+edit-subscription
=== modified file 'core/Body.hpp'
--- core/Body.hpp 2010-12-01 11:09:53 +0000
+++ core/Body.hpp 2010-12-05 17:10:06 +0000
@@ -51,7 +51,7 @@
// inline accessors
// logic: http://stackoverflow.com/questions/47981/how-do-you-set-clear-and-toggle-a-single-bit-in-c
bool isDynamic() const {return flags & FLAG_DYNAMIC; }
- void setDynamic(bool d){ if(d) flags|=FLAG_DYNAMIC; else flags&=~(FLAG_DYNAMIC); }
+ void setDynamic(bool d){ if(d){ flags|=FLAG_DYNAMIC; if(state) state->blockedDOFs=State::DOF_NONE; } else { flags&=~(FLAG_DYNAMIC); if(state){ state->blockedDOFs=State::DOF_ALL; state->vel=state->angVel=Vector3r::Zero(); } }}
bool isBounded() const {return flags & FLAG_BOUNDED; }
void setBounded(bool d){ if(d) flags|=FLAG_BOUNDED; else flags&=~(FLAG_BOUNDED); }
bool isAspherical() const {return flags & FLAG_ASPHERICAL; }
=== modified file 'core/main/yade-batch.in'
--- core/main/yade-batch.in 2010-11-25 13:51:43 +0000
+++ core/main/yade-batch.in 2010-12-05 17:10:06 +0000
@@ -4,7 +4,7 @@
# vim: syntax=python
# portions © 2008 Václav Šmilauer <eudoxos@xxxxxxxx>
-import os, sys, thread, time, logging, pipes, socket, xmlrpclib, re, shutil
+import os, sys, thread, time, logging, pipes, socket, xmlrpclib, re, shutil, random
#socket.setdefaulttimeout(10)
@@ -267,7 +267,9 @@
#print pending,'pending;',running,'running;',done,'done;',numFreeCores,'free;',minRequire,'min'
overloaded=False
if minRequire>numFreeCores and running==0: overloaded=True # a job wants more cores than the total we have
- for j in [j for j in jobs if j.status=='PENDING']:
+ pendingJobs=[j for j in jobs if j.status=='PENDING']
+ if opts.randomize: random.shuffle(pendingJobs)
+ for j in pendingJobs:
if j.nCores<=numFreeCores or overloaded:
freeCores=set(range(0,numCores))-set().union(*(j.cores for j in jobs if j.status=='RUNNING'))
#print 'freeCores:',freeCores,'numFreeCores:',numFreeCores,'overloaded',overloaded
@@ -309,6 +311,7 @@
parser.add_option('--plot-timeout',type='int',dest='plotTimeout',help='Maximum age (in seconds) of plots served over HTTP; they will be updated if they are older. (default: 10 seconds)',metavar='TIME',default=10)
parser.add_option('--timing',type='int',dest='timing',default=0,metavar='COUNT',help='Repeat each job COUNT times, and output a simple table with average/variance/minimum/maximum job duration; used for measuring how various parameters affect execution time. Jobs can override the global value with the !COUNT column.')
parser.add_option('--timing-output',type='str',metavar='FILE',dest='timingOut',default=None,help='With --timing, save measured durations to FILE, instead of writing to standard output.')
+parser.add_option('--randomize',action='store_true',dest='randomize',help='Randomize job order (within constraints given by assigned cores).')
#parser.add_option('--serial',action='store_true',dest='serial',default=False,help='Run all jobs serially, even if there are free cores
opts,args=parser.parse_args()
logFormat,lineList,maxJobs,nice,executable,gnuplotOut,dryRun,httpWait,globalLog=opts.logFormat,opts.lineList,opts.maxJobs,opts.nice,opts.executable,opts.gnuplotOut,opts.dryRun,opts.httpWait,opts.globalLog
=== modified file 'examples/simple-scene/simple-scene.py'
--- examples/simple-scene/simple-scene.py 2010-09-30 18:00:41 +0000
+++ examples/simple-scene/simple-scene.py 2010-12-05 17:10:06 +0000
@@ -23,21 +23,20 @@
Bo1_Sphere_Aabb(),
Bo1_Box_Aabb(),
]),
- ## Decide whether the potential collisions are real; if so, create geometry information about each potential collision.
- ## Here, the decision about which EngineUnit to use depends on types of _both_ bodies.
- ## Note that there is no EngineUnit for box-box collision. They are not implemented.
- IGeomDispatcher([
- Ig2_Sphere_Sphere_ScGeom(),
- Ig2_Box_Sphere_ScGeom()
- ]),
- ## Create physical information about the interaction.
- ## This may consist in deriving contact rigidity from elastic moduli of each body, for example.
- ## The purpose is that the contact may be "solved" without reference to related bodies,
- ## only with the information contained in contact geometry and physics.
- IPhysDispatcher([Ip2_FrictMat_FrictMat_FrictPhys()]),
- ## "Solver" of the contact, also called (consitutive) law.
- ## Based on the information in interaction physics and geometry, it applies corresponding forces on bodies in interaction.
- ElasticContactLaw(),
+ InteractionLoop(
+ ## Decide whether the potential collisions are real; if so, create geometry information about each potential collision.
+ ## Here, the decision about which EngineUnit to use depends on types of _both_ bodies.
+ ## Note that there is no EngineUnit for box-box collision. They are not implemented.
+ [Ig2_Sphere_Sphere_ScGeom(),Ig2_Box_Sphere_ScGeom()],
+ ## Create physical information about the interaction.
+ ## This may consist in deriving contact rigidity from elastic moduli of each body, for example.
+ ## The purpose is that the contact may be "solved" without reference to related bodies,
+ ## only with the information contained in contact geometry and physics.
+ [Ip2_FrictMat_FrictMat_FrictPhys()],
+ ## "Solver" of the contact, also called (consitutive) law.
+ ## Based on the information in interaction physics and geometry, it applies corresponding forces on bodies in interaction.
+ [Law2_ScGeom_FrictPhys_CundallStrack()]
+ ),
## Apply gravity: all bodies will have gravity applied on them.
## Note the engine parameter 'gravity', a vector that gives the acceleration.
GravityEngine(gravity=[0,0,-9.81]),
@@ -47,20 +46,6 @@
#
# note that following 4 engines (till the end) can be replaced by an optimized monolithic version:
NewtonIntegrator(damping=0.1)
- #
-# PhysicalActionDamper([
-# CundallNonViscousForceDamping(damping=0.2),
-# CundallNonViscousMomentumDamping(damping=0.2)
-# ]),
-# ## Now we have forces and momenta acting on bodies. Newton's law calculates acceleration that corresponds to them.
-# PhysicalActionApplier([
-# NewtonsForceLaw(),
-# NewtonsMomentumLaw(),
-# ]),
-# ## Acceleration results in velocity change. Integrating the velocity over dt, position of the body will change.
-# StateMetaEngine([LeapFrogPositionIntegrator()]),
-# ## Angular acceleration changes angular velocity, resulting in position and/or orientation change of the body.
-# StateMetaEngine([LeapFrogOrientationIntegrator()])
]
@@ -74,32 +59,9 @@
## * extents: half-size of the box. [.5,.5,.5] is unit cube
## * center: position of the center of the box
## * dynamic: it is not dynamic, i.e. will not move during simulation, even if forces are applied to it
-## * color: for the 3d display; specified within unit cube in the RGB space; [1,0,0] is, therefore, red
-## * young: Young's modulus
-## * poisson: Poissons's ratio
o.bodies.append(utils.box(center=[0,0,0],extents=[.5,.5,.5],color=[0,0,1],dynamic=False))
-## The above command could be actully written without the util.box function like this:
-## (will not be executed, since the condition is never True)
-if False:
- # Create empty body object
- b=Body()
- # set the isDynamic body attribute
- b.dynamic=False
- # Assign geometrical model (shape) to the body: a box of given size
- b.shape=Box(extents=[.5,.5,.5],color=[1,0,0])
- # physical parameters:
- # store mass to a temporary
- mass=8*.5*.5*.5*2400
- # * se3 (position & orientation) as 3 position coordinates, then 3 direction axis coordinates and rotation angle
- b.phys=BodyMacroParameters(se3=[0,0,0,1,0,0,0],mass=mass,inertia=[mass*4*(.5**2+.5**2),mass*4*(.5**2+.5**2),mass*4*(.5**2+.5**2)],young=30e9,poisson=.3)
- # other information about Aabb will be updated during simulation by the collider
- b.bound=Aabb(color=[0,1,0])
- # add the body to the simulation
- o.bodies.append(b)
-
-
## The sphere
##
## * First two arguments are radius and center, respectively. They are used as "positional arguments" here:
=== modified file 'gui/qt4/__init__.py'
--- gui/qt4/__init__.py 2010-11-02 12:02:13 +0000
+++ gui/qt4/__init__.py 2010-12-05 17:10:06 +0000
@@ -145,6 +145,8 @@
O.save(f)
def reloadSlot(self):
self.deactivateControls()
+ from yade import plot
+ plot.splitData()
O.reload()
def dtFixedSlot(self):
O.dt=O.dt
=== modified file 'lib/serialization/Serializable.hpp'
--- lib/serialization/Serializable.hpp 2010-11-07 11:46:20 +0000
+++ lib/serialization/Serializable.hpp 2010-12-05 17:10:06 +0000
@@ -251,17 +251,12 @@
#define REGISTER_ATTRIBUTES(baseClass,attrs) _REGISTER_ATTRIBUTES_DEPREC(_SOME_CLASS,baseClass,BOOST_PP_SEQ_FOR_EACH(_ATTR_NAME_ADD_DUMMY_FIELDS,~,attrs),)
-#if 0
-namespace{
- void pySetAttr(const std::string& key, const boost::python::object& /* value */){ PyErr_SetString(PyExc_AttributeError,(std::string("No such attribute: ")+key+".").c_str()); boost::python::throw_error_already_set(); }
- boost::python::list pyKeys(){ return boost::python::list();}
- boost::python::dict pyDict() { return boost::python::dict(); }
-};
-#endif
-
class Serializable: public Factorable {
public:
template <class ArchiveT> void serialize(ArchiveT & ar, unsigned int version){ };
+ // lovely cast members like in eigen :-)
+ template <class DerivedT> const DerivedT& cast() const { return *static_cast<DerivedT*>(this); }
+ template <class DerivedT> DerivedT& cast(){ return *static_cast<DerivedT*>(this); }
Serializable() {};
virtual ~Serializable() {};
=== modified file 'pkg/dem/DomainLimiter.cpp'
--- pkg/dem/DomainLimiter.cpp 2010-11-17 11:25:26 +0000
+++ pkg/dem/DomainLimiter.cpp 2010-12-05 17:10:06 +0000
@@ -56,7 +56,10 @@
const shared_ptr<Interaction> Inew=scene->interactions->find(ids[0],ids[1]);
string strIds("##"+lexical_cast<string>(ids[0])+"+"+lexical_cast<string>(ids[1]));
// interaction not found at initialization
- if(!I && (!Inew || !Inew->isReal())) throw std::runtime_error("LawTester: interaction "+strIds+" does not exist"+(Inew?" (to be honest, it does exist, but it is not real).":"."));
+ if(!I && (!Inew || !Inew->isReal())){
+ LOG_WARN("Interaction "<<strIds<<" does not exist (yet?), no-op."); return;
+ //throw std::runtime_error("LawTester: interaction "+strIds+" does not exist"+(Inew?" (to be honest, it does exist, but it is not real).":"."));
+ }
// interaction was deleted meanwhile
if(I && (!Inew || !Inew->isReal())) throw std::runtime_error("LawTester: interaction "+strIds+" was deleted"+(Inew?" (is not real anymore).":"."));
// different interaction object
@@ -120,7 +123,7 @@
trsf.col(0)=axX; trsf.col(1)=axY; trsf.col(2)=axZ;
} else {
trsf=l3Geom->trsf;
- axX=trsf.col(0); axY=trsf.col(1); axZ=trsf.col(2);
+ axX=trsf.row(0); axY=trsf.row(1); axZ=trsf.row(2);
ptGeom=l3Geom->u;
if(l6Geom) rotGeom=l6Geom->phi;
}
@@ -151,11 +154,13 @@
for(int i=0; i<2; i++){
int sign=(i==0?-1:1);
Real weight=(i==0?1-idWeight:idWeight);
+ // FIXME: this should not use refR1, but real CP-particle distance!
Real radius=(i==0?gsc->refR1:gsc->refR2);
+ Real relRad=radius/refLength;
// signed and weighted displacement/rotation to be applied on this sphere (reversed for #0)
// some rotations must cancel the sign, by multiplying by sign again
Vector3r ddU=sign*dU*weight;
- Vector3r ddPhi=sign*dPhi*weight;
+ Vector3r ddPhi=sign*dPhi*(1-relRad); /* angles must distribute to both, otherwise it would induce shear; FIXME: combination of shear and bending must make sure they are properly orthogonal! (rotWeight=?) */
vel[i]=angVel[i]=Vector3r::Zero();
// normal displacement
@@ -227,10 +232,10 @@
// switch to local coordinates
glTranslatev(tester->contPt);
#if EIGEN_MAJOR_VERSION<20 //Eigen3 definition, while it is not realized
- glMultMatrixd(Eigen::Transform3d(tester->trsf).data());
- #else
- glMultMatrixd(Eigen::Affine3d(tester->trsf).data());
- #endif
+ glMultMatrixd(Eigen::Transform3d(tester->trsf.transpose()).data());
+ #else
+ glMultMatrixd(Eigen::Affine3d(tester->trsf.transpose()).data());
+ #endif
glDisable(GL_LIGHTING);
=== modified file 'pkg/dem/L3Geom.cpp'
--- pkg/dem/L3Geom.cpp 2010-11-07 11:46:20 +0000
+++ pkg/dem/L3Geom.cpp 2010-12-05 17:10:06 +0000
@@ -1,13 +1,27 @@
#include<yade/pkg/dem/L3Geom.hpp>
#include<yade/pkg/common/Sphere.hpp>
-
-YADE_PLUGIN((L3Geom)(Ig2_Sphere_Sphere_L3Geom_Inc)(Law2_L3Geom_FrictPhys_ElPerfPl)(Law2_L6Geom_FrictPhys_Linear));
+#include<yade/pkg/common/Wall.hpp>
+
+#ifdef YADE_OPENGL
+ #include<yade/lib/opengl/OpenGLWrapper.hpp>
+ #include<yade/lib/opengl/GLUtils.hpp>
+ #include<GL/glu.h>
+#endif
+
+YADE_PLUGIN((L3Geom)(Ig2_Sphere_Sphere_L3Geom_Inc)(Ig2_Wall_Sphere_L3Geom_Inc)(Ig2_Sphere_Sphere_L6Geom_Inc)(Law2_L3Geom_FrictPhys_ElPerfPl)(Law2_L6Geom_FrictPhys_Linear)
+ #ifdef YADE_OPENGL
+ (Gl1_L3Geom)
+ #endif
+);
L3Geom::~L3Geom(){}
void L3Geom::applyLocalForceTorque(const Vector3r& localF, const Vector3r& localT, const Interaction* I, Scene* scene, NormShearPhys* nsp) const {
+
+ Vector2r foo; // avoid undefined ~Vector2r with clang?
+
Vector3r globF=trsf.transpose()*localF; // trsf is orthonormal, therefore inverse==transpose
- Vector3r x1c(normal*(refR1+.5*u[0])), x2c(normal*(refR1+.5*u[0]));
+ Vector3r x1c(normal*(refR1+.5*u[0])), x2c(-normal*(refR2+.5*u[0]));
if(nsp){ nsp->normalForce=normal*globF.dot(normal); nsp->shearForce=globF-nsp->normalForce; }
Vector3r globT=Vector3r::Zero();
// add torque, if any
@@ -33,11 +47,14 @@
};
+CREATE_LOGGER(Ig2_Sphere_Sphere_L3Geom_Inc);
+
bool Ig2_Sphere_Sphere_L3Geom_Inc::genericGo(bool is6Dof, const shared_ptr<Shape>& s1, const shared_ptr<Shape>& s2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& I){
+ // temporary hack only, to not have elastic potential energy in rigid packings with overlapping spheres
+ //if(state1.blockedDOFs==State::DOF_ALL && state2.blockedDOFs==State::DOF_ALL) return false;
- const Se3r& se31=state1.se3; const Se3r& se32=state2.se3;
- const Real& r1(static_pointer_cast<Sphere>(s1)->radius); const Real& r2(static_pointer_cast<Sphere>(s2)->radius);
- Vector3r relPos=(se32.position+shift2)-se31.position;
+ const Real& r1=s1->cast<Sphere>().radius; const Real& r2=s2->cast<Sphere>().radius;
+ Vector3r relPos=state2.pos+shift2-state1.pos;
Real unDistSq=relPos.squaredNorm()-pow(distFactor*(r1+r2),2);
if (unDistSq>0 && !I->isReal() && !force) return false;
@@ -46,21 +63,21 @@
Real dist=relPos.norm();
Real uN=dist-(r1+r2);
Vector3r normal=relPos/dist;
- Vector3r contPt=se31.position+(r1+0.5*uN)*normal;
+ Vector3r contPt=state1.pos+(r1+0.5*uN)*normal;
// create geometry
if(!I->geom){
if(is6Dof) I->geom=shared_ptr<L6Geom>(new L6Geom);
else I->geom=shared_ptr<L3Geom>(new L3Geom);
- const shared_ptr<L3Geom>& g(static_pointer_cast<L3Geom>(I->geom));
- g->contactPoint=contPt;
- g->refR1=r1; g->refR2=r1;
- g->normal=normal; const Vector3r& locX(g->normal);
+ L3Geom& g(I->geom->cast<L3Geom>());
+ g.contactPoint=contPt;
+ g.refR1=r1; g.refR2=r1;
+ g.normal=normal; const Vector3r& locX(g.normal);
// initial local y-axis orientation, in the xz or xy plane, depending on which component is larger to avoid singularities
- Vector3r locY=g->normal.cross(g->normal[1]>g->normal[2]?Vector3r::UnitY():Vector3r::UnitZ());
- Vector3r locZ=g->normal.cross(locY);
- g->trsf.col(0)=locX; g->trsf.col(1)=locY; g->trsf.col(2)=locZ;
- g->u=Vector3r(uN,0,0); // zero shear displacement
+ Vector3r locY=g.normal.cross(g.normal[1]>g.normal[2]?Vector3r::UnitY():Vector3r::UnitZ());
+ Vector3r locZ=g.normal.cross(locY);
+ g.trsf.row(0)=locX; g.trsf.row(1)=locY; g.trsf.row(2)=locZ;
+ g.u=Vector3r(uN,0,0); // zero shear displacement
// L6Geom::phi is initialized to Vector3r::Zero() automatically
return true;
}
@@ -71,8 +88,8 @@
they are used to update trsf and u
*/
- const shared_ptr<L3Geom>& g(static_pointer_cast<L3Geom>(I->geom));
- const Vector3r& currNormal(normal); const Vector3r& prevNormal(g->normal);
+ L3Geom& g(I->geom->cast<L3Geom>());
+ const Vector3r& currNormal(normal); const Vector3r& prevNormal(g.normal);
// normal rotation vector, between last steps
Vector3r normRotVec=prevNormal.cross(currNormal);
// contrary to what ScGeom::precompute does now (r2486), we take average normal, i.e. .5*(prevNormal+currNormal),
@@ -85,7 +102,7 @@
// compute relative velocity
// noRatch: take radius or current distance as the branch vector; see discussion in ScGeom::precompute (avoidGranularRatcheting)
Vector3r c1x=(noRatch ? ( r1*normal).eval() : (contPt-state1.pos).eval());
- Vector3r c2x=(noRatch ? (-r2*normal).eval() : (contPt-state2.pos).eval());
+ Vector3r c2x=(noRatch ? (-r2*normal).eval() : (contPt-state2.pos+shift2).eval());
Vector3r relShearVel=(state2.vel+state2.angVel.cross(c2x))-(state1.vel+state1.angVel.cross(c1x));
// account for relative velocity of particles in different cell periods
if(scene->isPeriodic) relShearVel+=scene->cell->velGrad*scene->cell->Hsize*I->cellDist.cast<Real>();
@@ -104,9 +121,9 @@
// compute current transformation, by updating previous axes
// the X axis can be prescribed directly (copy of normal)
// the mutual motion on the contact does not change transformation
- const Matrix3r& prevTrsf(g->trsf); Matrix3r currTrsf; currTrsf.col(0)=currNormal;
+ const Matrix3r& prevTrsf(g.trsf); Matrix3r currTrsf; currTrsf.row(0)=currNormal;
for(int i=1; i<3; i++){
- currTrsf.col(i)=prevTrsf.col(i)-prevTrsf.col(i).cross(normRotVec)-prevTrsf.col(i).cross(normTwistVec);
+ currTrsf.row(i)=prevTrsf.row(i)-prevTrsf.row(i).cross(normRotVec)-prevTrsf.row(i).cross(normTwistVec);
}
if(!(approxMask | APPROX_NO_RENORM_TRSF)){ /* renormalizing quternion is faster*/ currTrsf=Matrix3r(Quaternionr(currTrsf).normalized()); }
@@ -122,48 +139,116 @@
but it would have to be verified somehow.
*/
// if requested via approxMask, just use prevTrsf
+
Quaternionr midTrsf=(approxMask|APPROX_NO_MID_TRSF) ? Quaternionr(prevTrsf) : Quaternionr(prevTrsf).slerp(.5,Quaternionr(currTrsf));
+ // cerr<<"prevTrsf=\n"<<prevTrsf<<", currTrsf=\n"<<currTrsf<<", midTrsf=\n"<<Matrix3r(midTrsf)<<endl;
// updates of geom here
// midTrsf*relShearVel should have the 0-th component (approximately) zero -- to be checked
- g->u+=midTrsf*relShearDu;
- g->u[0]=uN; // this does not have to be computed incrementally
- g->trsf=currTrsf;
+ g.u+=midTrsf*relShearDu;
+ //cerr<<"midTrsf=\n"<<midTrsf<<",relShearDu="<<relShearDu<<", transformed "<<midTrsf*relShearDu<<endl;
+ g.u[0]=uN; // this does not have to be computed incrementally
+ g.trsf=currTrsf;
// GenericSpheresContact
- g->refR1=r1; g->refR2=r2;
- g->normal=currNormal;
- g->contactPoint=contPt;
+ g.refR1=r1; g.refR2=r2;
+ g.normal=currNormal;
+ g.contactPoint=contPt;
if(is6Dof){
- const shared_ptr<L6Geom> g6=static_pointer_cast<L6Geom>(g);
// update phi, from the difference of angular velocities
// the difference is transformed to local coord using the midTrsf transformation
- g6->phi+=midTrsf*(scene->dt*(state2.angVel-state1.angVel));
- }
-
- return true;
-};
-
+ // perhaps not consistent when spheres have different radii (depends how bending moment is computed)
+ I->geom->cast<L6Geom>().phi+=midTrsf*(scene->dt*(state2.angVel-state1.angVel));
+ #if 0
+ Vector3r u2=state2.vel+state2.angVel.cross(c2x)
+ Vector3r u1=state1.vel+state1.angVel.cross(c1x);
+ Vector3r rigidRot=relPos.cross(state2.vel-state1.vel); // rigid rotation of the interaction
+ // symmetric part of the mutual rotation is bending
+ g->cast<L6Geom>().phi+=midTrsf*(scene->dt*(2*(u1+u2)/2.-rigidRot)/dist);
+ #endif
+ }
+ return true;
+};
+
+bool Ig2_Wall_Sphere_L3Geom_Inc::go(const shared_ptr<Shape>& s1, const shared_ptr<Shape>& s2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& I){
+ if(scene->isPeriodic) throw std::logic_error("Ig2_Wall_Sphere_L3Geom_Inc does not handle periodic boundary conditions.");
+ const Real& radius=s2->cast<Sphere>().radius; const int& ax(s1->cast<Wall>().axis); const int& sense(s1->cast<Wall>().sense);
+ Real dist=state2.pos[ax]+shift2[ax]-state1.pos[ax]; // signed "distance" between centers
+ if(!I->isReal() && abs(dist)>radius && !force) { return false; }// wall and sphere too far from each other
+ // contact point is sphere center projected onto the wall
+ Vector3r contPt=state2.pos+shift2; contPt[ax]=state1.pos[ax];
+ Vector3r normal=Vector3r::Zero();
+ // wall interacting from both sides: normal depends on sphere's position
+ assert(sense==-1 || sense==0 || sense==1);
+ if(sense==0) normal[ax]=dist>0?1.:-1.;
+ else normal[ax]=sense==1?1.:-1;
+ Real uN=normal[ax]*dist-radius; // takes in account sense, radius and distance
+
+ if(!I->geom){
+ /* if(is6Dof) I->geom=shared_ptr<L6Geom>(new L6Geom);
+ else */ I->geom=shared_ptr<L3Geom>(new L3Geom);
+ L3Geom& g=I->geom->cast<L3Geom>();
+ g.contactPoint=contPt;
+ g.refR1=0; g.refR2=radius;
+ g.normal=normal;
+ g.trsf=Matrix3r::Zero();
+ g.trsf.row(0)=normal; g.trsf.row(1)[(ax+1)%3]=1; g.trsf.row(2)[(ax+2)%3]=1;
+ g.u=Vector3r(uN,0,0); // zero shear displacement
+ // L6Geom::phi is initialized to Vector3r::Zero() automatically
+ return true;
+ }
+ L3Geom& g=I->geom->cast<L3Geom>();
+ if(g.normal!=normal) throw std::logic_error(("Ig2_Wall_Sphere_L3Geom_Inc: normal changed in Wall+Sphere ##"+lexical_cast<string>(I->getId1())+"+"+lexical_cast<string>(I->getId2())+" (Wall.senseâ 0?)").c_str());
+ Vector3r normTwistVec=normal*scene->dt*.5*normal.dot(state1.angVel+state2.angVel);
+
+ /* TODO: below is a lot of code common with Sphere+Sphere; identify, factor out in a separate func */
+ /* needed params: states, geom (trsf, contact point, normal), branch vectors. That's it? */
+
+ Vector3r c1x=contPt-state1.pos; // is not aligned with normal; Wall could rotate in a plate-like manner
+ Vector3r c2x=(noRatch ? (-radius*normal).eval() : (contPt-state2.pos+shift2).eval());
+ Vector3r relShearVel=(state2.vel+state2.angVel.cross(c2x))-(state1.vel+state1.angVel.cross(c1x));
+ // perhaps not necessary, see in Ig2_Sphere_Sphere_L3Geom_Inc
+ relShearVel-=normal.dot(relShearVel)*normal;
+ Vector3r relShearDu=relShearVel*scene->dt;
+ // normal did not change, no need to re-assign row(0); no normRotVec either, since the normal orientation never changes
+ Matrix3r prevTrsf(g.trsf); // copy
+ for(int i=1; i<3; i++){ g.trsf.row(i)=g.trsf.row(i)-g.trsf.row(i).cross(normTwistVec); }
+ if(!(approxMask | APPROX_NO_RENORM_TRSF)){ /* renormalizing quternion is faster*/ g.trsf=Matrix3r(Quaternionr(g.trsf).normalized()); }
+ Quaternionr midTrsf=(approxMask|APPROX_NO_MID_TRSF) ? Quaternionr(prevTrsf) : Quaternionr(prevTrsf).slerp(.5,Quaternionr(g.trsf));
+ g.u+=midTrsf*relShearDu;
+ g.u[0]=uN;
+ // GenericSpheresContact
+ g.refR1=0; g.refR2=radius;
+ g.contactPoint=contPt;
+ /* if(is6Dof){ } */
+ return true;
+};
void Law2_L3Geom_FrictPhys_ElPerfPl::go(shared_ptr<IGeom>& ig, shared_ptr<IPhys>& ip, Interaction* I){
L3Geom* geom=static_cast<L3Geom*>(ig.get()); FrictPhys* phys=static_cast<FrictPhys*>(ip.get());
// compute force
- Vector3r localF=geom->relU().cwise()*Vector3r(phys->kn,phys->ks,phys->ks);
+ Vector3r& localF(geom->F);
+ localF=geom->relU().cwise()*Vector3r(phys->kn,phys->ks,phys->ks);
// break if necessary
if(localF[0]>0 && !noBreak){ scene->interactions->requestErase(I->getId1(),I->getId2()); }
if(!noSlip){
- // plastic slip, if necessary
- Real maxFs=localF[0]*phys->tangensOfFrictionAngle; Vector2r Fs=Vector2r::Map(&localF[1]);
+ // plastic slip, if necessary; non-zero elastic limit only for compression
+ Real maxFs=-min(0.,localF[0]*phys->tangensOfFrictionAngle); Eigen::Map<Vector2r> Fs(&localF[1]);
+ //cerr<<"u="<<geom->relU()<<", maxFs="<<maxFs<<", Fn="<<localF[0]<<", |Fs|="<<Fs.norm()<<", Fs="<<Fs<<endl;
if(Fs.squaredNorm()>maxFs*maxFs){
Real ratio=sqrt(maxFs*maxFs/Fs.squaredNorm());
- geom->u0+=(1-ratio)*Vector3r(0,geom->relU()[1],geom->relU()[2]); // increment plastic displacement
+ Vector3r u0slip=(1-ratio)*Vector3r(/*no slip in the normal sense*/0,geom->relU()[1],geom->relU()[2]);
+ geom->u0+=u0slip; // increment plastic displacement
Fs*=ratio; // decrement shear force value;
+ //cerr<<"SLIP: Fs="<<Fs<<", ratio="<<ratio<<", u0slip="<<u0slip<<", localF="<<localF<<endl;
+ if(unlikely(scene->trackEnergy)){ Real dissip=Fs.norm()*u0slip.norm(); if(dissip>0) scene->energy->add(dissip,"plastDissip",plastDissipIx,/*reset*/false); }
}
}
+ if(unlikely(scene->trackEnergy)){ scene->energy->add(0.5*(pow(geom->relU()[0],2)*phys->kn+(pow(geom->relU()[1],2)+pow(geom->relU()[2],2))*phys->ks),"elastPotential",elastPotentialIx,/*reset at every timestep*/true); }
// apply force: this converts the force to global space, updates NormShearPhys::{normal,shear}Force, applies to particles
geom->applyLocalForce(localF,I,scene,phys);
}
@@ -177,3 +262,27 @@
geom->applyLocalForceTorque(localF,localT,I,scene,phys);
}
+
+#ifdef YADE_OPENGL
+
+void Gl1_L3Geom::go(const shared_ptr<IGeom>& ig, const shared_ptr<Interaction>&, const shared_ptr<Body>&, const shared_ptr<Body>&, bool){
+ const L3Geom& g(ig->cast<L3Geom>());
+ glTranslatev(g.contactPoint);
+ #if EIGEN_MAJOR_VERSION<30
+ glMultMatrixd(Eigen::Transform3d(g.trsf.transpose()).data());
+ #else
+ glMultMatrixd(Eigen::Affine3d(g.trsf.transpose()).data());
+ #endif
+ Real rMin=min(g.refR1,g.refR2);
+ glLineWidth(2.);
+ for(int i=0; i<3; i++){
+ Vector3r pt=Vector3r::Zero(); pt[i]=.5*rMin; Vector3r color=.3*Vector3r::Ones(); color[i]=1;
+ GLUtils::GLDrawLine(Vector3r::Zero(),pt,color);
+ GLUtils::GLDrawText(string(i==0?"x":(i==1?"y":"z")),pt,color);
+ }
+ glLineWidth(8.);
+ GLUtils::GLDrawLine(Vector3r::Zero(),g.relU(),Vector3r(0,1,0));
+ glLineWidth(1.);
+};
+
+#endif
=== modified file 'pkg/dem/L3Geom.hpp'
--- pkg/dem/L3Geom.hpp 2010-11-07 11:46:20 +0000
+++ pkg/dem/L3Geom.hpp 2010-12-05 17:10:06 +0000
@@ -7,6 +7,9 @@
#include<yade/pkg/common/Dispatching.hpp>
#include<yade/pkg/dem/DemXDofGeom.hpp>
#include<yade/pkg/dem/FrictPhys.hpp>
+#ifdef YADE_OPENGL
+ #include<yade/pkg/common/GLDrawFunctors.hpp>
+#endif
struct L3Geom: public GenericSpheresContact{
const Real& uN;
@@ -31,6 +34,7 @@
* We need to extract local axes, and that is easier to be done from Matrix3r (columns)
*/
((Matrix3r,trsf,Matrix3r::Identity(),,"Transformation (rotation) from global to local coordinates. (the translation part is in :yref:`GenericSpheresContact.contactPoint`)"))
+ ((Vector3r,F,Vector3r::Zero(),,"Applied force in local coordinates [debugging only, will be removed]"))
,
/*init*/
((uN,u[0])) ((uT,Vector2r::Map(&u[1])))
@@ -44,11 +48,20 @@
};
REGISTER_SERIALIZABLE(L3Geom);
+#ifdef YADE_OPENGL
+struct Gl1_L3Geom: public GlIGeomFunctor{
+ FUNCTOR1D(L3Geom);
+ void go(const shared_ptr<IGeom>&, const shared_ptr<Interaction>&, const shared_ptr<Body>&, const shared_ptr<Body>&, bool);
+ YADE_CLASS_BASE_DOC_STATICATTRS(Gl1_L3Geom,GlIGeomFunctor,"Render :yref:`L3Geom` geometry.",
+ );
+};
+REGISTER_SERIALIZABLE(Gl1_L3Geom);
+#endif
struct L6Geom: public L3Geom{
virtual ~L6Geom();
Vector3r relPhi() const{ return phi-phi0; }
- YADE_CLASS_BASE_DOC_ATTRS(L6Geom,L3Geom,"Geoemtric of contact in local coordinates with 6 degrees of freedom. [experimental]",
+ YADE_CLASS_BASE_DOC_ATTRS(L6Geom,L3Geom,"Geometric of contact in local coordinates with 6 degrees of freedom. [experimental]",
((Vector3r,phi,Vector3r::Zero(),,"Rotation components, in local coordinates. |yupdate|"))
((Vector3r,phi0,Vector3r::Zero(),,"Zero rotation, should be always subtracted from *phi* to get the value. See :yref:`L3Geom.u0`."))
);
@@ -69,9 +82,20 @@
);
FUNCTOR2D(Sphere,Sphere);
DEFINE_FUNCTOR_ORDER_2D(Sphere,Sphere);
+ DECLARE_LOGGER;
};
REGISTER_SERIALIZABLE(Ig2_Sphere_Sphere_L3Geom_Inc);
+struct Ig2_Wall_Sphere_L3Geom_Inc: public Ig2_Sphere_Sphere_L3Geom_Inc{
+ virtual bool go(const shared_ptr<Shape>& s1, const shared_ptr<Shape>& s2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& I);
+ //virtual bool genericGo(bool is6Dof, const shared_ptr<Shape>& s1, const shared_ptr<Shape>& s2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& I);
+ YADE_CLASS_BASE_DOC(Ig2_Wall_Sphere_L3Geom_Inc,Ig2_Sphere_Sphere_L3Geom_Inc,"Incrementally compute :yref:`L3Geom` for contact between :yref:`Wall` and :yref:`Sphere`. Uses attributes of :yref:`Ig2_Sphere_Sphere_L3Geom_Inc`.");
+ FUNCTOR2D(Wall,Sphere);
+ DEFINE_FUNCTOR_ORDER_2D(Wall,Sphere);
+ DECLARE_LOGGER;
+};
+REGISTER_SERIALIZABLE(Ig2_Wall_Sphere_L3Geom_Inc);
+
struct Ig2_Sphere_Sphere_L6Geom_Inc: public Ig2_Sphere_Sphere_L3Geom_Inc{
virtual bool go(const shared_ptr<Shape>& s1, const shared_ptr<Shape>& s2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& I);
@@ -88,6 +112,8 @@
YADE_CLASS_BASE_DOC_ATTRS(Law2_L3Geom_FrictPhys_ElPerfPl,LawFunctor,"Basic law for testing :yref:`L3Geom`; it bears no cohesion (unless *noBreak* is ``True``), and plastic slip obeys the Mohr-Coulomb criterion (unless *noSlip* is ``True``).",
((bool,noBreak,false,,"Do not break contacts when particles separate."))
((bool,noSlip,false,,"No plastic slipping."))
+ ((int,plastDissipIx,-1,(Attr::noSave|Attr::hidden),"Index of plastically dissipated energy"))
+ ((int,elastPotentialIx,-1,(Attr::hidden|Attr::noSave),"Index for elastic potential energy (with O.trackEnergy)"))
);
};
REGISTER_SERIALIZABLE(Law2_L3Geom_FrictPhys_ElPerfPl);
@@ -100,3 +126,4 @@
);
};
REGISTER_SERIALIZABLE(Law2_L6Geom_FrictPhys_Linear);
+
=== modified file 'pkg/dem/NewtonIntegrator.cpp'
--- pkg/dem/NewtonIntegrator.cpp 2010-11-30 13:51:41 +0000
+++ pkg/dem/NewtonIntegrator.cpp 2010-12-05 17:10:06 +0000
@@ -123,14 +123,16 @@
if(!b->isAspherical()) scene->energy->add(state->angVel.cwise().abs().dot(m.cwise().abs())*damping*dt,"nonviscDamp",nonviscDampIx,false);
}
// kinetic energy
- Real Ek=.5*state->mass*fluctVel.squaredNorm();
+ Real Etrans=.5*state->mass*fluctVel.squaredNorm();
+ Real Erot;
// rotational terms
if(b->isAspherical()){
Matrix3r mI; mI<<state->inertia[0],0,0, 0,state->inertia[1],0, 0,0,state->inertia[2];
Matrix3r T(state->ori);
- Ek+=.5*b->state->angVel.transpose().dot((T.transpose()*mI*T)*b->state->angVel);
- } else { Ek+=state->angVel.dot(state->inertia.cwise()*state->angVel); }
- scene->energy->add(Ek,"kinetic",kinEnergyIx,/*non-incremental*/true);
+ Erot=.5*b->state->angVel.transpose().dot((T.transpose()*mI*T)*b->state->angVel);
+ } else { Erot=state->angVel.dot(state->inertia.cwise()*state->angVel); }
+ if(!kinSplit) scene->energy->add(Etrans+Erot,"kinetic",kinEnergyIx,/*non-incremental*/true);
+ else{ scene->energy->add(Etrans,"kinTrans",kinEnergyTransIx,true); scene->energy->add(Erot,"kinRot",kinEnergyRotIx,true); }
}
if (likely(b->isStandalone())){
=== modified file 'pkg/dem/NewtonIntegrator.hpp'
--- pkg/dem/NewtonIntegrator.hpp 2010-11-13 21:11:39 +0000
+++ pkg/dem/NewtonIntegrator.hpp 2010-12-05 17:10:06 +0000
@@ -55,8 +55,12 @@
((vector<shared_ptr<BodyCallback> >,callbacks,,,"List (std::vector in c++) of :yref:`BodyCallbacks<BodyCallback>` which will be called for each body as it is being processed."))
((Vector3r,prevCellSize,Vector3r(NaN,NaN,NaN),Attr::hidden,"cell size from previous step, used to detect change and find max velocity"))
((bool,warnNoForceReset,true,,"Warn when forces were not resetted in this step by :yref:`ForceResetter`; this mostly points to :yref:`ForceResetter` being forgotten incidentally and should be disabled only with a good reason."))
+ // energy tracking
((int,nonviscDampIx,-1,(Attr::hidden|Attr::noSave),"Index of the energy dissipated using the non-viscous damping (:yref:`damping<NewtonIntegrator.damping>`)."))
+ ((bool,kinSplit,false,,"Whether to separately track translational and rotational kinetic energy."))
((int,kinEnergyIx,-1,(Attr::hidden|Attr::noSave),"Index for kinetic energy in scene->energies."))
+ ((int,kinEnergyTransIx,-1,(Attr::hidden|Attr::noSave),"Index for translational kinetic energy in scene->energies."))
+ ((int,kinEnergyRotIx,-1,(Attr::hidden|Attr::noSave),"Index for rotational kinetic energy in scene->energies."))
,
/*ctor*/
#ifdef YADE_OPENMP
=== modified file 'pkg/dem/Shop.cpp'
--- pkg/dem/Shop.cpp 2010-11-13 21:11:39 +0000
+++ pkg/dem/Shop.cpp 2010-12-05 17:10:06 +0000
@@ -272,7 +272,6 @@
/*! Create body - sphere. */
shared_ptr<Body> Shop::sphere(Vector3r center, Real radius, shared_ptr<Material> mat){
shared_ptr<Body> body(new Body);
- body->setDynamic(true);
body->material=mat ? mat : static_pointer_cast<Material>(defaultGranularMat());
body->state->pos=center;
body->state->mass=4.0/3.0*Mathr::PI*radius*radius*radius*body->material->density;
@@ -285,7 +284,6 @@
/*! Create body - box. */
shared_ptr<Body> Shop::box(Vector3r center, Vector3r extents, shared_ptr<Material> mat){
shared_ptr<Body> body(new Body);
- body->setDynamic(true);
body->material=mat ? mat : static_pointer_cast<Material>(defaultGranularMat());
body->state->pos=center;
Real mass=8.0*extents[0]*extents[1]*extents[2]*body->material->density;
@@ -299,7 +297,6 @@
/*! Create body - tetrahedron. */
shared_ptr<Body> Shop::tetra(Vector3r v_global[4], shared_ptr<Material> mat){
shared_ptr<Body> body(new Body);
- body->setDynamic(true);
body->material=mat ? mat : static_pointer_cast<Material>(defaultGranularMat());
Vector3r centroid=(v_global[0]+v_global[1]+v_global[2]+v_global[3])*.25;
Vector3r v[4]; for(int i=0; i<4; i++) v[i]=v_global[i]-centroid;
=== modified file 'pkg/dem/SimpleShear.cpp'
--- pkg/dem/SimpleShear.cpp 2010-11-12 08:03:16 +0000
+++ pkg/dem/SimpleShear.cpp 2010-12-05 17:10:06 +0000
@@ -119,7 +119,6 @@
// shared_ptr<SphereModel> gSphere(new SphereModel);
shared_ptr<Sphere> iSphere(new Sphere);
- body->setDynamic(true);
body->state->pos =position;
body->state->ori =Quaternionr::Identity();
body->state->vel =Vector3r(0,0,0);
=== modified file 'py/plot.py'
--- py/plot.py 2010-11-15 16:49:59 +0000
+++ py/plot.py 2010-12-05 17:10:06 +0000
@@ -86,7 +86,7 @@
numSamples=len(data[data.keys()[0]]) if len(data)>0 else 0
for d in dd:
if d in data.keys(): continue
- d[d]=[nan for i in range(numSamples)]
+ data[d]=[nan for i in range(numSamples)]
def addData(*d_in,**kw):
"""Add data from arguments name1=value1,name2=value2 to yade.plot.data.
@@ -177,8 +177,10 @@
# create y1 lines
for d in plots_p_y1:
line,=pylab.plot(data[pStrip],data[d[0]],d[1])
- scatterPt=([0],[0]) if len(data[pStrip])==0 else (data[pStrip][current],data[d[0]][current])
- scatter=pylab.scatter(scatterPt[0],scatterPt[1],color=line.get_color())
+ # use (0,0) if there are no data yet
+ scatterPt=[0,0] if len(data[pStrip])==0 else (data[pStrip][current],data[d[0]][current])
+ # if current value is NaN, use zero instead
+ scatter=pylab.scatter(scatterPt[0] if not math.isnan(scatterPt[0]) else 0,scatterPt[1] if not math.isnan(scatterPt[1]) else 0,color=line.get_color())
currLineRefs.append(LineRef(line,scatter,data[pStrip],data[d[0]]))
# create the legend
l=pylab.legend([xlateLabel(_p[0]) for _p in plots_p_y1],loc=('upper left' if len(plots_p_y2)>0 else 'best'))
=== modified file 'py/utils.py'
--- py/utils.py 2010-11-02 12:02:13 +0000
+++ py/utils.py 2010-12-05 17:10:06 +0000
@@ -794,7 +794,7 @@
# !something cols are skipped, those are env vars we don't treat at all (they are contained in description, though)
for col in vv.keys():
if col=='description' or col[0]=='!': continue
- if col not in kw.keys() and (not unknownOk): raise NameError("Parameter `%s' has no default value assigned"%names[i])
+ if col not in kw.keys() and (not unknownOk): raise NameError("Parameter `%s' has no default value assigned"%col)
if vv[col]=='*': vv[col]=kw[col] # use default value for * in the table
elif col in kw.keys(): kw.pop(col) # remove the var from kw, so that it contains only those that were default at the end of this loop
#print 'ASSIGN',col,vv[col]
=== modified file 'py/wrapper/yadeWrapper.cpp'
--- py/wrapper/yadeWrapper.cpp 2010-11-24 22:42:15 +0000
+++ py/wrapper/yadeWrapper.cpp 2010-12-05 17:10:06 +0000
@@ -122,7 +122,6 @@
shared_ptr<Body> clumpBody=shared_ptr<Body>(new Body());
shared_ptr<Clump> clump=shared_ptr<Clump>(new Clump());
clumpBody->shape=clump;
- clumpBody->setDynamic(true);
clumpBody->setBounded(false);
proxee->insert(clumpBody);
// add clump members to the clump
=== modified file 'scripts/test/energy.py'
--- scripts/test/energy.py 2010-11-15 17:18:44 +0000
+++ scripts/test/energy.py 2010-12-05 17:10:06 +0000
@@ -1,25 +1,36 @@
from yade import pack,plot
+useL3Geom=True
+
sp=pack.SpherePack();
# bunch of balls, with an infinite plane just underneath
-if 0: sp.makeCloud((0,0,0),(1,1,1),.05,.5);
-# use clumps of 2 spheres instead, to have rotation without friction
-else: sp.makeClumpCloud((0,0,0),(1,1,1),[pack.SpherePack([((0,0,0),.05),((0,0,.08),.02)])],periodic=False)
-sp.toSimulation()
-O.bodies.append(utils.wall(position=0,axis=2))
+if 1:
+ if 1: sp.makeCloud((0,0,0),(1,1,1),.05,.5);
+ # use clumps of 2 spheres instead, to have rotation without friction
+ else: sp.makeClumpCloud((0,0,0),(1,1,1),[pack.SpherePack([((0,0,0),.05),((0,0,.08),.02)])],periodic=False)
+ sp.toSimulation()
+ #if useL3Geom:
+ #O.bodies.append(pack.regularHexa(pack.inAlignedBox((-1,-1,-1),(2,2,0)),.5,-.2,dynamic=False))
+ O.bodies.append(utils.wall(position=0,axis=2))
+else:
+ #O.bodies.append(utils.sphere((0,0,1),.2))
+ O.bodies.append(utils.sphere((0,0,0.1035818200000008),.2))
+ O.bodies[0].state.vel,O.bodies[0].state.accel=(0,0,-4.188869999999981),(0,0,-9.8100000000000005)
+ O.bodies.append(utils.sphere((0.30000000000000004,0.19282032302755092,-0.5),.5,dynamic=False))
O.engines=[
ForceResetter(),
InsertionSortCollider([Bo1_Sphere_Aabb(),Bo1_Wall_Aabb()]),
- InteractionLoop([Ig2_Sphere_Sphere_ScGeom(),Ig2_Wall_Sphere_ScGeom()],[Ip2_FrictMat_FrictMat_FrictPhys(frictAngle=0)],[Law2_ScGeom_FrictPhys_CundallStrack()]),
+ InteractionLoop([Ig2_Sphere_Sphere_L3Geom_Inc(approxMask=63),Ig2_Wall_Sphere_L3Geom_Inc(approxMask=63)],[Ip2_FrictMat_FrictMat_FrictPhys(frictAngle=None)],[Law2_L3Geom_FrictPhys_ElPerfPl(noSlip=False,noBreak=False)]) if useL3Geom else InteractionLoop([Ig2_Sphere_Sphere_ScGeom(),Ig2_Wall_Sphere_ScGeom()],[Ip2_FrictMat_FrictMat_FrictPhys(frictAngle=None)],[Law2_ScGeom_FrictPhys_CundallStrack()]),
GravityEngine(gravity=(0,0,-9.81)),
- NewtonIntegrator(damping=0.),
- PyRunner(iterPeriod=10,command='addPlotData()'),
+ NewtonIntegrator(damping=.1,kinSplit=True),
+ PyRunner(iterPeriod=1,command='addPlotData()'),
]
-O.dt=utils.PWaveTimeStep()
+O.dt=.2*utils.PWaveTimeStep()
def addPlotData():
- plot.addData(i=O.iter,total=O.energy.total(),**O.energy)
+ Ek,maxId=utils.kineticEnergy(findMaxId=True)
+ plot.addData(i=O.iter,total=O.energy.total(),maxId=maxId,**O.energy)
# turn on energy tracking
O.trackEnergy=True
@@ -32,8 +43,17 @@
#
# (unfortunately even if we were changing plot.plots periodically,
# plots would not pick up changes in plot.plots during live plotting)
-O.run(400,True)
-plot.plots={'i':['total',]+O.energy.keys()}
+#O.run(427,True)
+#print O.bodies[0].state.pos,O.bodies[0].state.vel,O.bodies[0].state.accel
+O.run(5,True)
+#print list(set(['total',]+O.energy.keys()+['gravWork','kinRot','kinTrans','plastDissip']))+[None,'maxId']
+plot.plots={'i':list(set(['total',]+O.energy.keys()+['gravWork','kinRot','kinTrans','plastDissip','elastPotential']))} #+[None,'maxId']}
+#plot.plots={'i':['total',]+O.energy.keys()+[None,'maxId']}
+
+#O.run()
+
+from yade import timing
+O.timingEnabled=True
+O.run(50000,True)
+timing.stats()
plot.plot(subPlots=True)
-
-O.run()
=== modified file 'scripts/test/law-test.py'
--- scripts/test/law-test.py 2010-10-16 18:31:17 +0000
+++ scripts/test/law-test.py 2010-12-05 17:10:06 +0000
@@ -13,6 +13,7 @@
#
from yade import utils,plot
import random, yade.log
+random.seed()
#yade.log.setLevel('LawTester',yade.log.TRACE)
# sphere's radii
@@ -20,8 +21,8 @@
# place sphere 1 at the origin
pt1=Vector3(0,0,0)
# random orientation of the interaction
-#normal=Vector3(random.random()-.5,random.random()-.5,random.random()-.5)
-normal=Vector3(1,0,0)
+normal=Vector3(random.random()-.5,random.random()-.5,random.random()-.5)
+#normal=Vector3(1,0,0)
O.bodies.append([
utils.sphere(pt1,r1,wire=True,color=(.7,.7,.7)),
utils.sphere(pt1+.999999*(r1+r2)*normal.normalized(),r2,wire=True,color=(0,0,0))
@@ -32,17 +33,18 @@
#PyRunner(iterPeriod=1,command='import time; time.sleep(.005)'),
InsertionSortCollider([Bo1_Sphere_Aabb()]),
InteractionLoop(
- #[Ig2_Sphere_Sphere_ScGeom()], [Ip2_FrictMat_FrictMat_FrictPhys()], [Law2_ScGeom_FrictPhys_CundallStrack()]
- [Ig2_Sphere_Sphere_L3Geom_Inc(approxMask=63)],[Ip2_FrictMat_FrictMat_FrictPhys()],[Law2_L3Geom_FrictPhys_ElPerfPl(noBreak=True,noSlip=False)] # use this line for L3Geom
+ #[Ig2_Sphere_Sphere_ScGeom()], [Ip2_FrictMat_FrictMat_FrictPhys()], [Law2_ScGeom_FrictPhys_CundallStrack()] # ScGeom
+ [Ig2_Sphere_Sphere_L3Geom_Inc(approxMask=63)],[Ip2_FrictMat_FrictMat_FrictPhys()],[Law2_L3Geom_FrictPhys_ElPerfPl(noBreak=True,noSlip=False)] # L3Geom
+ #[Ig2_Sphere_Sphere_L6Geom_Inc(approxMask=63)],[Ip2_FrictMat_FrictMat_FrictPhys()],[Law2_L6Geom_FrictPhys_Linear(charLen=1)] # L6Geom
),
- #LawTester(ids=[0,1],rotPath=[(.2,0,0),(-.2,0,0),(0,0,0),(0,.2,0),(0,0,0),(0,0,.2),(0,0,0),
+ #LawTester(ids=[0,1],path=[(0,0,0)]*7+[(-1e-5,0,0),(-1e-5,.1,.1)],rotPath=[(0,.2,0),(0,0,0),(0,0,.2),(0,0,0),(.2,0,0),(-.2,0,0),(0,0,0)],pathSteps=[10],doneHook='tester.dead=True; O.pause();',label='tester',rotWeight=0),
LawTester(ids=[0,1],path=[
(-1e-5,0,0),(-.1,0,0),(-.1,.1,0),(-1e-5,.1,0), # towards, shear, back to intial normal distance
(-.02,.1,.1),(-.02,-.1,.1),(-.02,-.1,-.1),(-.02,.1,-.1),(-.02,.1,.1), # go in square in the shear plane without changing normal deformation
(-1e-4,0,0) # back to the origin, but keep some overlap to not delete the interaction
],pathSteps=[100],doneHook='tester.dead=True; O.pause()',label='tester',rotWeight=.2,idWeight=.2),
PyRunner(iterPeriod=1,command='addPlotData()'),
- NewtonIntegrator()
+ NewtonIntegrator(),
]
def addPlotData():
@@ -52,9 +54,9 @@
ung=tester.ptGeom[0],us1g=tester.ptGeom[1],us2g=tester.ptGeom[2],
phiX=tester.rotOurs[0],phiY=tester.rotOurs[1],phiZ=tester.rotOurs[2],
phiXg=tester.rotGeom[0],phiYg=tester.rotGeom[1],phiZg=tester.rotGeom[2],
- i=O.iter,Fs=i.phys.shearForce.norm(),Fn=i.phys.normalForce.norm()
+ i=O.iter,Fs=i.phys.shearForce.norm(),Fn=i.phys.normalForce.norm(),Tx=O.forces.t(0)[0],Tyz=sqrt(O.forces.t(0)[1]**2+O.forces.t(0)[2]**2)
)
-plot.plots={'us1':('us2',),'Fn':('Fs',),'i':('un','us1','us2'),' i':('Fs','Fn'),' i':('ung','us1g','us2g'),'i ':('phiX','phiXg','phiY','phiYg','phiZ','phiZg')} #'ung','us1g','us2g'
+plot.plots={'us1':('us2',),'Fn':('Fs',),'i':('un','us1','us2'),' i':('Fs','Fn','Tx','Tyz'),' i':('ung','us1g','us2g'),'i ':('phiX','phiXg','phiY','phiYg','phiZ','phiZg')} #'ung','us1g','us2g'
plot.plot(subPlots=True)
try:
@@ -62,6 +64,7 @@
qt.Controller(); v=qt.View()
rr=qt.Renderer()
rr.extraDrawers=[GlExtra_LawTester()]
+ rr.intrGeom=True
except ImportError: pass
O.dt=1
=== renamed file 'scripts/test/periodic-triax-velgrad.py' => 'scripts/test/periodic-geom-compare.py'
--- scripts/test/periodic-triax-velgrad.py 2010-10-16 18:31:17 +0000
+++ scripts/test/periodic-geom-compare.py 2010-12-05 17:10:06 +0000
@@ -2,53 +2,55 @@
# 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
"Test and demonstrate use of PeriTriaxController."
from yade import *
-from yade import pack,log,qt
+from yade import pack,log
#log.setLevel('PeriTriaxController',log.DEBUG)
#log.setLevel('Shop',log.TRACE)
O.periodic=True
O.cell.refSize=Vector3(.1,.1,.1)
-O.cell.trsf=Matrix3().IDENTITY;
+O.cell.trsf=Matrix3().Identity;
sp=pack.SpherePack()
radius=5e-3
-num=sp.makeCloud(Vector3().ZERO,O.cell.refSize,radius,.6,-1,periodic=True) # min,max,radius,rRelFuzz,spheresInCell,periodic
-O.bodies.append([utils.sphere(s[0],s[1]) for s in sp])
+num=sp.makeCloud(Vector3().Zero,O.cell.refSize,radius,.6,-1,periodic=True) # min,max,radius,rRelFuzz,spheresInCell,periodic
+sp.toSimulation()
+
+# specify which family of geometry functors to use
+utils.readParamsFromTable(noTableOk=True,geom='sc')
+from yade.params.table import geom
+
+if geom=='sc':
+ loop=InteractionLoop([Ig2_Sphere_Sphere_ScGeom()],[Ip2_FrictMat_FrictMat_FrictPhys()],[Law2_ScGeom_FrictPhys_CundallStrack()])
+elif geom=='d3d':
+ loop=InteractionLoop([Ig2_Sphere_Sphere_Dem3DofGeom()],[Ip2_FrictMat_FrictMat_FrictPhys()],[Law2_Dem3DofGeom_FrictPhys_CundallStrack()])
+elif geom=='l3':
+ loop=InteractionLoop([Ig2_Sphere_Sphere_L3Geom_Inc()],[Ip2_FrictMat_FrictMat_FrictPhys()],[Law2_L3Geom_FrictPhys_ElPerfPl()])
+elif geom=='l3a':
+ loop=InteractionLoop([Ig2_Sphere_Sphere_L3Geom_Inc(approxMask=63)],[Ip2_FrictMat_FrictMat_FrictPhys()],[Law2_L3Geom_FrictPhys_ElPerfPl()])
+else: raise ValueError('geom must be one of sc, d3d, l3, l3a (not %s)'%geom)
O.engines=[
ForceResetter(),
InsertionSortCollider([Bo1_Sphere_Aabb()],nBins=5,sweepLength=.05*radius),
- InteractionLoop(
- [Ig2_Sphere_Sphere_Dem3DofGeom()],
- [Ip2_FrictMat_FrictMat_FrictPhys()],
- [Law2_Dem3DofGeom_FrictPhys_CundallStrack()]
- ),
- #PeriTriaxController(goal=[-1e3,-1e3,-1e3],stressMask=7,globUpdate=5,maxStrainRate=[5.,5.,5.],label='triax'),
- NewtonIntegrator(damping=.6, homotheticCellResize=0),
- PyRunner(command='utils.flipCell()',iterPeriod=1000),
+ loop,
+ NewtonIntegrator(damping=.6),
]
O.dt=0.5*utils.PWaveTimeStep()
-O.run(1)
-qt.View()
-O.cell.velGrad=Matrix3(0,10,0,0,0,0,0,0,0)
-#O.cell.velGrad=Matrix3(0,5,2,-5,0,0,-2,0,0)
+try:
+ from yade import qt
+ qt.View()
+except: pass
+
+O.cell.velGrad=Matrix3(-.1,.03,0, 0,-.1,0, 0,0,-.1)
O.saveTmp()
-O.run();
-rrr=qt.Renderer(); rrr['intrAllWire'],rrr['Body_interacting_geom']=True,False
+#O.run(10000,True);
+#rrr=qt.Renderer(); rrr.intrAllWire,rrr.intrGeom=True,False
-phase=0
-def triaxDone():
- global phase
- if phase==0:
- print 'Here we are: stress',triax['stress'],'strain',triax['strain'],'stiffness',triax['stiff']
- print 'Now εz will go from 0 to .2 while Ïx and Ïy will be kept the same.'
- triax['goal']=[-1e5,-1e5,.2]
- O.cell.velGrad=Matrix3(0,0,0,5,0,0, 0,0,0)
- phase+=1
- elif phase==1:
- print 'Here we are: stress',triax['stress'],'strain',triax['strain'],'stiffness',triax['stiff']
- print 'Done, pausing now.'
- O.pause()
-
+if utils.runningInBatch():
+ O.timingEnabled=True
+ O.run(300000,True)
+ O.timingEnabled
+ from yade import timing
+ timing.stats()