yade-dev team mailing list archive
-
yade-dev team
-
Mailing list archive
-
Message #09874
[Branch ~yade-pkg/yade/git-trunk] Rev 3702: remove Dem3Dof form Yade (also eudoxos module, mostly based on Dem3Dof)
------------------------------------------------------------
revno: 3702
committer: Bruno Chareyre <bruno.chareyre@xxxxxxxxxxx>
timestamp: Thu 2013-08-29 12:30:31 +0200
message:
remove Dem3Dof form Yade (also eudoxos module, mostly based on Dem3Dof)
removed:
examples/test/CundallStrackTest.py
examples/test/Dem3DofGeom.py
pkg/dem/Dem3DofGeom_FacetSphere.cpp
pkg/dem/Dem3DofGeom_FacetSphere.hpp
pkg/dem/Dem3DofGeom_SphereSphere.cpp
pkg/dem/Dem3DofGeom_SphereSphere.hpp
pkg/dem/Dem3DofGeom_WallSphere.cpp
pkg/dem/Dem3DofGeom_WallSphere.hpp
py/_eudoxos.cpp
py/eudoxos.py
modified:
pkg/dem/DemXDofGeom.cpp
pkg/dem/DemXDofGeom.hpp
pkg/dem/DomainLimiter.cpp
pkg/dem/Shop.cpp
pkg/dem/Shop.hpp
py/_extraDocs.py
py/_utils.cpp
py/tests/__init__.py
--
lp:yade
https://code.launchpad.net/~yade-pkg/yade/git-trunk
Your team Yade developers is subscribed to branch lp:yade.
To unsubscribe from this branch go to https://code.launchpad.net/~yade-pkg/yade/git-trunk/+edit-subscription
=== removed file 'examples/test/CundallStrackTest.py'
--- examples/test/CundallStrackTest.py 2013-03-28 11:13:12 +0000
+++ examples/test/CundallStrackTest.py 1970-01-01 00:00:00 +0000
@@ -1,21 +0,0 @@
-# -*- coding: utf-8 -*-
-
-
-O.engines=[
- ForceResetter(),
- InsertionSortCollider([Bo1_Sphere_Aabb(),]),
- IGeomDispatcher([Ig2_Sphere_Sphere_Dem3DofGeom()]),
- IPhysDispatcher([Ip2_2xFrictMat_CSPhys()]),
- LawDispatcher([Law2_Dem3Dof_CSPhys_CundallStrack()]),
- NewtonIntegrator(damping = 0.01,gravity=[0,0,-9.81])
-]
-
-
-
-O.bodies.append(sphere([0,0,6],1,fixed=False, color=[0,1,0]))
-O.bodies.append(sphere([0,0,0],1,fixed=True, color=[0,0,1]))
-O.dt=.2*PWaveTimeStep()
-
-from yade import qt
-qt.Controller()
-qt.View()
=== removed file 'examples/test/Dem3DofGeom.py'
--- examples/test/Dem3DofGeom.py 2013-03-28 16:15:54 +0000
+++ examples/test/Dem3DofGeom.py 1970-01-01 00:00:00 +0000
@@ -1,40 +0,0 @@
-"Script showing shear interaction between facet/wall and sphere."
-O.bodies.append([
- #sphere([0,0,0],1,dynamic=False,color=(0,1,0),wire=True),
- facet(([2,2,1],[-2,0,1],[2,-2,1]),fixed=True,color=(0,1,0),wire=False),
- #wall([0,0,1],axis=2,color=(0,1,0)),
- sphere([-1,0,2],1,fixed=False,color=(1,0,0),wire=True),
-])
-O.engines=[
- ForceResetter(),
- InsertionSortCollider([
- Bo1_Sphere_Aabb(),Bo1_Facet_Aabb(),Bo1_Wall_Aabb()
- ]),
- IGeomDispatcher([
- Ig2_Sphere_Sphere_Dem3DofGeom(),
- Ig2_Facet_Sphere_Dem3DofGeom(),
- Ig2_Wall_Sphere_Dem3DofGeom()
- ]),
- RotationEngine(rotationAxis=[0,1,0],angularVelocity=10,ids=[1]),
- TranslationEngine(translationAxis=[1,0,0],velocity=10,ids=[1]),
- NewtonIntegrator()#gravity=(0,0,-10))
-]
-O.miscParams=[
- Gl1_Dem3DofGeom_SphereSphere(normal=True,rolledPoints=True,unrolledPoints=True,shear=True,shearLabel=True),
- Gl1_Dem3DofGeom_FacetSphere(normal=False,rolledPoints=True,unrolledPoints=True,shear=True,shearLabel=True),
- Gl1_Dem3DofGeom_WallSphere(normal=False,rolledPoints=True,unrolledPoints=True,shear=True,shearLabel=True),
- Gl1_Sphere(wire=True)
-]
-
-try:
- from yade import qt
- renderer=qt.Renderer()
- renderer.wire=True
- renderer.intrGeom=True
- qt.Controller()
- qt.View()
-except ImportError: pass
-
-O.dt=1e-6
-O.saveTmp('init')
-O.run(1)
=== removed file 'pkg/dem/Dem3DofGeom_FacetSphere.cpp'
--- pkg/dem/Dem3DofGeom_FacetSphere.cpp 2011-02-14 08:05:09 +0000
+++ pkg/dem/Dem3DofGeom_FacetSphere.cpp 1970-01-01 00:00:00 +0000
@@ -1,221 +0,0 @@
-// © Václav Šmilauer <eudoxos@xxxxxxxx>
-#include "Dem3DofGeom_FacetSphere.hpp"
-#include<yade/pkg/common/Sphere.hpp>
-#include<yade/pkg/common/Facet.hpp>
-YADE_PLUGIN((Dem3DofGeom_FacetSphere)
- #ifdef YADE_OPENGL
- (Gl1_Dem3DofGeom_FacetSphere)
- #endif
- (Ig2_Facet_Sphere_Dem3DofGeom));
-
-CREATE_LOGGER(Dem3DofGeom_FacetSphere);
-Dem3DofGeom_FacetSphere::~Dem3DofGeom_FacetSphere(){}
-
-void Dem3DofGeom_FacetSphere::setTgPlanePts(const Vector3r& p1new, const Vector3r& p2new){
- TRVAR3(cp1pt,cp2rel,contPtInTgPlane2()-contPtInTgPlane1());
- cp1pt=se31.orientation.conjugate()*(turnPlanePt(p1new,normal,se31.orientation*localFacetNormal)+contactPoint-se31.position);
- cp2rel=se32.orientation.conjugate()*Dem3DofGeom_SphereSphere::rollPlanePtToSphere(p2new,effR2,-normal);
- TRVAR3(cp1pt,cp2rel,contPtInTgPlane2()-contPtInTgPlane1());
-}
-
-void Dem3DofGeom_FacetSphere::relocateContactPoints(const Vector3r& p1, const Vector3r& p2){
- //TRVAR2(p2.norm(),effR2);
- if(p2.squaredNorm()>pow(effR2,2)){
- setTgPlanePts(Vector3r::Zero(),p2-p1);
- }
-}
-
-Real Dem3DofGeom_FacetSphere::slipToDisplacementTMax(Real displacementTMax){
- //FIXME: not yet tested
- // negative or zero: reset shear
- if(displacementTMax<=0.){ setTgPlanePts(Vector3r(0,0,0),Vector3r(0,0,0)); return displacementTMax;}
- // otherwise
- Vector3r p1=contPtInTgPlane1(), p2=contPtInTgPlane2();
- Real currDistSq=(p2-p1).squaredNorm();
- if(currDistSq<pow(displacementTMax,2)) return 0; // close enough, no slip needed
- //Vector3r diff=.5*(sqrt(currDistSq)/displacementTMax-1)*(p2-p1); setTgPlanePts(p1+diff,p2-diff);
- Real scale=displacementTMax/sqrt(currDistSq); setTgPlanePts(scale*p1,scale*p2);
- return (displacementTMax/scale)*(1-scale);
-}
-
-CREATE_LOGGER(Ig2_Facet_Sphere_Dem3DofGeom);
-bool Ig2_Facet_Sphere_Dem3DofGeom::go(const shared_ptr<Shape>& cm1, const shared_ptr<Shape>& cm2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& c){
- Facet* facet=static_cast<Facet*>(cm1.get());
- Real sphereRadius=static_cast<Sphere*>(cm2.get())->radius;
-
- // IGeomFunctor::go(cm1,cm2,state1,state2,shift2,force,c);
-
- #if 1
- /* new code written from scratch, to make sure the algorithm is correct; it is about the same speed
- as sega's algo below, but seems more readable to me.
- The FACET_TOPO thing is still missing here but can be copied literally once it is tested */
- // begin facet-local coordinates
- Vector3r cogLine=state1.ori.conjugate()*(state2.pos+shift2-state1.pos); // connect centers of gravity
- //TRVAR4(state1.pos,state1.ori,state2.pos,cogLine);
- Vector3r normal=facet->normal;
- Real planeDist=normal.dot(cogLine);
- if(planeDist<0){normal*=-1; planeDist*=-1; }
- if(planeDist>sphereRadius && !c->isReal() && !force) { /* LOG_TRACE("Sphere too far ("<<planeDist<<") from plane"); */ return false; }
- Vector3r planarPt=cogLine-planeDist*normal; // project sphere center to the facet plane
- Real normDotPt[3];
- Vector3r contactPt(Vector3r::Zero());
- for(int i=0; i<3; i++) normDotPt[i]=facet->ne[i].dot(planarPt-facet->vertices[i]);
- short w=(normDotPt[0]>0?1:0)+(normDotPt[1]>0?2:0)+(normDotPt[2]>0?4:0);
- //TRVAR4(planarPt,normDotPt[0],normDotPt[1],normDotPt[2]);
- //TRVAR2(normal,cogLine);
- //TRVAR3(facet->vertices[0],facet->vertices[1],facet->vertices[2]);
- switch(w){
- case 0: contactPt=planarPt; break; // inside triangle
- case 1: contactPt=getClosestSegmentPt(planarPt,facet->vertices[0],facet->vertices[1]); break; // +-- (n1)
- case 2: contactPt=getClosestSegmentPt(planarPt,facet->vertices[1],facet->vertices[2]); break; // -+- (n2)
- case 4: contactPt=getClosestSegmentPt(planarPt,facet->vertices[2],facet->vertices[0]); break; // --+ (n3)
- case 3: contactPt=facet->vertices[1]; break; // ++- (v1)
- case 5: contactPt=facet->vertices[0]; break; // +-+ (v0)
- case 6: contactPt=facet->vertices[2]; break; // -++ (v2)
- case 7: throw logic_error("Impossible triangle intersection?"); // +++ (impossible)
- default: throw logic_error("Nonsense intersection value!");
- }
- normal=cogLine-contactPt; // called normal, but it is no longer the facet's normal (for compat)
- //TRVAR3(normal,contactPt,sphereRadius);
- if(!c->isReal() && normal.squaredNorm()>sphereRadius*sphereRadius && !force) { /* LOG_TRACE("Sphere too far from closest point"); */ return false; } // fast test before sqrt
- Real norm=normal.norm(); normal/=norm; // normal is unit vector now
- Real penetrationDepth=sphereRadius-norm;
- #else
- /* This code was mostly copied from InteractingFacet2InteractinSphere4SpheresContactGeometry */
- // begin facet-local coordinates
- Vector3r contactLine=state1.ori.Conjugate()*(state2.pos+shift2-state1.pos);
- Vector3r normal=facet->normal;
- Real L=normal.Dot(contactLine); // height/depth of sphere's center from facet's plane
- if(L<0){normal*=-1; L*=-1;}
- if(L>sphereRadius && !c->isReal()) return false; // sphere too far away from the plane
-
- Vector3r contactPt=contactLine-L*normal; // projection of sphere's center to facet's plane (preliminary contact point)
- const Vector3r* edgeNormals=facet->ne; // array[3] of edge normals (in facet plane)
- int edgeMax=0; Real distMax=edgeNormals[0].Dot(contactPt);
- for(int i=1; i<3; i++){
- Real dist=edgeNormals[i].Dot(contactPt);
- if(distMax<dist){edgeMax=i; distMax=dist;}
- }
- //TRVAR2(distMax,edgeMax);
- // OK, what's the logic here? Copying from IF2IS4SCG…
- Real sphereRReduced=shrinkFactor*sphereRadius;
- Real inCircleR=facet->icr-sphereRReduced;
- Real penetrationDepth;
- if(inCircleR<0){inCircleR=facet->icr; sphereRReduced=0;}
- if(distMax<inCircleR){// contact with facet's surface
- penetrationDepth=sphereRadius-L;
- normal.normalize();
- } else { // contact with the edge
- contactPt+=edgeNormals[edgeMax]*(inCircleR-distMax);
- bool noVertexContact=false;
- //TRVAR3(edgeNormals[edgeMax],inCircleR,distMax);
- // contact with vertex no. edgeMax
- // FIXME: this is the original version, but why (edgeMax-1)%3? IN that case, edgeNormal to edgeMax would never be tried
- // if (contactPt.Dot(edgeNormals[ (edgeMax-1)%3])>inCircleR) contactPt=facet->vu[edgeMax]*(facet->vl[edgeMax]-sphereRReduced);
- if (contactPt.Dot(edgeNormals[ edgeMax ])>inCircleR) contactPt=facet->vu[edgeMax]*(facet->vl[edgeMax]-sphereRReduced);
- // contact with vertex no. edgeMax+1
- else if(contactPt.Dot(edgeNormals[edgeMax=(edgeMax+1)%3])>inCircleR) contactPt=facet->vu[edgeMax]*(facet->vl[edgeMax]-sphereRReduced);
- // contact with edge no. edgeMax
- else noVertexContact=true;
- normal=contactLine-contactPt;
- #ifdef FACET_TOPO
- if(noVertexContact && facet->edgeAdjIds[edgeMax]!=Body::ID_NONE){
- // find angle between our normal and the facet's normal (still local coords)
- Quaternionr q; q.Align(facet->normal,normal); AngleAxisr aa(q);
- assert(aa.angle()>=0 && aa.angle()<=Mathr::PI);
- if(edgeNormals[edgeMax].Dot(aa.axis())<0) aa.angle()*=-1.;
- bool negFace=normal.Dot(facet->normal)<0; // contact in on the negative facet's face
- Real halfAngle=(negFace?-1.:1.)*facet->edgeAdjHalfAngle[edgeMax];
- if(halfAngle<0 && aa.angle()>halfAngle) return false; // on concave boundary, and if in the other facet's sector, no contact
- // otherwise the contact will be created
- }
- #endif
- //TRVAR4(contactLine,contactPt,normal,normal.norm());
- //TRVAR3(se31.orientation*contactLine,se31.position+se31.orientation*contactPt,se31.orientation*normal);
- Real norm=normal.norm(); normal/=norm;
- penetrationDepth=sphereRadius-norm;
- //TRVAR1(penetrationDepth);
- }
- // end facet-local coordinates
- #endif
-
- if(penetrationDepth<0 && !c->isReal()) return false;
-
-
- shared_ptr<Dem3DofGeom_FacetSphere> fs;
- Vector3r normalGlob=state1.ori*normal;
- bool isNew=false;
- if(c->geom) fs=YADE_PTR_CAST<Dem3DofGeom_FacetSphere>(c->geom);
- else {
- // LOG_TRACE("Creating new Dem3DofGeom_FacetSphere");
- fs=shared_ptr<Dem3DofGeom_FacetSphere>(new Dem3DofGeom_FacetSphere());
- c->geom=fs;
- isNew=true;
- fs->effR2=sphereRadius-penetrationDepth;
- fs->refR1=-1; fs->refR2=sphereRadius;
- // postponed till below, to avoid numeric issues
- // see https://lists.launchpad.net/yade-dev/msg02794.html
- // since displacementN() is computed from fs->contactPoint,
- // it was returning something like +1e-16 at the very first step
- // when it was created ⇒ the constitutive law was erasing the
- // contact as soon as it was created.
- // fs->refLength=…
- fs->cp1pt=contactPt; // facet-local intial contact point
- fs->localFacetNormal=facet->normal;
- fs->cp2rel.setFromTwoVectors(Vector3r::UnitX(),state2.ori.conjugate()*(-normalGlob)); // initial sphere-local center-contactPt orientation WRT +x
- fs->cp2rel.normalize();
- }
- fs->se31=state1.se3; fs->se32=state2.se3; fs->se32.position+=shift2;
- fs->normal=normalGlob;
- fs->contactPoint=state2.pos+shift2+(-normalGlob)*(sphereRadius-penetrationDepth);
- // this refLength computation mimics what displacementN() does inside
- // displcementN will therefore return exactly zero at the step the contact
- // was created, which is what we want
- if(isNew) fs->refLength=(state2.pos+shift2-fs->contactPoint).norm();
- return true;
-}
-
-#ifdef YADE_OPENGL
-
- #include<yade/lib/opengl/OpenGLWrapper.hpp>
- #include<yade/lib/opengl/GLUtils.hpp>
-
- bool Gl1_Dem3DofGeom_FacetSphere::normal=false;
- bool Gl1_Dem3DofGeom_FacetSphere::rolledPoints=false;
- bool Gl1_Dem3DofGeom_FacetSphere::unrolledPoints=false;
- bool Gl1_Dem3DofGeom_FacetSphere::shear=false;
- bool Gl1_Dem3DofGeom_FacetSphere::shearLabel=false;
-
- void Gl1_Dem3DofGeom_FacetSphere::go(const shared_ptr<IGeom>& ig, const shared_ptr<Interaction>& ip, const shared_ptr<Body>& b1, const shared_ptr<Body>& b2, bool wireFrame){
- Dem3DofGeom_FacetSphere* fs = static_cast<Dem3DofGeom_FacetSphere*>(ig.get());
- const Se3r& se31=b1->state->se3,se32=b2->state->se3;
- const Vector3r& pos1=se31.position; const Vector3r& pos2=se32.position;
- const Quaternionr& ori1=se31.orientation; const Quaternionr& ori2=se32.orientation;
- const Vector3r& contPt=fs->contactPoint;
-
- if(normal){
- GLUtils::GLDrawArrow(contPt,contPt+fs->refLength*fs->normal); // normal of the contact
- }
- // sphere center to point on the sphere
- if(rolledPoints){
- //cerr<<pos1<<" "<<pos1+ori1*fs->cp1pt<<" "<<contPt<<endl;
- GLUtils::GLDrawLine(pos1+ori1*fs->cp1pt,contPt,Vector3r(0,.5,1));
- GLUtils::GLDrawLine(pos2,pos2+(ori2*fs->cp2rel*Vector3r::UnitX()*fs->effR2),Vector3r(0,1,.5));
- }
- // contact point to projected points
- if(unrolledPoints||shear){
- Vector3r ptTg1=fs->contPtInTgPlane1(), ptTg2=fs->contPtInTgPlane2();
- if(unrolledPoints){
- //TRVAR3(ptTg1,ptTg2,ss->normal)
- GLUtils::GLDrawLine(contPt,contPt+ptTg1,Vector3r(0,.5,1));
- GLUtils::GLDrawLine(contPt,contPt+ptTg2,Vector3r(0,1,.5)); GLUtils::GLDrawLine(pos2,contPt+ptTg2,Vector3r(0,1,.5));
- }
- if(shear){
- GLUtils::GLDrawLine(contPt+ptTg1,contPt+ptTg2,Vector3r(1,1,1));
- if(shearLabel) GLUtils::GLDrawNum(fs->displacementT().norm(),contPt,Vector3r(1,1,1));
- }
- }
- }
-
-#endif
-
=== removed file 'pkg/dem/Dem3DofGeom_FacetSphere.hpp'
--- pkg/dem/Dem3DofGeom_FacetSphere.hpp 2013-08-23 15:21:20 +0000
+++ pkg/dem/Dem3DofGeom_FacetSphere.hpp 1970-01-01 00:00:00 +0000
@@ -1,80 +0,0 @@
-#pragma once
-#include<yade/pkg/dem/DemXDofGeom.hpp>
-// for static roll/unroll functions in Dem3DofGeom_SphereSphere
-#include<yade/pkg/dem/Dem3DofGeom_SphereSphere.hpp>
-#include<yade/pkg/common/Sphere.hpp>
-#include<yade/pkg/common/Facet.hpp>
-
-class Dem3DofGeom_FacetSphere: public Dem3DofGeom{
- //! turn planePt in plane with normal0 around line passing through origin to plane with normal1
- static Vector3r turnPlanePt(const Vector3r& planePt, const Vector3r& normal0, const Vector3r& normal1){ Quaternionr q; q.setFromTwoVectors(normal0,normal1); return q*planePt; }
-
- Vector3r contPtInTgPlane1() const { return turnPlanePt(se31.position+se31.orientation*cp1pt-contactPoint,se31.orientation*localFacetNormal,normal); }
- Vector3r contPtInTgPlane2() const { return Dem3DofGeom_SphereSphere::unrollSpherePtToPlane(se32.orientation*cp2rel,effR2,-normal);}
-
- public:
- virtual ~Dem3DofGeom_FacetSphere();
- /******* API ********/
- virtual Real displacementN(){ return (se32.position-contactPoint).norm()-refLength;}
- virtual Vector3r displacementT(){ relocateContactPoints(); return contPtInTgPlane2()-contPtInTgPlane1(); }
- virtual Real slipToDisplacementTMax(Real displacementTMax);
- /***** end API ******/
-
- void setTgPlanePts(const Vector3r&, const Vector3r&);
- void relocateContactPoints(){ relocateContactPoints(contPtInTgPlane1(),contPtInTgPlane2()); }
- void relocateContactPoints(const Vector3r& p1, const Vector3r& p2);
- YADE_CLASS_BASE_DOC_ATTRS_CTOR(Dem3DofGeom_FacetSphere,Dem3DofGeom,"Class representing facet+sphere in contact which computes 3 degrees of freedom (normal and shear deformation).",
- ((Vector3r,cp1pt,,,"Reference contact point on the facet in facet-local coords."))
- ((Quaternionr,cp2rel,,,"Orientation between +x and the reference contact point (on the sphere) in sphere-local coords"))
- ((Vector3r,localFacetNormal,,,"Unit normal of the facet plane in facet-local coordinates"))
- ((Real,effR2,,,"Effective radius of sphere")),
- /*ctor*/ createIndex();
- );
- REGISTER_CLASS_INDEX(Dem3DofGeom_FacetSphere,Dem3DofGeom);
- DECLARE_LOGGER;
- friend class Gl1_Dem3DofGeom_FacetSphere;
- friend class Ig2_Facet_Sphere_Dem3DofGeom;
-};
-REGISTER_SERIALIZABLE(Dem3DofGeom_FacetSphere);
-
-#ifdef YADE_OPENGL
- #include<yade/pkg/common/GLDrawFunctors.hpp>
- class Gl1_Dem3DofGeom_FacetSphere:public GlIGeomFunctor{
- public:
- virtual void go(const shared_ptr<IGeom>&,const shared_ptr<Interaction>&,const shared_ptr<Body>&,const shared_ptr<Body>&,bool wireFrame);
- RENDERS(Dem3DofGeom_FacetSphere);
- YADE_CLASS_BASE_DOC_STATICATTRS(Gl1_Dem3DofGeom_FacetSphere,GlIGeomFunctor,"Render interaction of facet and sphere (represented by Dem3DofGeom_FacetSphere)",
- ((bool,normal,false,,"Render interaction normal"))
- ((bool,rolledPoints,false,,"Render points rolled on the sphere & facet (original contact point)"))
- ((bool,unrolledPoints,false,,"Render original contact points unrolled to the contact plane"))
- ((bool,shear,false,,"Render shear line in the contact plane"))
- ((bool,shearLabel,false,,"Render shear magnitude as number"))
- );
- };
- REGISTER_SERIALIZABLE(Gl1_Dem3DofGeom_FacetSphere);
-#endif
-
-#include<yade/pkg/common/Dispatching.hpp>
-class Ig2_Facet_Sphere_Dem3DofGeom:public IGeomFunctor{
- Vector3r getClosestSegmentPt(const Vector3r& P, const Vector3r& A, const Vector3r& B){
- // algo: http://local.wasp.uwa.edu.au/~pbourke/geometry/pointline/
- Vector3r BA=B-A;
- Real u=(P.dot(BA)-A.dot(BA))/(BA.squaredNorm());
- return A+min((Real)1.,max((Real)0.,u))*BA;
- }
- public:
- virtual bool go(const shared_ptr<Shape>& cm1, const shared_ptr<Shape>& cm2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& c);
- virtual bool goReverse( const shared_ptr<Shape>& cm1, const shared_ptr<Shape>& cm2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& c){
- c->swapOrder(); return go(cm2,cm1,state2,state1,-shift2,force,c);
- LOG_ERROR("!! goReverse maybe doesn't work in Ig2_Facet_Sphere_Dem3DofGeom. IGeomDispatcher should swap interaction members first and call go(...) afterwards.");
- }
-
- FUNCTOR2D(Facet,Sphere);
- DEFINE_FUNCTOR_ORDER_2D(Facet,Sphere);
- YADE_CLASS_BASE_DOC_ATTRS(Ig2_Facet_Sphere_Dem3DofGeom,IGeomFunctor,"Compute geometry of facet-sphere contact with normal and shear DOFs. As in all other Dem3DofGeom-related classes, total formulation of both shear and normal deformations is used. See :yref:`Dem3DofGeom_FacetSphere` for more information.",
- // unused: ((Real,shrinkFactor,0.,,"Reduce the facet's size, probably to avoid singularities at common facets' edges (?)"))
- );
- DECLARE_LOGGER;
-};
-REGISTER_SERIALIZABLE(Ig2_Facet_Sphere_Dem3DofGeom);
-
=== removed file 'pkg/dem/Dem3DofGeom_SphereSphere.cpp'
--- pkg/dem/Dem3DofGeom_SphereSphere.cpp 2010-12-13 12:11:43 +0000
+++ pkg/dem/Dem3DofGeom_SphereSphere.cpp 1970-01-01 00:00:00 +0000
@@ -1,196 +0,0 @@
-#include "Dem3DofGeom_SphereSphere.hpp"
-
-#include<yade/pkg/common/Sphere.hpp>
-#include<yade/core/Omega.hpp>
-YADE_PLUGIN((Dem3DofGeom_SphereSphere)
- #ifdef YADE_OPENGL
- (Gl1_Dem3DofGeom_SphereSphere)
- #endif
- (Ig2_Sphere_Sphere_Dem3DofGeom));
-
-
-Dem3DofGeom_SphereSphere::~Dem3DofGeom_SphereSphere(){}
-
-/*! Project point from sphere surface to tangent plane,
- * such that the angle of shortest arc from (1,0,0) pt on the sphere to the point itself is the same
- * as the angle of segment of the same length on the tangent plane.
- *
- * This function is (or should be) inverse of ScGeom::rollPlanePtToSphere.
- *
- * @param fromXtoPtOri gives orientation of the vector from sphere center to the sphere point from the global +x axis.
- * @param radius the distance from sphere center to the contact plane
- * @param planeNormal unit vector pointing away from the sphere center, determining plane orientation on which the projected point lies.
- * @returns The projected point coordinates (with origin at the contact point).
- */
-Vector3r Dem3DofGeom_SphereSphere::unrollSpherePtToPlane(const Quaternionr& fromXtoPtOri, const Real& radius, const Vector3r& planeNormal){
- Quaternionr normal2pt; normal2pt.setFromTwoVectors(planeNormal,fromXtoPtOri*Vector3r::UnitX());
- AngleAxisr aa(normal2pt);
- return (aa.angle()*radius) /* length */ *(aa.axis().cross(planeNormal)) /* direction: both are unit vectors */;
-}
-
-/*! Project point from tangent plane to the sphere.
- *
- * This function is (or should be) inverse of ScGeom::unrollSpherePtToPlane.
- *
- * @param planePt point on the tangent plane, with origin at the contact point (i.e. at sphere center + normal*radius)
- * @param radius sphere radius
- * @param planeNormal _unit_ vector pointing away from sphere center
- * @returns orientation that transforms +x axis to the vector between sphere center and point on the sphere that corresponds to planePt.
- *
- * @note It is not checked whether planePt relly lies on the tangent plane. If not, result will be incorrect.
- */
-Quaternionr Dem3DofGeom_SphereSphere::rollPlanePtToSphere(const Vector3r& planePt, const Real& radius, const Vector3r& planeNormal){
- if (planePt!=Vector3r::Zero()) {
- Quaternionr normal2pt;
- Vector3r axis=planeNormal.cross(planePt); axis.normalize();
- Real angle=planePt.norm()/radius;
- normal2pt=Quaternionr(AngleAxisr(angle,axis));
- Quaternionr ret; return ret.setFromTwoVectors(Vector3r::UnitX(),normal2pt*planeNormal);
- } else {
- Quaternionr ret; return ret.setFromTwoVectors(Vector3r::UnitX(),planeNormal);
- }
-}
-
-
-
-/* Set contact points on both spheres such that their projection is the one given
- * (should be on the plane passing through origin and oriented with normal; not checked!)
- */
-void Dem3DofGeom_SphereSphere::setTgPlanePts(Vector3r p1new, Vector3r p2new){
- cp1rel=ori1.conjugate()*rollPlanePtToSphere(p1new,effR1,normal);
- cp2rel=ori2.conjugate()*rollPlanePtToSphere(p2new,effR2,-normal);
-}
-
-
-
-/*! Perform slip of the projected contact points so that their distance becomes equal (or remains smaller) than the given one.
- * The slipped distance is returned.
- */
-Real Dem3DofGeom_SphereSphere::slipToDisplacementTMax(Real displacementTMax){
- // very close, reset shear
- if(displacementTMax<=0.){ setTgPlanePts(Vector3r(0,0,0),Vector3r(0,0,0)); return displacementTMax;}
- // otherwise
- Vector3r p1=contPtInTgPlane1(), p2=contPtInTgPlane2();
- Real currDistSq=(p2-p1).squaredNorm();
- if(currDistSq<pow(displacementTMax,2)) return 0; // close enough, no slip needed
- Vector3r diff=.5*(displacementTMax/sqrt(currDistSq)-1)*(p2-p1);
- setTgPlanePts(p1-diff,p2+diff);
- return 2*diff.norm();
-}
-
-
-/* Move contact point on both spheres in such way that their relative position (displacementT) is the same;
- * this should be done regularly to ensure that the angle doesn't go over π, since then quaternion would
- * flip axis and the point would project on other side of the tangent plane piece. */
-void Dem3DofGeom_SphereSphere::relocateContactPoints(){
- relocateContactPoints(contPtInTgPlane1(),contPtInTgPlane2());
-}
-
-/*! Like Dem3DofGeom_SphereSphere::relocateContactPoints(), but use already computed tangent plane points. */
-void Dem3DofGeom_SphereSphere::relocateContactPoints(const Vector3r& p1, const Vector3r& p2){
- Vector3r midPt=(effR1/(effR1+effR2))*(p1+p2); // proportionally to radii, so that angle would be the same
- if((p1.squaredNorm()>pow(effR1,2) || p2.squaredNorm()>pow(effR2,2)) && midPt.squaredNorm()>pow(min(effR1,effR2),2)){
- //cerr<<"RELOCATION with displacementT="<<displacementT(); // should be the same before and after relocation
- setTgPlanePts(p1-midPt,p2-midPt);
- //cerr<<" → "<<displacementT()<<endl;
- }
-}
-
-
-
-#ifdef YADE_OPENGL
- #include<yade/lib/opengl/OpenGLWrapper.hpp>
- #include<yade/lib/opengl/GLUtils.hpp>
- bool Gl1_Dem3DofGeom_SphereSphere::normal=false;
- bool Gl1_Dem3DofGeom_SphereSphere::rolledPoints=false;
- bool Gl1_Dem3DofGeom_SphereSphere::unrolledPoints=false;
- bool Gl1_Dem3DofGeom_SphereSphere::shear=false;
- bool Gl1_Dem3DofGeom_SphereSphere::shearLabel=false;
-
- void Gl1_Dem3DofGeom_SphereSphere::go(const shared_ptr<IGeom>& ig, const shared_ptr<Interaction>& ip, const shared_ptr<Body>& b1, const shared_ptr<Body>& b2, bool wireFrame){
- Dem3DofGeom_SphereSphere* ss = static_cast<Dem3DofGeom_SphereSphere*>(ig.get());
- //const Se3r& se31=b1->physicalParameters->dispSe3,se32=b2->physicalParameters->dispSe3;
- const Se3r& se31=b1->state->se3,se32=b2->state->se3;
- const Vector3r& pos1=se31.position,pos2=se32.position;
- Vector3r& contPt=ss->contactPoint;
-
- if(normal){
- GLUtils::GLDrawArrow(contPt,contPt+ss->normal*.5*ss->refLength); // normal of the contact
- }
- #if 0
- // never used, since bending/torsion not used
- //Vector3r contPt=se31.position+(ss->effR1/ss->refLength)*(se32.position-se31.position); // must be recalculated to not be unscaled if scaling displacements ...
- GLUtils::GLDrawLine(pos1,pos2,Vector3r(.5,.5,.5));
- Vector3r bend; Real tors;
- ss->bendingTorsionRel(bend,tors);
- GLUtils::GLDrawLine(contPt,contPt+10*ss->radius1*(bend+ss->normal*tors),Vector3r(1,0,0));
- #if 0
- GLUtils::GLDrawNum(bend[0],contPt-.2*ss->normal*ss->radius1,Vector3r(1,0,0));
- GLUtils::GLDrawNum(bend[1],contPt,Vector3r(0,1,0));
- GLUtils::GLDrawNum(bend[2],contPt+.2*ss->normal*ss->radius1,Vector3r(0,0,1));
- GLUtils::GLDrawNum(tors,contPt+.5*ss->normal*ss->radius2,Vector3r(1,1,0));
- #endif
- #endif
- // sphere center to point on the sphere
- if(rolledPoints){
- GLUtils::GLDrawLine(pos1,pos1+(ss->ori1*ss->cp1rel*Vector3r::UnitX()*ss->effR1),Vector3r(0,.5,1));
- GLUtils::GLDrawLine(pos2,pos2+(ss->ori2*ss->cp2rel*Vector3r::UnitX()*ss->effR2),Vector3r(0,1,.5));
- }
- //TRVAR4(pos1,ss->ori1,pos2,ss->ori2);
- //TRVAR2(ss->cp2rel,pos2+(ss->ori2*ss->cp2rel*Vector3r::UnitX()*ss->effR2));
- // contact point to projected points
- if(unrolledPoints||shear){
- Vector3r ptTg1=ss->contPtInTgPlane1(), ptTg2=ss->contPtInTgPlane2();
- if(unrolledPoints){
- //TRVAR3(ptTg1,ptTg2,ss->normal)
- GLUtils::GLDrawLine(contPt,contPt+ptTg1,Vector3r(0,.5,1)); GLUtils::GLDrawLine(pos1,contPt+ptTg1,Vector3r(0,.5,1));
- GLUtils::GLDrawLine(contPt,contPt+ptTg2,Vector3r(0,1,.5)); GLUtils::GLDrawLine(pos2,contPt+ptTg2,Vector3r(0,1,.5));
- }
- if(shear){
- GLUtils::GLDrawLine(contPt+ptTg1,contPt+ptTg2,Vector3r(1,1,1));
- if(shearLabel) GLUtils::GLDrawNum(ss->displacementT().norm(),contPt,Vector3r(1,1,1));
- }
- }
- }
-#endif
-
-CREATE_LOGGER(Ig2_Sphere_Sphere_Dem3DofGeom);
-
-bool Ig2_Sphere_Sphere_Dem3DofGeom::go(const shared_ptr<Shape>& cm1, const shared_ptr<Shape>& cm2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& c){
- Sphere *s1=static_cast<Sphere*>(cm1.get()), *s2=static_cast<Sphere*>(cm2.get());
- Vector3r normal=(state2.pos+shift2)-state1.pos;
- Real penetrationDepthSq=pow((distFactor>0?distFactor:1.)*(s1->radius+s2->radius),2)-normal.squaredNorm();
- if (penetrationDepthSq<0 && !c->isReal() && !force){
- return false;
- }
-
- Real dist=normal.norm(); normal/=dist; /* normal is unit vector now */
- shared_ptr<Dem3DofGeom_SphereSphere> ss;
- if(c->geom) ss=YADE_PTR_CAST<Dem3DofGeom_SphereSphere>(c->geom);
- else {
- ss=shared_ptr<Dem3DofGeom_SphereSphere>(new Dem3DofGeom_SphereSphere());
- c->geom=ss;
-
- // constants
- if(distFactor>0) ss->refLength=dist;
- else ss->refLength=s1->radius+s2->radius;
- ss->refR1=s1->radius; ss->refR2=s2->radius;
-
- Real penetrationDepth=s1->radius+s2->radius-ss->refLength;
-
- if(scene->iter<=10){
- ss->effR1=s1->radius-.5*penetrationDepth; ss->effR2=s2->radius-.5*penetrationDepth;
- } else {ss->effR1=s1->radius; ss->effR2=s2->radius;}
-
- // for bending only: ss->initRelOri12=state1.ori.Conjugate()*state2.ori;
- // quasi-constants
- ss->cp1rel.setFromTwoVectors(Vector3r::UnitX(),state1.ori.conjugate()*normal);
- ss->cp2rel.setFromTwoVectors(Vector3r::UnitX(),state2.ori.conjugate()*(-normal));
- ss->cp1rel.normalize(); ss->cp2rel.normalize();
- }
- ss->normal=normal;
- ss->contactPoint=state1.pos+(ss->effR1-.5*(ss->refLength-dist))*ss->normal;
- ss->se31=state1.se3; ss->se32=state2.se3; ss->se32.position+=shift2;
- return true;
-}
-
=== removed file 'pkg/dem/Dem3DofGeom_SphereSphere.hpp'
--- pkg/dem/Dem3DofGeom_SphereSphere.hpp 2011-01-09 16:34:50 +0000
+++ pkg/dem/Dem3DofGeom_SphereSphere.hpp 1970-01-01 00:00:00 +0000
@@ -1,80 +0,0 @@
-#pragma once
-#include<yade/pkg/dem/DemXDofGeom.hpp>
-#include<yade/pkg/common/Sphere.hpp>
-
-class Dem3DofGeom_SphereSphere: public Dem3DofGeom{
- public:
- // auxiliary functions; the quaternion magic is all in here
- static Vector3r unrollSpherePtToPlane(const Quaternionr& fromXtoPtOri, const Real& radius, const Vector3r& normal);
- static Quaternionr rollPlanePtToSphere(const Vector3r& planePt, const Real& radius, const Vector3r& normal);
- private:
- Vector3r contPtInTgPlane1() const { return unrollSpherePtToPlane(ori1*cp1rel,effR1,normal); }
- Vector3r contPtInTgPlane2() const { return unrollSpherePtToPlane(ori2*cp2rel,effR2,-normal);}
- void setTgPlanePts(Vector3r p1new, Vector3r p2new);
- void relocateContactPoints();
- void relocateContactPoints(const Vector3r& tgPlanePt1, const Vector3r& tgPlanePt2);
- public:
- //! shorthands
- const Vector3r &pos1; const Quaternionr &ori1; const Vector3r &pos2; const Quaternionr &ori2;
- virtual ~Dem3DofGeom_SphereSphere();
-
- /********* API **********/
- Real displacementN(){ return (pos2-pos1).norm()-refLength; }
- Vector3r displacementT() {
- // enabling automatic relocation decreases overall simulation speed by about 3%; perhaps: bool largeStrains ... ?
- #if 1
- Vector3r p1=contPtInTgPlane1(), p2=contPtInTgPlane2(); relocateContactPoints(p1,p2); return p2-p1; // shear before relocation, but that is OK
- #else
- return contPtInTgPlane2()-contPtInTgPlane1();
- #endif
- }
- virtual Real slipToDisplacementTMax(Real displacementTMax);
- /********* end API ***********/
-
- YADE_CLASS_BASE_DOC_ATTRS_INIT_CTOR_PY(Dem3DofGeom_SphereSphere,Dem3DofGeom,"Class representing 2 spheres in contact which computes 3 degrees of freedom (normal and shear deformation).",
- ((Real,effR1,,,"Effective radius of sphere #1; can be smaller/larger than refR1 (the actual radius), but quasi-constant throughout interaction life"))
- ((Real,effR2,,,"Same as effR1, but for sphere #2."))
- ((Quaternionr,cp1rel,,,"Sphere's #1 relative orientation of the contact point with regards to sphere-local +x axis (quasi-constant)"))
- ((Quaternionr,cp2rel,,,"Same as cp1rel, but for sphere #2.")),
- /* extra initializers */ ((pos1,se31.position))((ori1,se31.orientation))((pos2,se32.position))((ori2,se32.orientation)),
- /*ctor*/ createIndex(); ,
- /*py*/
- );
- REGISTER_CLASS_INDEX(Dem3DofGeom_SphereSphere,Dem3DofGeom);
- friend class Gl1_Dem3DofGeom_SphereSphere;
- friend class Ig2_Sphere_Sphere_Dem3DofGeom;
-};
-REGISTER_SERIALIZABLE(Dem3DofGeom_SphereSphere);
-
-#ifdef YADE_OPENGL
- #include<yade/pkg/common/GLDrawFunctors.hpp>
- class Gl1_Dem3DofGeom_SphereSphere:public GlIGeomFunctor{
- public:
- virtual void go(const shared_ptr<IGeom>&,const shared_ptr<Interaction>&,const shared_ptr<Body>&,const shared_ptr<Body>&,bool wireFrame);
- RENDERS(Dem3DofGeom_SphereSphere);
- YADE_CLASS_BASE_DOC_STATICATTRS(Gl1_Dem3DofGeom_SphereSphere,GlIGeomFunctor,"Render interaction of 2 spheres (represented by Dem3DofGeom_SphereSphere)",
- ((bool,normal,false,,"Render interaction normal"))
- ((bool,rolledPoints,false,,"Render points rolled on the spheres (tracks the original contact point)"))
- ((bool,unrolledPoints,false,,"Render original contact points unrolled to the contact plane"))
- ((bool,shear,false,,"Render shear line in the contact plane"))
- ((bool,shearLabel,false,,"Render shear magnitude as number"))
- );
- };
- REGISTER_SERIALIZABLE(Gl1_Dem3DofGeom_SphereSphere);
-#endif
-
-#include<yade/pkg/common/Dispatching.hpp>
-class Ig2_Sphere_Sphere_Dem3DofGeom:public IGeomFunctor{
- public:
- virtual bool go(const shared_ptr<Shape>& cm1, const shared_ptr<Shape>& cm2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& c);
- virtual bool goReverse( const shared_ptr<Shape>&, const shared_ptr<Shape>&, const State&, const State&, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>&){throw runtime_error("goReverse on symmetric functor should never be called!");}
- FUNCTOR2D(Sphere,Sphere);
- DEFINE_FUNCTOR_ORDER_2D(Sphere,Sphere);
- DECLARE_LOGGER;
- YADE_CLASS_BASE_DOC_ATTRS(Ig2_Sphere_Sphere_Dem3DofGeom,IGeomFunctor,
- "Functor handling contact of 2 spheres, producing Dem3DofGeom instance",
- ((Real,distFactor,-1,,"Factor of sphere radius such that sphere \"touch\" if their centers are not further than distFactor*(r1+r2); if negative, equilibrium distance is the sum of the sphere's radii."))
- );
-};
-REGISTER_SERIALIZABLE(Ig2_Sphere_Sphere_Dem3DofGeom);
-
=== removed file 'pkg/dem/Dem3DofGeom_WallSphere.cpp'
--- pkg/dem/Dem3DofGeom_WallSphere.cpp 2010-12-13 12:11:43 +0000
+++ pkg/dem/Dem3DofGeom_WallSphere.cpp 1970-01-01 00:00:00 +0000
@@ -1,117 +0,0 @@
-// © 2009 Václav Šmilauer <eudoxos@xxxxxxxx>
-#include<yade/pkg/dem/Dem3DofGeom_WallSphere.hpp>
-#include<yade/pkg/common/Sphere.hpp>
-#include<yade/pkg/common/Wall.hpp>
-YADE_PLUGIN((Dem3DofGeom_WallSphere)
- #ifdef YADE_OPENGL
- (Gl1_Dem3DofGeom_WallSphere)
- #endif
- (Ig2_Wall_Sphere_Dem3DofGeom));
-
-CREATE_LOGGER(Dem3DofGeom_WallSphere);
-Dem3DofGeom_WallSphere::~Dem3DofGeom_WallSphere(){}
-
-void Dem3DofGeom_WallSphere::setTgPlanePts(const Vector3r& p1new, const Vector3r& p2new){
- TRVAR3(cp1pt,cp2rel,contPtInTgPlane2()-contPtInTgPlane1());
- cp1pt=p1new+contactPoint-se31.position;
- cp2rel=se32.orientation.conjugate()*Dem3DofGeom_SphereSphere::rollPlanePtToSphere(p2new,effR2,-normal);
- TRVAR3(cp1pt,cp2rel,contPtInTgPlane2()-contPtInTgPlane1());
-}
-
-void Dem3DofGeom_WallSphere::relocateContactPoints(const Vector3r& p1, const Vector3r& p2){
- //TRVAR2(p2.norm(),effR2);
- if(p2.squaredNorm()>pow(effR2,2)){
- setTgPlanePts(Vector3r::Zero(),p2-p1);
- }
-}
-
-Real Dem3DofGeom_WallSphere::slipToDisplacementTMax(Real displacementTMax){
- //FIXME: not yet tested
- // negative or zero: reset shear
- if(displacementTMax<=0.){ setTgPlanePts(Vector3r(0,0,0),Vector3r(0,0,0)); return displacementTMax;}
- // otherwise
- Vector3r p1=contPtInTgPlane1(), p2=contPtInTgPlane2();
- Real currDistSq=(p2-p1).squaredNorm();
- if(currDistSq<pow(displacementTMax,2)) return 0; // close enough, no slip needed
- //Vector3r diff=.5*(sqrt(currDistSq)/displacementTMax-1)*(p2-p1); setTgPlanePts(p1+diff,p2-diff);
- Real scale=displacementTMax/sqrt(currDistSq); setTgPlanePts(scale*p1,scale*p2);
- return (displacementTMax/scale)*(1-scale);
-}
-
-CREATE_LOGGER(Ig2_Wall_Sphere_Dem3DofGeom);
-bool Ig2_Wall_Sphere_Dem3DofGeom::go(const shared_ptr<Shape>& cm1, const shared_ptr<Shape>& cm2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& c){
- Wall* wall=static_cast<Wall*>(cm1.get());
- Real sphereRadius=static_cast<Sphere*>(cm2.get())->radius;
-
- Real dist=(state2.pos+shift2)[wall->axis]-state1.pos[wall->axis];
- if(!c->isReal() && abs(dist)>sphereRadius && !force){ /*LOG_DEBUG("dist="<<dist<<", returning false");*/ return false; } // wall and sphere too far from each other
-
- // contact point is sphere center projected onto the wall
- Vector3r contPt=state2.pos; contPt[wall->axis]=state1.pos[wall->axis];
- Vector3r normalGlob(0.,0.,0.);
- // wall interacting from both sides: normal depends on sphere's position
- assert(wall->sense==-1 || wall->sense==0 || wall->sense==1);
- if(wall->sense==0) normalGlob[wall->axis]=dist>0?1.:-1.;
- else normalGlob[wall->axis]=wall->sense==1?1.:-1;
-
- shared_ptr<Dem3DofGeom_WallSphere> ws;
- if(c->geom) ws=YADE_PTR_CAST<Dem3DofGeom_WallSphere>(c->geom);
- else {
- ws=shared_ptr<Dem3DofGeom_WallSphere>(new Dem3DofGeom_WallSphere());
- c->geom=ws;
- ws->effR2=abs(dist);
- ws->refR1=-1; ws->refR2=sphereRadius;
- ws->refLength=ws->effR2;
- ws->cp1pt=contPt-state1.pos; // initial contact point relative to wall position (orientation is global, since it is coincident with local for a wall)
- ws->cp2rel=Quaternionr::Identity();
- ws->cp2rel.setFromTwoVectors(Vector3r::UnitX(),state2.ori.conjugate()*(-normalGlob)); // initial sphere-local center-contactPt orientation WRT +x
- ws->cp2rel.normalize();
- //LOG_INFO(ws->cp1pt);
- }
- ws->se31=state1.se3; ws->se32=state2.se3; ws->se32.position+=shift2;
- ws->contactPoint=contPt;
- ws->normal=normalGlob;
- return true;
-}
-#ifdef YADE_OPENGL
-
- #include<yade/lib/opengl/OpenGLWrapper.hpp>
- #include<yade/lib/opengl/GLUtils.hpp>
-
- bool Gl1_Dem3DofGeom_WallSphere::normal=false;
- bool Gl1_Dem3DofGeom_WallSphere::rolledPoints=false;
- bool Gl1_Dem3DofGeom_WallSphere::unrolledPoints=false;
- bool Gl1_Dem3DofGeom_WallSphere::shear=false;
- bool Gl1_Dem3DofGeom_WallSphere::shearLabel=false;
-
- void Gl1_Dem3DofGeom_WallSphere::go(const shared_ptr<IGeom>& ig, const shared_ptr<Interaction>& ip, const shared_ptr<Body>& b1, const shared_ptr<Body>& b2, bool wireFrame){
- Dem3DofGeom_WallSphere* ws=static_cast<Dem3DofGeom_WallSphere*>(ig.get());
- const Se3r& se31=b1->state->se3,se32=b2->state->se3;
- const Vector3r& pos1=se31.position; const Vector3r& pos2=se32.position;
- //const Quaternionr& ori1=se31.orientation;
- const Quaternionr& ori2=se32.orientation;
- const Vector3r& contPt=ws->contactPoint;
-
- if(normal){
- GLUtils::GLDrawArrow(contPt,contPt+ws->refLength*ws->normal); // normal of the contact
- }
- // sphere center to point on the sphere
- if(rolledPoints){
- GLUtils::GLDrawLine(pos1+ws->cp1pt,contPt,Vector3r(0,.5,1));
- GLUtils::GLDrawLine(pos2,pos2+(ori2*ws->cp2rel*Vector3r::UnitX()*ws->effR2),Vector3r(0,1,.5));
- }
- // contact point to projected points
- if(unrolledPoints||shear){
- Vector3r ptTg1=ws->contPtInTgPlane1(), ptTg2=ws->contPtInTgPlane2();
- if(unrolledPoints){
- GLUtils::GLDrawLine(contPt,contPt+ptTg1,Vector3r(0,.5,1));
- GLUtils::GLDrawLine(contPt,contPt+ptTg2,Vector3r(0,1,.5)); GLUtils::GLDrawLine(pos2,contPt+ptTg2,Vector3r(0,1,.5));
- }
- if(shear){
- GLUtils::GLDrawLine(contPt+ptTg1,contPt+ptTg2,Vector3r(1,1,1));
- if(shearLabel) GLUtils::GLDrawNum(ws->displacementT().norm(),contPt,Vector3r(1,1,1));
- }
- }
- }
-
-#endif
=== removed file 'pkg/dem/Dem3DofGeom_WallSphere.hpp'
--- pkg/dem/Dem3DofGeom_WallSphere.hpp 2011-01-09 16:34:50 +0000
+++ pkg/dem/Dem3DofGeom_WallSphere.hpp 1970-01-01 00:00:00 +0000
@@ -1,70 +0,0 @@
-#pragma once
-#include<yade/pkg/dem/DemXDofGeom.hpp>
-// for static roll/unroll functions in Dem3DofGeom_SphereSphere
-#include<yade/pkg/dem/Dem3DofGeom_SphereSphere.hpp>
-#include<yade/pkg/common/Sphere.hpp>
-#include<yade/pkg/common/Wall.hpp>
-
-class Dem3DofGeom_WallSphere: public Dem3DofGeom{
-
- Vector3r contPtInTgPlane1() const { return se31.position+cp1pt-contactPoint; }
- Vector3r contPtInTgPlane2() const { return Dem3DofGeom_SphereSphere::unrollSpherePtToPlane(se32.orientation*cp2rel,effR2,-normal);}
-
- public:
- virtual ~Dem3DofGeom_WallSphere();
- /******* API ********/
- virtual Real displacementN(){ return (se32.position-contactPoint).norm()-refLength;}
- virtual Vector3r displacementT(){ relocateContactPoints(); return contPtInTgPlane2()-contPtInTgPlane1(); }
- virtual Real slipToDisplacementTMax(Real displacementTMax);
- /***** end API ******/
-
- void setTgPlanePts(const Vector3r&, const Vector3r&);
- void relocateContactPoints(){ relocateContactPoints(contPtInTgPlane1(),contPtInTgPlane2()); }
- void relocateContactPoints(const Vector3r& p1, const Vector3r& p2);
-
- YADE_CLASS_BASE_DOC_ATTRS_CTOR(Dem3DofGeom_WallSphere,Dem3DofGeom,"Representation of contact between wall and sphere, based on Dem3DofGeom.",
- ((Vector3r,cp1pt,,,"initial contact point on the wall, relative to the current contact point"))
- ((Quaternionr,cp2rel,,,"orientation between +x and the reference contact point (on the sphere) in sphere-local coords"))
- ((Real,effR2,,,"effective radius of sphere")),
- /*ctor*/ createIndex();
- );
- REGISTER_CLASS_INDEX(Dem3DofGeom_WallSphere,Dem3DofGeom);
- DECLARE_LOGGER;
- friend class Gl1_Dem3DofGeom_WallSphere;
- friend class Ig2_Wall_Sphere_Dem3DofGeom;
-};
-REGISTER_SERIALIZABLE(Dem3DofGeom_WallSphere);
-
-#ifdef YADE_OPENGL
- #include<yade/pkg/common/GLDrawFunctors.hpp>
- class Gl1_Dem3DofGeom_WallSphere:public GlIGeomFunctor{
- public:
- virtual void go(const shared_ptr<IGeom>&,const shared_ptr<Interaction>&,const shared_ptr<Body>&,const shared_ptr<Body>&,bool wireFrame);
- RENDERS(Dem3DofGeom_WallSphere);
- YADE_CLASS_BASE_DOC_STATICATTRS(Gl1_Dem3DofGeom_WallSphere,GlIGeomFunctor,"Render interaction of wall and sphere (represented by Dem3DofGeom_WallSphere)",
- ((bool,normal,false,,"Render interaction normal"))
- ((bool,rolledPoints,false,,"Render points rolled on the spheres (tracks the original contact point)"))
- ((bool,unrolledPoints,false,,"Render original contact points unrolled to the contact plane"))
- ((bool,shear,false,,"Render shear line in the contact plane"))
- ((bool,shearLabel,false,,"Render shear magnitude as number"))
- );
- };
- REGISTER_SERIALIZABLE(Gl1_Dem3DofGeom_WallSphere);
-#endif
-
-#include<yade/pkg/common/Dispatching.hpp>
-class Ig2_Wall_Sphere_Dem3DofGeom:public IGeomFunctor{
- public:
- virtual bool go(const shared_ptr<Shape>& cm1, const shared_ptr<Shape>& cm2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& c);
- virtual bool goReverse( const shared_ptr<Shape>& cm1, const shared_ptr<Shape>& cm2, const State& state1, const State& state2, const Vector3r& shift2, const bool& force, const shared_ptr<Interaction>& c){
- c->swapOrder(); return go(cm2,cm1,state2,state1,-shift2,force,c);
- LOG_ERROR("!! goReverse might not work in Ig2_Wall_Sphere_Dem3DofGeom. IGeomDispatcher should swap interaction members first and call go(...) afterwards.");
- }
-
- FUNCTOR2D(Wall,Sphere);
- DEFINE_FUNCTOR_ORDER_2D(Wall,Sphere);
- YADE_CLASS_BASE_DOC(Ig2_Wall_Sphere_Dem3DofGeom,IGeomFunctor,"Create/update contact of :yref:`Wall` and :yref:`Sphere` (:yref:`Dem3DofGeom_WallSphere` instance)");
- DECLARE_LOGGER;
-};
-REGISTER_SERIALIZABLE(Ig2_Wall_Sphere_Dem3DofGeom);
-
=== modified file 'pkg/dem/DemXDofGeom.cpp'
--- pkg/dem/DemXDofGeom.cpp 2010-10-13 16:23:08 +0000
+++ pkg/dem/DemXDofGeom.cpp 2013-08-29 10:30:31 +0000
@@ -1,5 +1,3 @@
#include"DemXDofGeom.hpp"
-YADE_PLUGIN((GenericSpheresContact)(Dem3DofGeom));
-Real Dem3DofGeom::displacementN(){throw;}
-Dem3DofGeom::~Dem3DofGeom(){}
+YADE_PLUGIN((GenericSpheresContact));
GenericSpheresContact::~GenericSpheresContact(){}
=== modified file 'pkg/dem/DemXDofGeom.hpp'
--- pkg/dem/DemXDofGeom.hpp 2011-01-24 14:45:35 +0000
+++ pkg/dem/DemXDofGeom.hpp 2013-08-29 10:30:31 +0000
@@ -2,12 +2,12 @@
#pragma once
#include<yade/core/IGeom.hpp>
-/*! Abstract class that unites ScGeom and Dem3DofGeom,
+/*! Abstract class that unites ScGeom and L3Geom,
created for the purposes of GlobalStiffnessTimeStepper.
It might be removed in the future. */
class GenericSpheresContact: public IGeom{
YADE_CLASS_BASE_DOC_ATTRS_CTOR(GenericSpheresContact,IGeom,
- "Class uniting :yref:`ScGeom` and :yref:`Dem3DofGeom`, for the purposes of :yref:`GlobalStiffnessTimeStepper`. (It might be removed inthe future). Do not use this class directly.",
+ "Class uniting :yref:`ScGeom` and :yref:`L3Geom`, for the purposes of :yref:`GlobalStiffnessTimeStepper`. (It might be removed inthe future). Do not use this class directly.",
((Vector3r,normal,,,"Unit vector oriented along the interaction, from particle #1, towards particle #2. |yupdate|"))
((Vector3r,contactPoint,,,"some reference point for the interaction (usually in the middle). |ycomp|"))
((Real,refR1,,,"Reference radius of particle #1. |ycomp|"))
@@ -19,45 +19,3 @@
virtual ~GenericSpheresContact(); // vtable
};
REGISTER_SERIALIZABLE(GenericSpheresContact);
-
-/*! Abstract base class for representing contact geometry of 2 elements that has 3 degrees of freedom:
- * normal (1 component) and shear (Vector3r, but in plane perpendicular to the normal)
- */
-class Dem3DofGeom: public GenericSpheresContact{
- public:
- virtual ~Dem3DofGeom();
-
- // API that needs to be implemented in derived classes
- virtual Real displacementN();
- virtual Vector3r displacementT(){throw;}
- virtual Real slipToDisplacementTMax(Real displacementTMax){throw;}; // plasticity
- // reference radii, for contact stiffness computation; set to negative for nonsense values
- // end API
-
- Real strainN(){
- //if(!logCompression)
- return displacementN()/refLength;
- //else{Real dn=displacementN(); }
- }
- Vector3r strainT(){return displacementT()/refLength;}
- Real slipToStrainTMax(Real strainTMax){return slipToDisplacementTMax(strainTMax*refLength)/refLength;}
-
- YADE_CLASS_BASE_DOC_ATTRS_CTOR_PY(Dem3DofGeom,GenericSpheresContact,
- "Abstract base class for representing contact geometry of 2 elements that has 3 degrees of freedom: normal (1 component) and shear (Vector3r, but in plane perpendicular to the normal).",
- ((Real,refLength,,,"some length used to convert displacements to strains. |ycomp|"))
- ((bool,logCompression,false,,"make strain go to -∞ for length going to zero (false by default)."))
- ((Se3r,se31,,,"Copy of body #1 se3 (needed to compute torque from the contact, strains etc). |yupdate|"))
- ((Se3r,se32,,,"Copy of body #2 se3. |yupdate|")),
- createIndex();,
- .def("displacementN",&Dem3DofGeom::displacementN)
- .def("displacementT",&Dem3DofGeom::displacementT)
- .def("strainN",&Dem3DofGeom::strainN)
- .def("strainT",&Dem3DofGeom::strainT)
- .def("slipToDisplacementTMax",&Dem3DofGeom::slipToDisplacementTMax)
- .def("slipToStrainTMax",&Dem3DofGeom::slipToStrainTMax)
- );
- REGISTER_CLASS_INDEX(Dem3DofGeom,IGeom);
-};
-REGISTER_SERIALIZABLE(Dem3DofGeom);
-
-
=== modified file 'pkg/dem/DomainLimiter.cpp'
--- pkg/dem/DomainLimiter.cpp 2013-08-23 15:21:20 +0000
+++ pkg/dem/DomainLimiter.cpp 2013-08-29 10:30:31 +0000
@@ -81,15 +81,14 @@
// test object types
GenericSpheresContact* gsc=dynamic_cast<GenericSpheresContact*>(I->geom.get());
ScGeom* scGeom=dynamic_cast<ScGeom*>(I->geom.get());
- Dem3DofGeom* d3dGeom=dynamic_cast<Dem3DofGeom*>(I->geom.get());
L3Geom* l3Geom=dynamic_cast<L3Geom*>(I->geom.get());
L6Geom* l6Geom=dynamic_cast<L6Geom*>(I->geom.get());
ScGeom6D* scGeom6d=dynamic_cast<ScGeom6D*>(I->geom.get());
bool hasRot=(l6Geom || scGeom6d);
//NormShearPhys* phys=dynamic_cast<NormShearPhys*>(I->phys.get()); //Disabled because of warning
if(!gsc) throw std::invalid_argument("LawTester: IGeom of "+strIds+" not a GenericSpheresContact.");
- if(!scGeom && !d3dGeom && !l3Geom) throw std::invalid_argument("LawTester: IGeom of "+strIds+" is neither ScGeom, nor Dem3DofGeom, nor L3Geom (or L6Geom).");
- assert(!((bool)scGeom && (bool)d3dGeom && (bool)l3Geom)); // nonsense
+ if(!scGeom && !l3Geom) throw std::invalid_argument("LawTester: IGeom of "+strIds+" is neither ScGeom, nor Dem3DofGeom, nor L3Geom (or L6Geom).");
+ assert(!((bool)scGeom && (bool)l3Geom)); // nonsense
// get body objects
State *state1=Body::byId(id1,scene)->state.get(), *state2=Body::byId(id2,scene)->state.get();
scene->forces.sync();
@@ -125,9 +124,7 @@
if(scGeom6d) uGeom.tail<3>()=-1.*Vector3r(scGeom6d->getTwist(),scGeom6d->getBending().dot(axY),scGeom6d->getBending().dot(axZ));
}
else{ // d3dGeom
- throw runtime_error("LawTester: Dem3DofGeom not yet supported.");
- // essentially copies code from ScGeom, which is not very nice indeed; oh well…
- // Vector3r vRel=(state2->vel+state2->angVel.cross(-gsc->refR2*gsc->normal))-(state1->vel+state1->angVel.cross(gsc->refR1*gsc->normal));
+ throw runtime_error("Geom type not yet supported.");
}
}
// update the transformation
=== modified file 'pkg/dem/Shop.cpp'
--- pkg/dem/Shop.cpp 2013-06-20 14:56:35 +0000
+++ pkg/dem/Shop.cpp 2013-08-29 10:30:31 +0000
@@ -559,44 +559,23 @@
Vector3r normalStress,shearStress;
if(!I->isReal()) continue;
- //NormShearPhys + Dem3DofGeom
- const NormShearPhys* physNSP = YADE_CAST<NormShearPhys*>(I->phys.get());
- //Dem3DofGeom* geom=YADE_CAST<Dem3DofGeom*>(I->geom.get()); //For the moment only for Dem3DofGeom!!!
- // FIXME: slower, but does not crash
- Dem3DofGeom* geomDDG=dynamic_cast<Dem3DofGeom*>(I->geom.get()); //For the moment only for Dem3DofGeom!!!
-
- //FrictPhys + ScGeom
const FrictPhys* physFP = YADE_CAST<FrictPhys*>(I->phys.get());
- ScGeom* geomScG=dynamic_cast<ScGeom*>(I->geom.get());
+ ScGeom* geomScG=YADE_CAST<ScGeom*>(I->geom.get());
const Body::id_t id1=I->getId1(), id2=I->getId2();
- if(((physNSP) and (geomDDG)) or ((physFP) and (geomScG))){
- if ((physNSP) and (geomDDG)) {
- Real minRad=(geomDDG->refR1<=0?geomDDG->refR2:(geomDDG->refR2<=0?geomDDG->refR1:min(geomDDG->refR1,geomDDG->refR2)));
- Real crossSection=Mathr::PI*pow(minRad,2);
-
- normalStress=((1./crossSection)*geomDDG->normal.dot(physNSP->normalForce))*geomDDG->normal;
- for(int i=0; i<3; i++){
- int ix1=(i+1)%3,ix2=(i+2)%3;
- shearStress[i]=geomDDG->normal[ix1]*physNSP->shearForce[ix1]+geomDDG->normal[ix2]*physNSP->shearForce[ix2];
- shearStress[i]/=crossSection;
- }
- } else if ((physFP) and (geomScG)) {
- Real minRad=(geomScG->radius1<=0?geomScG->radius2:(geomScG->radius2<=0?geomScG->radius1:min(geomScG->radius1,geomScG->radius2)));
- Real crossSection=Mathr::PI*pow(minRad,2);
+ if((physFP) and (geomScG)){
+ Real minRad=(geomScG->radius1<=0?geomScG->radius2:(geomScG->radius2<=0?geomScG->radius1:min(geomScG->radius1,geomScG->radius2)));
+ Real crossSection=Mathr::PI*pow(minRad,2);
- normalStress=((1./crossSection)*geomScG->normal.dot(physFP->normalForce))*geomScG->normal;
- for(int i=0; i<3; i++){
- int ix1=(i+1)%3,ix2=(i+2)%3;
- shearStress[i]=geomScG->normal[ix1]*physFP->shearForce[ix1]+geomScG->normal[ix2]*physFP->shearForce[ix2];
- shearStress[i]/=crossSection;
- }
+ normalStress=((1./crossSection)*geomScG->normal.dot(physFP->normalForce))*geomScG->normal;
+ for(int i=0; i<3; i++){
+ int ix1=(i+1)%3,ix2=(i+2)%3;
+ shearStress[i]=geomScG->normal[ix1]*physFP->shearForce[ix1]+geomScG->normal[ix2]*physFP->shearForce[ix2];
+ shearStress[i]/=crossSection;
}
-
bodyStates[id1].normStress+=normalStress;
bodyStates[id2].normStress+=normalStress;
-
bodyStates[id1].shearStress+=shearStress;
bodyStates[id2].shearStress+=shearStress;
}
@@ -796,33 +775,6 @@
return stressTensor/volume;
}
-/*
-Matrix3r Shop::stressTensorOfPeriodicCell(bool smallStrains){
- Scene* scene=Omega::instance().getScene().get();
- if (!scene->isPeriodic){ throw runtime_error("Can't compute stress of periodic cell in aperiodic simulation."); }
-// if (smallStrains){volume = scene->getVolume()cell->refSize[0]*scene->cell->refSize[1]*scene->cell->refSize[2];}
-// else volume = scene->cell->trsf.determinant()*scene->cell->refSize[0]*scene->cell->refSize[1]*scene->cell->refSize[2];
- // Using the function provided by Cell (BC)
- Real volume = scene->cell->getVolume();
- Matrix3r stress = Matrix3r::Zero();
- FOREACH(const shared_ptr<Interaction>& I, *scene->interactions){
- if(!I->isReal()) continue;
- Dem3DofGeom* geom=YADE_CAST<Dem3DofGeom*>(I->geom.get());
- NormShearPhys* phys=YADE_CAST<NormShearPhys*>(I->phys.get());
- Real l;
- if (smallStrains){l = geom->refLength;}
- else l=(geom->se31.position-geom->se32.position).norm();
- Vector3r& n=geom->normal;
- Vector3r& fT=phys->shearForce;
- Real fN=phys->normalForce.dot(n);
-
- stress += l*(fN*n*n.transpose() + .5*(fT*n.transpose() + n*fT.transpose()));
- }
- stress/=volume;
- return stress;
-}
-*/
-
void Shop::getStressLWForEachBody(vector<Matrix3r>& bStresses){
const shared_ptr<Scene>& scene=Omega::instance().getScene();
bStresses.resize(scene->bodies->size());
=== modified file 'pkg/dem/Shop.hpp'
--- pkg/dem/Shop.hpp 2013-05-30 20:19:43 +0000
+++ pkg/dem/Shop.hpp 2013-08-29 10:30:31 +0000
@@ -123,8 +123,6 @@
static Matrix3r getStress(Real volume=0);
static Matrix3r getCapillaryStress(Real volume=0);
static Matrix3r stressTensorOfPeriodicCell() { LOG_WARN("Shop::stressTensorOfPeriodicCelli is DEPRECATED: use getStress instead"); return Shop::getStress(); }
- //! This version is restricted to periodic BCs and Dem3Dof
- static Matrix3r stressTensorOfPeriodicCell(bool smallStrains=true);
//! Compute overall ("macroscopic") stress of periodic cell, returning 2 tensors
//! (contribution of normal and shear forces)
static py::tuple normalShearStressTensors(bool compressionPositive=false, bool splitNormalTensor=false, Real thresholdForce=NaN);
=== removed file 'py/_eudoxos.cpp'
--- py/_eudoxos.cpp 2013-03-07 18:28:01 +0000
+++ py/_eudoxos.cpp 1970-01-01 00:00:00 +0000
@@ -1,335 +0,0 @@
-#if 0
- #include<yade/lib/pyutil/numpy.hpp>
-#endif
-
-#include<yade/pkg/dem/ConcretePM.hpp>
-#include<boost/python.hpp>
-#include<boost/python/object.hpp>
-#include<boost/version.hpp>
-#include<yade/pkg/dem/Shop.hpp>
-#include<yade/pkg/dem/DemXDofGeom.hpp>
-
-#ifdef YADE_VTK
- #pragma GCC diagnostic ignored "-Wdeprecated"
- #include<vtkPointLocator.h>
- #include<vtkIdList.h>
- #include<vtkUnstructuredGrid.h>
- #include<vtkPoints.h>
- #pragma GCC diagnostic warning "-Wdeprecated"
-#endif
-
-namespace py = boost::python;
-using namespace std;
-
-#ifdef YADE_CPM_FULL_MODEL_AVAILABLE
- #include"../../brefcom-mm.hh"
-#endif
-
-# if 0
-Real elasticEnergyDensityInAABB(python::tuple Aabb){
- Vector3r bbMin=tuple2vec(python::extract<python::tuple>(Aabb[0])()), bbMax=tuple2vec(python::extract<python::tuple>(Aabb[1])()); Vector3r box=bbMax-bbMin;
- shared_ptr<Scene> rb=Omega::instance().getScene();
- Real E=0;
- FOREACH(const shared_ptr<Interaction>&i, *rb->interactions){
- if(!i->phys) continue;
- shared_ptr<CpmPhys> bc=dynamic_pointer_cast<CpmPhys>(i->phys); if(!bc) continue;
- const shared_ptr<Body>& b1=Body::byId(i->getId1(),rb), b2=Body::byId(i->getId2(),rb);
- bool isIn1=isInBB(b1->state->pos,bbMin,bbMax), isIn2=isInBB(b2->state->pos,bbMin,bbMax);
- if(!isIn1 && !isIn2) continue;
- Real weight=1.;
- if((!isIn1 && isIn2) || (isIn1 && !isIn2)){
- //shared_ptr<Body> bIn=isIn1?b1:b2, bOut=isIn2?b2:b1;
- Vector3r vIn=(isIn1?b1:b2)->state->pos, vOut=(isIn2?b1:b2)->state->pos;
- #define _WEIGHT_COMPONENT(axis) if(vOut[axis]<bbMin[axis]) weight=min(weight,abs((vOut[axis]-bbMin[axis])/(vOut[axis]-vIn[axis]))); else if(vOut[axis]>bbMax[axis]) weight=min(weight,abs((vOut[axis]-bbMax[axis])/(vOut[axis]-vIn[axis])));
- _WEIGHT_COMPONENT(0); _WEIGHT_COMPONENT(1); _WEIGHT_COMPONENT(2);
- assert(weight>=0 && weight<=1);
- }
- E+=.5*bc->E*bc->crossSection*pow(bc->epsN,2)+.5*bc->G*bc->crossSection*pow(bc->epsT.norm(),2);
- }
- return E/(box[0]*box[1]*box[2]);
-}
-#endif
-
-/*! Set velocity of all dynamic particles so that if their motion were unconstrained,
- * axis given by axisPoint and axisDirection would be reached in timeToAxis
- * (or, point at distance subtractDist from axis would be reached).
- *
- * The code is analogous to AxialGravityEngine and is intended to give initial motion
- * to particles subject to axial compaction to speed up the process. */
-void velocityTowardsAxis(const Vector3r& axisPoint, const Vector3r& axisDirection, Real timeToAxis, Real subtractDist=0., Real perturbation=0.1){
- FOREACH(const shared_ptr<Body>&b, *(Omega::instance().getScene()->bodies)){
- if(b->state->blockedDOFs==State::DOF_ALL) continue;
- const Vector3r& x0=b->state->pos;
- const Vector3r& x1=axisPoint;
- const Vector3r x2=axisPoint+axisDirection;
- Vector3r closestAxisPoint=(x2-x1) * /* t */ (-(x1-x0).dot(x2-x1))/((x2-x1).squaredNorm());
- Vector3r toAxis=closestAxisPoint-x0;
- if(subtractDist>0) toAxis*=(toAxis.norm()-subtractDist)/toAxis.norm();
- b->state->vel=toAxis/timeToAxis;
- Vector3r ppDiff=perturbation*(1./sqrt(3.))*Vector3r(Mathr::UnitRandom(),Mathr::UnitRandom(),Mathr::UnitRandom())*b->state->vel.norm();
- b->state->vel+=ppDiff;
- }
-}
-BOOST_PYTHON_FUNCTION_OVERLOADS(velocityTowardsAxis_overloads,velocityTowardsAxis,3,5);
-
-void particleConfinement(){
- CpmStateUpdater csu; csu.update();
-}
-
-// makes linker error out with monolithic build..
-#if 0
-python::dict testNumpy(){
- Scene* scene=Omega::instance().getScene().get();
- int dim1[]={scene->bodies->size()};
- int dim2[]={scene->bodies->size(),3};
- numpy_boost<Real,1> mass(dim1);
- numpy_boost<Real,2> vel(dim2);
- FOREACH(const shared_ptr<Body>& b, *scene->bodies){
- if(!b) continue;
- mass[b->getId()]=b->state->mass;
- VECTOR3R_TO_NUMPY(vel[b->getId()],b->state->vel);
- }
- py::dict ret;
- ret["mass"]=mass;
- ret["vel"]=vel;
- return ret;
-}
-#endif
-
-#if 0
-/* Compute stress tensor on each particle */
-void particleMacroStress(void){
- Scene* scene=Omega::instance().getScene().get();
- // find interactions of each particle
- std::vector<std::list<Body::id_t> > bIntr(scene->bodies->size());
- FOREACH(const shared_ptr<Interaction>& i, *scene->interactions){
- if(!i->isReal) continue;
- // only contacts between 2 spheres
- Sphere* s1=dynamic_cast<Sphere*>(Body::byId(i->getId1(),scene)->shape.get())
- Sphere* s2=dynamic_cast<Sphere*>(Body::byId(i->getId2(),scene)->shape.get())
- if(!s1 || !s2) continue;
- bIntr[i.getId1()].push_back(i.getId2());
- bIntr[i.getId2()].push_back(i.getId1());
- }
- for(Body::id_t id1=0; id1<(Body::id_t)bIntr.size(); id1++){
- if(bIntr[id1].size()==0) continue;
- Matrix3r ss(Matrix3r::Zero()); // stress tensor on current particle
- FOREACH(Body::id_t id2, bIntr[id1]){
- const shared_ptr<Interaction> i=scene->interactions->find(id1,id2);
- assert(i);
- Dem3DofGeom* geom=YADE_CAST<Dem3DofGeom*>(i->geom);
- CpmPhys* phys=YADE_CAST<CpmPhys*>(i->phys);
- Real d=(geom->se31->pos-geom->se32->pos).norm(); // current contact length
- const Vector3r& n=geom->normal;
- const Real& A=phys->crossSection;
- const Vector3r& sigmaT=phys->sigmaT;
- const Real& sigmaN=phys->sigmaN;
- for(int i=0; i<3; i++) for(int j=0;j<3; j++){
- ss[i][j]=d*A*(sigmaN*n[i]*n[j]+.5*(sigmaT[i]*n[j]+sigmaT[j]*n[i]));
- }
- }
- // divide ss by V of the particle
- // FIXME: for now, just use 2*(4/3)*π*r³ (.5 porosity)
- ss*=1/(2*(4/3)*Mathr::PI*);
- }
-}
-#endif
-#include<yade/lib/smoothing/WeightedAverage2d.hpp>
-/* Fastly locate interactions within given distance from a point in 2d (projected to plane) */
-struct HelixInteractionLocator2d{
- struct FlatInteraction{ Real r,h,theta; shared_ptr<Interaction> i; FlatInteraction(Real _r, Real _h, Real _theta, const shared_ptr<Interaction>& _i): r(_r), h(_h), theta(_theta), i(_i){}; };
- shared_ptr<GridContainer<FlatInteraction> > grid;
- Real thetaSpan;
- int axis;
- HelixInteractionLocator2d(Real dH_dTheta, int _axis, Real periodStart, Real theta0, Real thetaMin, Real thetaMax): axis(_axis){
- Scene* scene=Omega::instance().getScene().get();
- Real inf=std::numeric_limits<Real>::infinity();
- Vector2r lo=Vector2r(inf,inf), hi(-inf,-inf);
- Real minD0(inf),maxD0(-inf);
- Real minTheta(inf), maxTheta(-inf);
- std::list<FlatInteraction> intrs;
- // first pass: find extrema for positions and interaction lengths, build interaction list
- FOREACH(const shared_ptr<Interaction>& i, *scene->interactions){
- Dem3DofGeom* ge=dynamic_cast<Dem3DofGeom*>(i->geom.get());
- CpmPhys* ph=dynamic_cast<CpmPhys*>(i->phys.get());
- if(!ge || !ph) continue;
- Real r,h,theta;
- boost::tie(r,h,theta)=Shop::spiralProject(ge->contactPoint,dH_dTheta,axis,periodStart,theta0);
- if(!isnan(thetaMin) && theta<thetaMin) continue;
- if(!isnan(thetaMax) && theta>thetaMax) continue;
- lo=lo.cwiseMin(Vector2r(r,h)); hi=hi.cwiseMax(Vector2r(r,h));
- minD0=min(minD0,ge->refLength); maxD0=max(maxD0,ge->refLength);
- minTheta=min(minTheta,theta); maxTheta=max(maxTheta,theta);
- intrs.push_back(FlatInteraction(r,h,theta,i));
- }
- // create grid, put interactions inside
- Vector2i nCells=Vector2i(max(10,(int)((hi[0]-lo[0])/(2*minD0))),max(10,(int)((hi[1]-lo[1])/(2*minD0))));
- Vector2r hair=1e-2*Vector2r((hi[0]-lo[0])/nCells[0],(hi[1]-lo[1])/nCells[1]); // avoid rounding issue on boundary, enlarge by 1/100 cell size on each side
- grid=shared_ptr<GridContainer<FlatInteraction> >(new GridContainer<FlatInteraction>(lo-hair,hi+hair,nCells));
- FOREACH(const FlatInteraction& fi, intrs){
- grid->add(fi,Vector2r(fi.r,fi.h));
- }
- thetaSpan=maxTheta-minTheta;
- }
- py::list intrsAroundPt(const Vector2r& pt, Real radius){
- py::list ret;
- FOREACH(const Vector2i& v, grid->circleFilter(pt,radius)){
- FOREACH(const FlatInteraction& fi, grid->grid[v[0]][v[1]]){
- if((pow(fi.r-pt[0],2)+pow(fi.h-pt[1],2))>radius*radius) continue; // too far
- ret.append(fi.i);
- }
- }
- return ret;
- }
- // return macroscopic stress around interactions that project around given point and their average omega
- // stresses are rotated around axis back by theta angle
- python::tuple macroAroundPt(const Vector2r& pt, Real radius){
- Matrix3r ss(Matrix3r::Zero());
- Real omegaCumm=0, kappaCumm=0; int nIntr=0;
- FOREACH(const Vector2i& v, grid->circleFilter(pt,radius)){
- FOREACH(const FlatInteraction& fi, grid->grid[v[0]][v[1]]){
- if((pow(fi.r-pt[0],2)+pow(fi.h-pt[1],2))>radius*radius) continue; // too far
- Dem3DofGeom* geom=YADE_CAST<Dem3DofGeom*>(fi.i->geom.get());
- CpmPhys* phys=YADE_CAST<CpmPhys*>(fi.i->phys.get());
- // transformation matrix, to rotate to the plane
- Vector3r ax(Vector3r::Zero()); ax[axis]=1.;
- Quaternionr q(AngleAxisr(fi.theta,ax)); q=q.conjugate();
- Matrix3r TT=q.toRotationMatrix();
- //
- Real d=(geom->se31.position-geom->se32.position).norm(); // current contact length
- const Vector3r& n=TT*geom->normal;
- const Real& A=phys->crossSection;
- const Vector3r& sigmaT=TT*phys->sigmaT;
- const Real& sigmaN=phys->sigmaN;
- for(int i=0; i<3; i++) for(int j=0;j<3; j++){
- ss(i,j)+=d*A*(sigmaN*n[i]*n[j]+.5*(sigmaT[i]*n[j]+sigmaT[j]*n[i]));
- }
- omegaCumm+=phys->omega; kappaCumm+=phys->kappaD;
- nIntr++;
- }
- }
- // divide by approx spatial volume over which we averaged:
- // spiral cylinder with two half-spherical caps at ends
- ss*=1/((4/3.)*Mathr::PI*pow(radius,3)+Mathr::PI*pow(radius,2)*(thetaSpan*pt[0]-2*radius));
- return python::make_tuple(nIntr,ss,omegaCumm/nIntr,kappaCumm/nIntr);
- }
- Vector2r getLo(){ return grid->getLo(); }
- Vector2r getHi(){ return grid->getHi(); }
-
-};
-
-#ifdef YADE_VTK
-
-/* Fastly locate interactions within given distance from a given point. See python docs for details. */
-class InteractionLocator{
- // object doing the work, see http://www.vtk.org/doc/release/5.2/html/a01048.html
- vtkPointLocator *locator;
- // used by locator
- vtkUnstructuredGrid* grid;
- vtkPoints* points;
- // maps vtk's id to Interaction objects
- vector<shared_ptr<Interaction> > intrs;
- // axis-aligned bounds of all interactions
- Vector3r mn,mx;
- // count of interactions we hold
- int cnt;
- public:
- InteractionLocator(){
- // traverse all real interactions in the current simulation
- // add them to points, create grid with those points
- // store shared_ptr's to interactions in intrs separately
- Scene* scene=Omega::instance().getScene().get();
- locator=vtkPointLocator::New();
- points=vtkPoints::New();
- int count=0;
- FOREACH(const shared_ptr<Interaction>& i, *scene->interactions){
- if(!i->isReal()) continue;
- Dem3DofGeom* ge=dynamic_cast<Dem3DofGeom*>(i->geom.get());
- if(!ge) continue;
- const Vector3r& cp(ge->contactPoint);
- int id=points->InsertNextPoint(cp[0],cp[1],cp[2]);
- if(intrs.size()<=(size_t)id){intrs.resize(id+1000);}
- intrs[id]=i;
- count++;
- }
- if(count==0) throw std::runtime_error("Zero interactions when constructing InteractionLocator!");
- double bb[6];
- points->ComputeBounds(); points->GetBounds(bb);
- mn=Vector3r(bb[0],bb[2],bb[4]); mx=Vector3r(bb[1],bb[3],bb[5]);
- cnt=points->GetNumberOfPoints();
-
- grid=vtkUnstructuredGrid::New();
- grid->SetPoints(points);
- locator->SetDataSet(grid);
- locator->BuildLocator();
- }
- // cleanup
- ~InteractionLocator(){ locator->Delete(); points->Delete(); grid->Delete(); }
-
- py::list intrsAroundPt(const Vector3r& pt, Real radius){
- vtkIdList *ids=vtkIdList::New();
- locator->FindPointsWithinRadius(radius,(const double*)(&pt),ids);
- int numIds=ids->GetNumberOfIds();
- py::list ret;
- for(int i=0; i<numIds; i++){
- // LOG_TRACE("Add "<<i<<"th id "<<ids->GetId(i));
- ret.append(intrs[ids->GetId(i)]);
- }
- return ret;
- }
- python::tuple macroAroundPt(const Vector3r& pt, Real radius, Real forceVolume=-1){
- Matrix3r ss(Matrix3r::Zero());
- vtkIdList *ids=vtkIdList::New();
- locator->FindPointsWithinRadius(radius,(const double*)(&pt),ids);
- int numIds=ids->GetNumberOfIds();
- Real omegaCumm=0, kappaCumm=0;
- for(int k=0; k<numIds; k++){
- const shared_ptr<Interaction>& I(intrs[ids->GetId(k)]);
- Dem3DofGeom* geom=YADE_CAST<Dem3DofGeom*>(I->geom.get());
- CpmPhys* phys=YADE_CAST<CpmPhys*>(I->phys.get());
- Real d=(geom->se31.position-geom->se32.position).norm(); // current contact length
- const Vector3r& n=geom->normal;
- const Real& A=phys->crossSection;
- const Vector3r& sigmaT=phys->sigmaT;
- const Real& sigmaN=phys->sigmaN;
- for(int i=0; i<3; i++) for(int j=0;j<3; j++){
- ss(i,j)+=d*A*(sigmaN*n[i]*n[j]+.5*(sigmaT[i]*n[j]+sigmaT[j]*n[i]));
- }
- omegaCumm+=phys->omega; kappaCumm+=phys->kappaD;
- }
- Real volume=(forceVolume>0?forceVolume:(4/3.)*Mathr::PI*pow(radius,3));
- ss*=1/volume;
- return py::make_tuple(ss,omegaCumm/numIds,kappaCumm/numIds);
- }
- py::tuple getBounds(){ return py::make_tuple(mn,mx);}
- int getCnt(){ return cnt; }
-};
-#endif
-
-BOOST_PYTHON_MODULE(_eudoxos){
- YADE_SET_DOCSTRING_OPTS;
- py::def("velocityTowardsAxis",velocityTowardsAxis,velocityTowardsAxis_overloads(py::args("axisPoint","axisDirection","timeToAxis","subtractDist","perturbation")));
- // def("spiralSphereStresses2d",spiralSphereStresses2d,(python::arg("dH_dTheta"),python::arg("axis")=2));
- py::def("particleConfinement",particleConfinement);
- #if 0
- import_array();
- py::def("testNumpy",testNumpy);
- #endif
-#ifdef YADE_VTK
- py::class_<InteractionLocator>("InteractionLocator","Locate all (real) interactions in space by their :yref:`contact point<Dem3DofGeom::contactPoint>`. When constructed, all real interactions are spatially indexed (uses `vtkPointLocator <http://www.vtk.org/doc/release/5.4/html/a01247.html>`_ internally). Use instance methods to use those data. \n\n.. note::\n\tData might become inconsistent with real simulation state if simulation is being run between creation of this object and spatial queries.")
- .def("intrsAroundPt",&InteractionLocator::intrsAroundPt,((python::arg("point"),python::arg("maxDist"))),"Return list of real interactions that are not further than *maxDist* from *point*.")
- .def("macroAroundPt",&InteractionLocator::macroAroundPt,((python::arg("point"),python::arg("maxDist"),python::arg("forceVolume")=-1)),"Return tuple of averaged stress tensor (as Matrix3), average omega and average kappa values. *forceVolume* can be used (if positive) rather than the sphere (with *maxDist* radius) volume for the computation. (This is useful if *point* and *maxDist* encompass empty space that you want to avoid.)")
- .add_property("bounds",&InteractionLocator::getBounds,"Return coordinates of lower and uppoer corner of axis-aligned abounding box of all interactions")
- .add_property("count",&InteractionLocator::getCnt,"Number of interactions held")
- ;
-#endif
- py::class_<HelixInteractionLocator2d>("HelixInteractionLocator2d",
- "Locate all real interactions in 2d plane (reduced by spiral projection from 3d, using ``Shop::spiralProject``, which is the same as :yref:`yade.utils.spiralProject`) using their :yref:`contact points<Dem3DofGeom::contactPoint>`. \n\n.. note::\n\tDo not run simulation while using this object.",
- python::init<Real,int,Real,Real,Real,Real>((python::arg("dH_dTheta"),python::arg("axis")=0,python::arg("periodStart")=NaN,python::arg("theta0")=0,python::arg("thetaMin")=NaN,python::arg("thetaMax")=NaN),":param float dH_dTheta: Spiral inclination, i.e. height increase per 1 radian turn;\n:param int axis: axis of rotation (0=x,1=y,2=z)\n:param float theta: spiral angle at zero height (theta intercept)\n:param float thetaMin: only interactions with $\\theta$≥\\ *thetaMin* will be considered (NaN to deactivate)\n:param float thetaMax: only interactions with $\\theta$≤\\ *thetaMax* will be considered (NaN to deactivate)\n\nSee :yref:`yade.utils.spiralProject`.")
- )
- .def("intrsAroundPt",&HelixInteractionLocator2d::intrsAroundPt,(python::arg("pt2d"),python::arg("radius")),"Return list of interaction objects that are not further from *pt2d* than *radius* in the projection plane")
- .def("macroAroundPt",&HelixInteractionLocator2d::macroAroundPt,(python::arg("pt2d"),python::arg("radius")),"Compute macroscopic stress around given point; the interaction ($n$ and $\\sigma^T$ are rotated to the projection plane by $\\theta$ (as given by :yref:`yade.utils.spiralProject`) first, but no skew is applied). The formula used is\n\n.. math::\n\n \\sigma_{ij}=\\frac{1}{V}\\sum_{IJ}d^{IJ}A^{IJ}\\left[\\sigma^{N,IJ}n_i^{IJ}n_j^{IJ}+\\frac{1}{2}\\left(\\sigma_i^{T,IJ}n_j^{IJ}+\\sigma_j^{T,IJ}n_i^{IJ}\\right)\\right]\n\nwhere the sum is taken over volume $V$ containing interactions $IJ$ between spheres $I$ and $J$;\n\n* $i$, $j$ indices denote Cartesian components of vectors and tensors,\n* $d^{IJ}$ is current distance between spheres $I$ and $J$,\n* $A^{IJ}$ is area of contact $IJ$,\n* $n$ is ($\\theta$-rotated) interaction normal (unit vector pointing from center of $I$ to the center of $J$)\n* $\\sigma^{N,IJ}$ is normal stress (as scalar) in contact $IJ$,\n* $\\sigma^{T,IJ}$ is shear stress in contact $IJ$ in global coordinates and $\\theta$-rotated. \n\nAdditionally, computes average of :yref:`CpmPhys.omega` ($\\bar\\omega$) and :yref:`CpmPhys.kappaD` ($\\bar\\kappa_D$). *N* is the number of interactions in the volume given.\n\n:return: tuple of (*N*, $\\tens{\\sigma}$, $\\bar\\omega$, $\\bar\\kappa_D$).\n")
- .add_property("lo",&HelixInteractionLocator2d::getLo,"Return lower corner of the rectangle containing all interactions.")
- .add_property("hi",&HelixInteractionLocator2d::getHi,"Return upper corner of the rectangle containing all interactions.");
-
-}
=== modified file 'py/_extraDocs.py'
--- py/_extraDocs.py 2012-09-08 01:19:45 +0000
+++ py/_extraDocs.py 2013-08-29 10:30:31 +0000
@@ -198,7 +198,6 @@
:yref:`L6Geom` 6 full
:yref:`ScGeom` 3 emulate local coordinate system
:yref:`ScGeom6D` 6 emulate local coordinate system
-:yref:`Dem3DofGeom` 3 *not supported*
=================== ===== ==================================
Depending on :yref:`IGeom`, 3 ($u_x$, $u_y$, $u_z$) or 6 ($u_x$, $u_y$, $u_z$, $\phi_x$, $\phi_y$, $\phi_z$) degrees of freedom (DoFs) are controlled with LawTester, by prescribing linear and angular velocities of both particles in contact. All DoFs controlled with LawTester are orthogonal (fully decoupled) and are controlled independently.
=== modified file 'py/_utils.cpp'
--- py/_utils.cpp 2013-05-31 13:27:13 +0000
+++ py/_utils.cpp 2013-08-29 10:30:31 +0000
@@ -75,32 +75,33 @@
Real PWaveTimeStep(){return Shop::PWaveTimeStep();};
Real RayleighWaveTimeStep(){return Shop::RayleighWaveTimeStep();};
-Real elasticEnergyInAABB(py::tuple Aabb){
- Vector3r bbMin=py::extract<Vector3r>(Aabb[0])(), bbMax=py::extract<Vector3r>(Aabb[1])();
- shared_ptr<Scene> rb=Omega::instance().getScene();
- Real E=0;
- FOREACH(const shared_ptr<Interaction>&i, *rb->interactions){
- if(!i->phys) continue;
- shared_ptr<NormShearPhys> bc=dynamic_pointer_cast<NormShearPhys>(i->phys); if(!bc) continue;
- shared_ptr<Dem3DofGeom> geom=dynamic_pointer_cast<Dem3DofGeom>(i->geom); if(!geom){LOG_ERROR("NormShearPhys contact doesn't have Dem3DofGeom associated?!"); continue;}
- const shared_ptr<Body>& b1=Body::byId(i->getId1(),rb), b2=Body::byId(i->getId2(),rb);
- bool isIn1=isInBB(b1->state->pos,bbMin,bbMax), isIn2=isInBB(b2->state->pos,bbMin,bbMax);
- if(!isIn1 && !isIn2) continue;
- LOG_DEBUG("Interaction #"<<i->getId1()<<"--#"<<i->getId2());
- Real weight=1.;
- if((!isIn1 && isIn2) || (isIn1 && !isIn2)){
- //shared_ptr<Body> bIn=isIn1?b1:b2, bOut=isIn2?b2:b1;
- Vector3r vIn=(isIn1?b1:b2)->state->pos, vOut=(isIn2?b1:b2)->state->pos;
- #define _WEIGHT_COMPONENT(axis) if(vOut[axis]<bbMin[axis]) weight=min(weight,abs((vOut[axis]-bbMin[axis])/(vOut[axis]-vIn[axis]))); else if(vOut[axis]>bbMax[axis]) weight=min(weight,abs((vOut[axis]-bbMax[axis])/(vOut[axis]-vIn[axis])));
- _WEIGHT_COMPONENT(0); _WEIGHT_COMPONENT(1); _WEIGHT_COMPONENT(2);
- assert(weight>=0 && weight<=1);
- //cerr<<"Interaction crosses Aabb boundary, weight is "<<weight<<endl;
- //LOG_DEBUG("Interaction crosses Aabb boundary, weight is "<<weight);
- } else {assert(isIn1 && isIn2); /* cerr<<"Interaction inside, weight is "<<weight<<endl;*/ /*LOG_DEBUG("Interaction inside, weight is "<<weight);*/}
- E+=geom->refLength*weight*(.5*bc->kn*pow(geom->strainN(),2)+.5*bc->ks*pow(geom->strainT().norm(),2));
- }
- return E;
-}
+// FIXME: rewrite for ScGeom or remove
+// Real elasticEnergyInAABB(py::tuple Aabb){
+// Vector3r bbMin=py::extract<Vector3r>(Aabb[0])(), bbMax=py::extract<Vector3r>(Aabb[1])();
+// shared_ptr<Scene> rb=Omega::instance().getScene();
+// Real E=0;
+// FOREACH(const shared_ptr<Interaction>&i, *rb->interactions){
+// if(!i->phys) continue;
+// shared_ptr<NormShearPhys> bc=dynamic_pointer_cast<NormShearPhys>(i->phys); if(!bc) continue;
+// shared_ptr<Dem3DofGeom> geom=dynamic_pointer_cast<Dem3DofGeom>(i->geom); if(!geom){LOG_ERROR("NormShearPhys contact doesn't have Dem3DofGeom associated?!"); continue;}
+// const shared_ptr<Body>& b1=Body::byId(i->getId1(),rb), b2=Body::byId(i->getId2(),rb);
+// bool isIn1=isInBB(b1->state->pos,bbMin,bbMax), isIn2=isInBB(b2->state->pos,bbMin,bbMax);
+// if(!isIn1 && !isIn2) continue;
+// LOG_DEBUG("Interaction #"<<i->getId1()<<"--#"<<i->getId2());
+// Real weight=1.;
+// if((!isIn1 && isIn2) || (isIn1 && !isIn2)){
+// //shared_ptr<Body> bIn=isIn1?b1:b2, bOut=isIn2?b2:b1;
+// Vector3r vIn=(isIn1?b1:b2)->state->pos, vOut=(isIn2?b1:b2)->state->pos;
+// #define _WEIGHT_COMPONENT(axis) if(vOut[axis]<bbMin[axis]) weight=min(weight,abs((vOut[axis]-bbMin[axis])/(vOut[axis]-vIn[axis]))); else if(vOut[axis]>bbMax[axis]) weight=min(weight,abs((vOut[axis]-bbMax[axis])/(vOut[axis]-vIn[axis])));
+// _WEIGHT_COMPONENT(0); _WEIGHT_COMPONENT(1); _WEIGHT_COMPONENT(2);
+// assert(weight>=0 && weight<=1);
+// //cerr<<"Interaction crosses Aabb boundary, weight is "<<weight<<endl;
+// //LOG_DEBUG("Interaction crosses Aabb boundary, weight is "<<weight);
+// } else {assert(isIn1 && isIn2); /* cerr<<"Interaction inside, weight is "<<weight<<endl;*/ /*LOG_DEBUG("Interaction inside, weight is "<<weight);*/}
+// E+=geom->refLength*weight*(.5*bc->kn*pow(geom->strainN(),2)+.5*bc->ks*pow(geom->strainT().norm(),2));
+// }
+// return E;
+// }
/* return histogram ([bin1Min,bin2Min,…],[value1,value2,…]) from projections of interactions
* to the plane perpendicular to axis∈[0,1,2]; the number of bins can be specified and they cover
@@ -353,34 +354,35 @@
upper part" (lower and upper parts with respect to the plane's normal).
(This could be easily extended to return sum of only normal forces or only of shear forces.)
+ // FIXME: adapt to ScGeom or remove
*/
-Vector3r forcesOnPlane(const Vector3r& planePt, const Vector3r& normal){
- Vector3r ret(Vector3r::Zero());
- Scene* scene=Omega::instance().getScene().get();
- FOREACH(const shared_ptr<Interaction>&I, *scene->interactions){
- if(!I->isReal()) continue;
- NormShearPhys* nsi=dynamic_cast<NormShearPhys*>(I->phys.get());
- if(!nsi) continue;
- Vector3r pos1,pos2;
- Dem3DofGeom* d3dg=dynamic_cast<Dem3DofGeom*>(I->geom.get()); // Dem3DofGeom has copy of se3 in itself, otherwise we have to look up the bodies
- if(d3dg){ pos1=d3dg->se31.position; pos2=d3dg->se32.position; }
- else{ pos1=Body::byId(I->getId1(),scene)->state->pos; pos2=Body::byId(I->getId2(),scene)->state->pos; }
- Real dot1=(pos1-planePt).dot(normal), dot2=(pos2-planePt).dot(normal);
- if(dot1*dot2>0) continue; // both (centers of) bodies are on the same side of the plane=> this interaction has to be disregarded
- // if pt1 is on the negative plane side, d3dg->normal.Dot(normal)>0, the force is well oriented;
- // otherwise, reverse its contribution. So that we return finally
- // Sum [ ( normal(plane) dot normal(interaction= from 1 to 2) ) "nsi->force" ]
- ret+=(dot1<0.?1.:-1.)*(nsi->normalForce+nsi->shearForce);
- }
- return ret;
-}
+// Vector3r forcesOnPlane(const Vector3r& planePt, const Vector3r& normal){
+// Vector3r ret(Vector3r::Zero());
+// Scene* scene=Omega::instance().getScene().get();
+// FOREACH(const shared_ptr<Interaction>&I, *scene->interactions){
+// if(!I->isReal()) continue;
+// NormShearPhys* nsi=dynamic_cast<NormShearPhys*>(I->phys.get());
+// if(!nsi) continue;
+// Vector3r pos1,pos2;
+// Dem3DofGeom* d3dg=dynamic_cast<Dem3DofGeom*>(I->geom.get()); // Dem3DofGeom has copy of se3 in itself, otherwise we have to look up the bodies
+// if(d3dg){ pos1=d3dg->se31.position; pos2=d3dg->se32.position; }
+// else{ pos1=Body::byId(I->getId1(),scene)->state->pos; pos2=Body::byId(I->getId2(),scene)->state->pos; }
+// Real dot1=(pos1-planePt).dot(normal), dot2=(pos2-planePt).dot(normal);
+// if(dot1*dot2>0) continue; // both (centers of) bodies are on the same side of the plane=> this interaction has to be disregarded
+// // if pt1 is on the negative plane side, d3dg->normal.Dot(normal)>0, the force is well oriented;
+// // otherwise, reverse its contribution. So that we return finally
+// // Sum [ ( normal(plane) dot normal(interaction= from 1 to 2) ) "nsi->force" ]
+// ret+=(dot1<0.?1.:-1.)*(nsi->normalForce+nsi->shearForce);
+// }
+// return ret;
+// }
/* Less general than forcesOnPlane, computes force on plane perpendicular to axis, passing through coordinate coord. */
-Vector3r forcesOnCoordPlane(Real coord, int axis){
- Vector3r planePt(Vector3r::Zero()); planePt[axis]=coord;
- Vector3r normal(Vector3r::Zero()); normal[axis]=1;
- return forcesOnPlane(planePt,normal);
-}
+// /*Vector3r forcesOnCoordPlane(Real coord, int axis){
+// Vector3r planePt(Vector3r::Zero()); planePt[axis]=coord;
+// Vector3r normal(Vector3r::Zero()); normal[axis]=1;
+// return forcesOnPlane(planePt,normal);
+// }*/
py::tuple spiralProject(const Vector3r& pt, Real dH_dTheta, int axis=2, Real periodStart=std::numeric_limits<Real>::quiet_NaN(), Real theta0=0){
@@ -507,15 +509,15 @@
py::def("setRefSe3",setRefSe3,"Set reference :yref:`positions<State::refPos>` and :yref:`orientations<State::refOri>` of all :yref:`bodies<Body>` equal to their current :yref:`positions<State::pos>` and :yref:`orientations<State::ori>`.");
py::def("interactionAnglesHistogram",interactionAnglesHistogram,interactionAnglesHistogram_overloads(py::args("axis","mask","bins","aabb")));
py::def("bodyNumInteractionsHistogram",bodyNumInteractionsHistogram,bodyNumInteractionsHistogram_overloads(py::args("aabb")));
- py::def("elasticEnergy",elasticEnergyInAABB);
+// py::def("elasticEnergy",elasticEnergyInAABB);
py::def("inscribedCircleCenter",inscribedCircleCenter,(py::arg("v1"),py::arg("v2"),py::arg("v3")),"Return center of inscribed circle for triangle given by its vertices *v1*, *v2*, *v3*.");
py::def("unbalancedForce",&Shop__unbalancedForce,(py::args("useMaxForce")=false),"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.");
py::def("kineticEnergy",Shop__kineticEnergy,(py::args("findMaxId")=false),"Compute overall kinetic energy of the simulation as\n\n.. math:: \\sum\\frac{1}{2}\\left(m_i\\vec{v}_i^2+\\vec{\\omega}(\\mat{I}\\vec{\\omega}^T)\\right).\n\nFor :yref:`aspherical<Body.aspherical>` bodies, the inertia tensor $\\mat{I}$ is transformed to global frame, before multiplied by $\\vec{\\omega}$, therefore the value should be accurate.\n");
py::def("sumForces",sumForces,(py::arg("ids"),py::arg("direction")),"Return summary force on bodies with given *ids*, projected on the *direction* vector.");
py::def("sumTorques",sumTorques,(py::arg("ids"),py::arg("axis"),py::arg("axisPt")),"Sum forces and torques on bodies given in *ids* with respect to axis specified by a point *axisPt* and its direction *axis*.");
py::def("sumFacetNormalForces",sumFacetNormalForces,(py::arg("ids"),py::arg("axis")=-1),"Sum force magnitudes on given bodies (must have :yref:`shape<Body.shape>` of the :yref:`Facet` type), considering only part of forces perpendicular to each :yref:`facet's<Facet>` face; if *axis* has positive value, then the specified axis (0=x, 1=y, 2=z) will be used instead of facet's normals.");
- py::def("forcesOnPlane",forcesOnPlane,(py::arg("planePt"),py::arg("normal")),"Find all interactions deriving from :yref:`NormShearPhys` that cross given plane and sum forces (both normal and shear) on them.\n\n:param Vector3 planePt: a point on the plane\n:param Vector3 normal: plane normal (will be normalized).\n");
- py::def("forcesOnCoordPlane",forcesOnCoordPlane);
+// py::def("forcesOnPlane",forcesOnPlane,(py::arg("planePt"),py::arg("normal")),"Find all interactions deriving from :yref:`NormShearPhys` that cross given plane and sum forces (both normal and shear) on them.\n\n:param Vector3 planePt: a point on the plane\n:param Vector3 normal: plane normal (will be normalized).\n");
+// py::def("forcesOnCoordPlane",forcesOnCoordPlane);
py::def("totalForceInVolume",Shop__totalForceInVolume,"Return summed forces on all interactions and average isotropic stiffness, as tuple (Vector3,float)");
py::def("createInteraction",Shop__createExplicitInteraction,(py::arg("id1"),py::arg("id2")),"Create interaction between given bodies by hand.\n\nCurrent engines are searched for :yref:`IGeomDispatcher` and :yref:`IPhysDispatcher` (might be both hidden in :yref:`InteractionLoop`). Geometry is created using ``force`` parameter of the :yref:`geometry dispatcher<IGeomDispatcher>`, wherefore the interaction will exist even if bodies do not spatially overlap and the functor would return ``false`` under normal circumstances. \n\n.. warning:: This function will very likely behave incorrectly for periodic simulations (though it could be extended it to handle it farily easily).");
py::def("spiralProject",spiralProject,(py::arg("pt"),py::arg("dH_dTheta"),py::arg("axis")=2,py::arg("periodStart")=std::numeric_limits<Real>::quiet_NaN(),py::arg("theta0")=0));
=== removed file 'py/eudoxos.py'
--- py/eudoxos.py 2013-04-24 19:49:00 +0000
+++ py/eudoxos.py 1970-01-01 00:00:00 +0000
@@ -1,311 +0,0 @@
-# encoding: utf-8
-# 2008 © Václav Šmilauer <eudoxos@xxxxxxxx>
-#
-# I doubt there functions will be useful for anyone besides me.
-#
-"""Miscillaneous functions that are not believed to be generally usable,
-therefore kept in my "private" module here.
-
-They comprise notably oofem export and various CPM-related functions.
-"""
-
-from yade.wrapper import *
-from math import *
-from yade._eudoxos import * ## c++ implementations
-
-
-class IntrSmooth3d():
- r"""Return spatially weigted gaussian average of arbitrary quantity defined on interactions.
-
- At construction time, all real interactions are put inside spatial grid, permitting fast search for
- points in neighbourhood defined by distance.
-
- Parameters for the distribution are standard deviation :math:`\sigma` and relative cutoff distance
- *relThreshold* (3 by default) which will discard points farther than *relThreshold* :math:`\times \sigma`.
-
- Given central point :math:`p_0`, points are weighted by gaussian function
-
- .. math::
-
- \rho(p_0,p)=\frac{1}{\sigma\sqrt{2\pi}}\exp\left(\frac{-||p_0-p||^2}{2\sigma^2}\right)
-
- To get the averaged value, simply call the instance, passing central point and callable object which received interaction object and returns the desired quantity:
-
- >>> O.reset()
- >>> from yade import utils
- >>> O.bodies.append([utils.sphere((0,0,0),1),utils.sphere((0,0,1.9),1)])
- [0, 1]
- >>> O.engines=[InteractionLoop([Ig2_Sphere_Sphere_ScGeom(),],[Ip2_FrictMat_FrictMat_FrictPhys()],[])]
- >>> utils.createInteraction(0,1) #doctest: +ELLIPSIS
- <Interaction instance at 0x...>
-
- >> is3d=IntrSmooth3d(0.003)
- >> is3d((0,0,0),lambda i: i.phys.normalForce)
- Vector3(0,0,0)
-
- """
- def __init__(self,stDev):
- self.locator=InteractionLocator()
- self.stDev=stDev
- self.relThreshold=3.
- self.sqrt2pi=sqrt(2*pi)
- import yade.config
- if not 'vtk' in yade.config.features: raise RuntimeError("IntrSmooth3d is only function with VTK-enabled builds.")
- def _ptpt2weight(self,pt0,pt1):
- distSq=(pt0-pt1).SquaredLength()
- return (1./(self.stDev*self.sqrt2pi))*exp(-distSq/(2*self.stDev*self.stDev))
- def bounds(self): return self.locator.bounds()
- def count(self): return self.locator.count()
- def __call__(self,pt,extr):
- intrs=self.locator.intrsAroundPt(pt,self.stDev*self.relThreshold)
- if len(intrs)==0: return float('nan')
- weights,val=0.,0.
- for i in intrs:
- weight=self._ptpt2weight(pt,i.geom.contactPoint)
- val+=weight*extr(i)
- weights+=weight
- #print i,weight,extr(i)
- return val/weights
-
-
-def estimateStress(strain,cutoff=0.):
- """Use summed stored energy in contacts to compute macroscopic stress over the same volume, provided known strain."""
- # E=(1/2)σεAl # global stored energy
- # σ=EE/(.5εAl)=EE/(.5εV)
- from yade import utils
- dim=utils.aabbDim(cutoff,centers=False)
- return utils.elasticEnergy(utils.aabbExtrema(cutoff))/(.5*strain*dim[0]*dim[1]*dim[2])
-
-def estimatePoissonYoung(principalAxis,stress=0,plot=False,cutoff=0.):
- """Estimate Poisson's ration given the "principal" axis of straining.
- For every base direction, homogenized strain is computed
- (slope in linear regression on discrete function particle coordinate →
- → particle displacement in the same direction as returned by
- utils.coordsAndDisplacements) and, (if axis '0' is the strained
- axis) the poisson's ratio is given as -½(ε₁+ε₂)/ε₀.
-
- Young's modulus is computed as σ/ε₀; if stress σ is not given (default 0),
- the result is 0.
-
- cutoff, if > 0., will take only smaller part (centered) or the specimen into account
- """
- dd=[] # storage for linear regression parameters
- import pylab,numpy
- try:
- import stats
- except ImportError:
- raise ImportError("Unable to import stats; install the python-stats package.")
- from yade import utils
- if cutoff>0: cut=utils.fractionalBox(fraction=1-cutoff)
- for axis in [0,1,2]:
- if cutoff>0:
- w,dw=utils.coordsAndDisplacements(axis,Aabb=cut)
- else:
- w,dw=utils.coordsAndDisplacements(axis)
- l,ll=stats.linregress(w,dw)[0:2] # use only tangent and section
- dd.append((l,ll,min(w),max(w)))
- if plot: pylab.plot(w,dw,'.',label=r'$\Delta %s(%s)$'%('xyz'[axis],'xyz'[axis]))
- if plot:
- for axis in [0,1,2]:
- dist=dd[axis][-1]-dd[axis][-2]
- c=numpy.linspace(dd[axis][-2]-.2*dist,dd[axis][-1]+.2*dist)
- d=[dd[axis][0]*cc+dd[axis][1] for cc in c]
- pylab.plot(c,d,label=r'$\widehat{\Delta %s}(%s)$'%('xyz'[axis],'xyz'[axis]))
- pylab.legend(loc='upper left')
- pylab.xlabel(r'$x,\;y,\;z$')
- pylab.ylabel(r'$\Delta x,\;\Delta y,\; \Delta z$')
- pylab.show()
- otherAxes=(principalAxis+1)%3,(principalAxis+2)%3
- avgTransHomogenizedStrain=.5*(dd[otherAxes[0]][0]+dd[otherAxes[1]][0])
- principalHomogenizedStrain=dd[principalAxis][0]
- return -avgTransHomogenizedStrain/principalHomogenizedStrain,stress/principalHomogenizedStrain
-
-
-def oofemTextExport(fName):
- """Export simulation data in text format
-
- The format is line-oriented as follows::
-
- E G # elastic material parameters
- epsCrackOnset relDuctility xiShear transStrainCoeff # tensile parameters; epsFr=epsCrackOnset*relDuctility
- cohesionT tanPhi # shear parameters
- number_of_spheres number_of_links
- id x y z r boundary # spheres; boundary: -1 negative, 0 none, 1 positive
- …
- id1 id2 cp_x cp_y cp_z A # interactions; cp = contact point; A = cross-section
-
- """
- material,bodies,interactions=[],[],[]
-
- f=open(fName,'w') # fail early on I/O problem
-
- ph=O.interactions.nth(0).phys # some params are the same everywhere
- material.append("%g %g"%(ph.E,ph.G))
- material.append("%g %g %g %g"%(ph.epsCrackOnset,ph.epsFracture,1e50,0.0))
- material.append("%g %g"%(ph.undamagedCohesion,ph.tanFrictionAngle))
-
- # need strainer for getting bodies in positive/negative boundary
- strainers=[e for e in O.engines if e.name=='UniaxialStrainer']
- if len(strainers)>0: strainer=strainers[0]
- else: strainer=None
-
- for b in O.bodies:
- if not b.shape or b.shape.name!='Sphere': continue
- if strainer and b.id in strainer.negIds: boundary=-1
- elif strainer and b.id in strainer.posIds: boundary=1
- else: boundary=0
- bodies.append("%d %g %g %g %g %d"%(b.id,b.state.pos[0],b.state.pos[1],b.state.pos[2],b.shape.radius,boundary))
-
- for i in O.interactions:
- cp=i.geom.contactPoint
- interactions.append("%d %d %g %g %g %g"%(i.id1,i.id2,cp[0],cp[1],cp[2],i.phys.crossSection))
-
- f.write('\n'.join(material+["%d %d"%(len(bodies),len(interactions))]+bodies+interactions))
- f.close()
-
-def oofemPrescribedDisplacementsExport(fileName):
- f=open(fileName,'w')
- f.write(fileName+'.out\n'+'''All Yade displacements prescribed as boundary conditions
-NonLinearStatic nsteps 2 contextOutputStep 1 rtolv 1.e-2 stiffMode 2 maxiter 50 controllmode 1 nmodules 0
-domain 3dshell
-OutputManager tstep_all dofman_all element_all
-''')
- inters=[i for i in O.interactions if (i.geom and i.phys)]
- f.write("ndofman %d nelem %d ncrosssect 1 nmat 1 nbc %d nic 0 nltf 1 nbarrier 0\n"%(len(O.bodies),len(inters),len(O.bodies)*6))
- bcMax=0; bcMap={}
- for b in O.bodies:
- mf=' '.join([str(a) for a in list(O.actions.f(b.id))+list(O.actions.m(b.id))])
- f.write("## #%d: forces %s\n"%(b.id+1,mf))
- f.write("Particle %d coords 3 %.15e %.15e %.15e rad %g"%(b.id+1,b.phys['se3'][0],b.phys['se3'][1],b.phys['se3'][2],b.mold['radius']))
- bcMap[b.id]=tuple([bcMax+i for i in [1,2,3,4,5,6]])
- bcMax+=6
- f.write(' bc '+' '.join([str(i) for i in bcMap[b.id]])+'\n')
- for j,i in enumerate(inters):
- epsTNorm=sqrt(sum([e**2 for e in i.phys['epsT']]))
- epsT='epsT [ %g %g %g ] %g'%(i.phys['epsT'][0],i.phys['epsT'][1],i.phys['epsT'][2],epsTNorm)
- en=i.phys['epsN']; n=i.geom['normal']
- epsN='epsN [ %g %g %g ] %g'%(en*n[0],en*n[1],en*n[2],en)
- Fn='Fn [ %g %g %g ] %g'%(i.phys['normalForce'][0],i.phys['normalForce'][1],i.phys['normalForce'][2],i.phys['Fn'])
- Fs='Fs [ %lf %lf %lf ] %lf'%(i.phys['shearForce'][0],i.phys['shearForce'][1],i.phys['shearForce'][2],sqrt(sum([fs**2 for fs in i.phys['shearForce']])))
- f.write('## #%d #%d: %s %s %s %s\n'%(i.id1+1,i.id2+1,epsN,epsT,Fn,Fs))
- f.write('CohSur3d %d nodes 2 %d %d mat 1 crossSect 1 area %g\n'%(j+1,i.id1+1,i.id2+1,i.phys['crossSection']))
- # crosssection
- f.write("SimpleCS 1 thick 1.0 width 1.0\n")
- # material
- ph=inters[0].phys
- f.write("CohInt 1 kn %g ks %g e0 %g ef %g c 0. ksi %g coh %g tanphi %g d 1.0 conf 0.0 maxdist 0.0\n"%(ph['E'],ph['G'],ph['epsCrackOnset'],ph['epsFracture'],ph['xiShear'],ph['undamagedCohesion'],ph['tanFrictionAngle']))
- # boundary conditions
- for b in O.bodies:
- displ=b.phys.displ; rot=b.phys.rot
- dofs=[displ[0],displ[1],displ[2],rot[0],rot[1],rot[2]]
- f.write('# particle %d\n'%b.id)
- for dof in range(6):
- f.write('BoundaryCondition %d loadTimeFunction 1 prescribedvalue %.15e\n'%(bcMap[b.id][dof],dofs[dof]))
- #f.write('PiecewiseLinFunction 1 npoints 3 t 3 0. 10. 1000. f(t) 3 0. 10. 1000.\n')
- f.write('ConstantFunction 1 f(t) 1.0\n')
-
-
-
-
-def oofemDirectExport(fileBase,title=None,negIds=[],posIds=[]):
- from yade.wrapper import Omega
- material,bodies,interactions=[],[],[]
- o=Omega()
- strainers=[e for e in o.engines if e.name=='UniaxialStrainer']
- if len(strainers)>0:
- strainer=strainers[0]
- posIds,negIds=strainer.posIds,strainer.negIds
- else: strainer=None
- f=open(fileBase+'.in','w')
- # header
- f.write(fileBase+'.out\n')
- f.write((title if title else 'Yade simulation for '+fileBase)+'\n')
- f.write("NonLinearStatic nsteps 2 contextOutputStep 1 rtolv 1.e-2 stiffMode 2 maxiter 50 controllmode 1 nmodules 0\n")
- f.write("domain 3dShell\n")
- f.write("OutputManager tstep_all dofman_all element_all\n")
- inters=[i for i in o.interactions if (i.geom and i.phys)]
- f.write("ndofman %d nelem %d ncrosssect 1 nmat 1 nbc 2 nic 0 nltf 1 nbarrier 0\n"%(len(o.bodies)+2,len(inters)))
- # elements
- f.write("Node 1 coords 3 0.0 0.0 0.0 bc 6 1 1 1 1 1 1\n")
- f.write("Node 2 coords 3 0.0 0.0 0.0 bc 6 1 2 1 1 1 1\n")
- for b in o.bodies:
- f.write("Particle %d coords 3 %g %g %g rad %g"%(b.id+3,b.state.refPos[0],b.state.refPos[1],b.state.refPos[2],b.shape.radius))
- if b.id in negIds: f.write(" dofType 6 1 1 1 1 1 1 masterMask 6 0 1 0 0 0 0 ")
- elif b.id in posIds: f.write(" dofType 6 1 1 1 1 1 1 masterMask 6 0 2 0 0 0 0 0")
- f.write('\n')
- j=1
- for i in inters:
- f.write('CohSur3d %d nodes 2 %d %d mat 1 crossSect 1 area %g\n'%(j,i.id1+3,i.id2+3,i.phys.crossSection))
- j+=1
- # crosssection
- f.write("SimpleCS 1 thick 1.0 width 1.0\n")
- # material
- ph=inters[0].phys
- f.write("CohInt 1 kn %g ks %g e0 %g ef %g c 0. ksi %g coh %g tanphi %g damchartime %g damrateexp %g plchartime %g plrateexp %g d 1.0\n"%(ph.E,ph.G,ph.epsCrackOnset,ph.epsFracture,0.0,ph.undamagedCohesion,ph.tanFrictionAngle,ph.dmgTau,ph.dmgRateExp,ph.plTau,ph.plRateExp))
- # boundary conditions
- f.write('BoundaryCondition 1 loadTimeFunction 1 prescribedvalue 0.0\n')
- f.write('BoundaryCondition 2 loadTimeFunction 1 prescribedvalue 1.e-4\n')
- f.write('PiecewiseLinFunction 1 npoints 3 t 3 0. 10. 1000. f(t) 3 0. 10. 1000.\n')
-
-
-def displacementsInteractionsExport(fName):
- f=open(fName,'w')
- print "Writing body displacements and interaction strains."
- o=Omega()
- for b in o.bodies:
- x0,y0,z0=b.phys['refSe3'][0:3]; x,y,z=b.phys.pos
- rx,ry,rz,rr=b.phys['se3'][3:7]
- f.write('%d xyz [ %g %g %g ] dxyz [ %g %g %g ] rxyz [ %g %g %g ] \n'%(b.id,x0,y0,z0,x-x0,y-y0,z-z0,rr*rx,rr*ry,rr*rz))
- f.write('\n')
- for i in o.interactions:
- if not i['isReal']:continue
- epsTNorm=sqrt(sum([e**2 for e in i.phys['epsT']]))
- epsT='epsT [ %g %g %g ] %g'%(i.phys['epsT'][0],i.phys['epsT'][1],i.phys['epsT'][2],epsTNorm)
- en=i.phys['epsN']; n=i.geom['normal']
- epsN='epsN [ %g %g %g ] %g'%(en*n[0],en*n[1],en*n[2],en)
- Fn='Fn [ %g %g %g ] %g'%(i.phys['normalForce'][0],i.phys['normalForce'][1],i.phys['normalForce'][2],i.phys['Fn'])
- Fs='Fs [ %lf %lf %lf ] %lf'%(i.phys['shearForce'][0],i.phys['shearForce'][1],i.phys['shearForce'][2],sqrt(sum([fs**2 for fs in i.phys['shearForce']])))
- f.write('%d %d %s %s %s %s\n'%(i.id1,i.id2,epsN,epsT,Fn,Fs))
- # f.write('%d %d %g %g %g %g %g\n'%(i.id1,i.id2,i.phys['epsN'],i.phys['epsT'][0],i.phys['epsT'][1],i.phys['epsT'][2],epsTNorm))
- f.close()
-
-
-
-
-
-def eliminateJumps(eps,sigma,numSteep=10,gapWidth=5,movWd=40):
- from matplotlib.mlab import movavg
- from numpy import diff,abs
- import numpy
- # get histogram of 'derivatives'
- ds=abs(diff(sigma))
- n,bins=numpy.histogram(ds)
- i=1; sum=0
- # numSteep steepest pieces will be discarded
- while sum<numSteep:
- #print n[-i],bins[-i]
- sum+=n[-i]; i+=1
- #print n[-i],bins[-i]
- threshold=bins[-i]
- # old algo: replace with nan's
- ##rEps,rSigma=eps[:],sigma[:]; nan=float('nan')
- ##indices=where(ds>threshold)[0]
- ##for i in indices:
- ## for ii in range(max(0,i-gapWidth),min(len(rEps),i+gapWidth+1)): rEps[ii]=rSigma[ii]=nan
-
- ## doesn't work with older numpy (?)
- # indices1=where(ds>threshold)[0]
- indices1=[]
- for i in range(len(ds)):
- if ds[i]>threshold: indices1.append(i)
- indices=[]
- for i in indices1:
- for ii in range(i-gapWidth,i+gapWidth+1): indices.append(ii)
- #print indices1, indices
- rEps=[eps[i] for i in range(0,len(eps)) if i not in indices]
- rSigma=[sigma[i] for i in range(0,len(sigma)) if i not in indices]
- # apply moving average to the result
- rSigma=movavg(rSigma,movWd)
- rEps=rEps[movWd/2:-movWd/2+1]
- return rEps,rSigma.flatten().tolist()
-
=== modified file 'py/tests/__init__.py'
--- py/tests/__init__.py 2012-04-13 16:27:00 +0000
+++ py/tests/__init__.py 2013-08-29 10:30:31 +0000
@@ -7,8 +7,8 @@
allTests=['wrapper','core','pbc','clump','cohesive-chain']
# all yade modules (ugly...)
-import yade.eudoxos,yade.export,yade.linterpolation,yade.pack,yade.plot,yade.post2d,yade.timing,yade.utils,yade.ymport,yade.geom
-allModules=(yade.eudoxos,yade.export,yade.linterpolation,yade.pack,yade.plot,yade.post2d,yade.timing,yade.utils,yade.ymport,yade.geom)
+import yade.export,yade.linterpolation,yade.pack,yade.plot,yade.post2d,yade.timing,yade.utils,yade.ymport,yade.geom
+allModules=(yade.export,yade.linterpolation,yade.pack,yade.plot,yade.post2d,yade.timing,yade.utils,yade.ymport,yade.geom)
try:
import yade.qt
allModules+=(yade.qt,)