← Back to team overview

yade-dev team mailing list archive

[Branch ~yade-dev/yade/trunk] Rev 1936: 1. May fixes for errors found when running larger simulation.

 

------------------------------------------------------------
revno: 1936
committer: Václav Šmilauer <eudoxos@xxxxxxxx>
branch nick: trunk
timestamp: Sun 2010-01-03 21:30:24 +0100
message:
  1. May fixes for errors found when running larger simulation.
  2. Move material properties from Ip2_CpmMat_CpmMat_CpmPhys to CpmMat itself.
  3. Some reverts in PeriIsoCompressor (log strain and usage of refSize)
  
  @Bruno: fell free to undo my diffs on PeriIsoCompressor, I am aware exact implementation should be matter of ongoing discussion (better on the list than by comments in the code perhaps).
added:
  lib/pyutil/gil.cpp
modified:
  examples/concrete/uniax-post.py
  examples/concrete/uniax.py
  lib/SConscript
  lib/pyutil/gil.hpp
  pkg/common/Engine/Dispatcher/InteractionDispatchers.cpp
  pkg/common/Engine/GlobalEngine/SpheresFactory.cpp
  pkg/common/Engine/ParallelEngine.cpp
  pkg/common/Engine/PartialEngine/MomentEngine.cpp
  pkg/common/Engine/PartialEngine/MomentEngine.hpp
  pkg/common/Engine/PartialEngine/RotationEngine.cpp
  pkg/common/Engine/PartialEngine/Se3Interpolator.cpp
  pkg/dem/DataClass/Clump.cpp
  pkg/dem/Engine/GlobalEngine/PeriIsoCompressor.cpp
  pkg/dem/meta/ConcretePM.cpp
  pkg/dem/meta/ConcretePM.hpp
  py/pack.py
  py/post2d.py
  py/system.py
  py/utils.py
  py/yadeWrapper/yadeWrapper.cpp


--
lp:yade
https://code.launchpad.net/~yade-dev/yade/trunk

Your team Yade developers is subscribed to branch lp:yade.
To unsubscribe from this branch go to https://code.launchpad.net/~yade-dev/yade/trunk/+edit-subscription.
=== modified file 'examples/concrete/uniax-post.py'
--- examples/concrete/uniax-post.py	2009-11-24 17:03:29 +0000
+++ examples/concrete/uniax-post.py	2010-01-03 20:30:24 +0000
@@ -19,18 +19,29 @@
 pylab.figure()
 # plot raw damage
 post2d.plot(post2d.data(extractDmg,flattener))
+pylab.suptitle('damage')
 
 # plot smooth damage into new figure
 pylab.figure(); ax,map=post2d.plot(post2d.data(extractDmg,flattener,stDev=2e-3))
-
+pylab.suptitle('smooth damage')
 # show color scale
 pylab.colorbar(map,orientation='horizontal')
 
+# shear stress
+pylab.figure()
+post2d.plot(post2d.data(lambda b: b.state['sigma'],flattener))
+pylab.suptitle('sigma')
+pylab.figure()
+post2d.plot(post2d.data(lambda b: b.state['tau'],flattener,stDev=2e-3))
+pylab.suptitle('smooth tau (in grid)')
+
 # raw velocity (vector field) plot
 pylab.figure(); post2d.plot(post2d.data(extractVelocity,flattener))
+pylab.suptitle('velocity')
 
 # smooth velocity plot; data are sampled at regular grid
 pylab.figure(); ax,map=post2d.plot(post2d.data(extractVelocity,flattener,stDev=1e-3))
+pylab.suptitle('smooth velocity')
 # save last (current) figure to file
 pylab.gcf().savefig('/tmp/foo.png') 
 

=== modified file 'examples/concrete/uniax.py'
--- examples/concrete/uniax.py	2009-12-25 14:46:48 +0000
+++ examples/concrete/uniax.py	2010-01-03 20:30:24 +0000
@@ -64,7 +64,8 @@
 # make geom; the dimensions are hard-coded here; could be in param table if desired
 # z-oriented hyperboloid, length 20cm, diameter 10cm, skirt 8cm
 # using spheres 7mm of diameter
-concreteId=O.materials.append(CpmMat(young=young,frictionAngle=frictionAngle,poisson=poisson,density=4800))
+concreteId=O.materials.append(CpmMat(young=young,frictionAngle=frictionAngle,poisson=poisson,density=4800,sigmaT=sigmaT,relDuctility=relDuctility,epsCrackOnset=epsCrackOnset,G_over_E=G_over_E,isoPrestress=isoPrestress))
+
 spheres=pack.randomDensePack(pack.inHyperboloid((0,0,-.5*specimenLength),(0,0,.5*specimenLength),.25*specimenLength,.17*specimenLength),spheresInCell=2000,radius=sphereRadius,memoizeDb='/tmp/triaxPackCache.sqlite',material=concreteId)
 O.bodies.append(spheres)
 bb=utils.uniaxialTestFeatures()
@@ -81,8 +82,8 @@
 	BoundDispatcher([Bo1_Sphere_Aabb(aabbEnlargeFactor=intRadius,label='is2aabb'),]),
 	InsertionSortCollider(sweepLength=.05*sphereRadius,nBins=5,binCoeff=5),
 	InteractionDispatchers(
-		[ef2_Sphere_Sphere_Dem3DofGeom(distFactor=intRadius,label='ss2d3dg')],
-		[Ip2_CpmMat_CpmMat_CpmPhys(sigmaT=sigmaT,relDuctility=relDuctility,epsCrackOnset=epsCrackOnset,G_over_E=G_over_E,isoPrestress=isoPrestress)],
+		[Ig2_Sphere_Sphere_Dem3DofGeom(distFactor=intRadius,label='ss2d3dg')],
+		[Ip2_CpmMat_CpmMat_CpmPhys()],
 		[Law2_Dem3DofGeom_CpmPhys_Cpm()],
 	),
 	NewtonIntegrator(damping=damping,label='damper'),

=== modified file 'lib/SConscript'
--- lib/SConscript	2009-12-30 15:45:32 +0000
+++ lib/SConscript	2010-01-03 20:30:24 +0000
@@ -60,6 +60,7 @@
 			'multimethods/Indexable.cpp','multimethods/MultiMethodsExceptions.cpp',
 			'serialization-xml/XMLFormatManager.cpp','serialization-xml/XMLSaxParser.cpp','serialization/Archive.cpp','serialization/IOFormatManager.cpp','serialization/IOManagerExceptions.cpp',
 			'serialization/FormatChecker.cpp','serialization/Serializable.cpp','serialization/SerializationExceptions.cpp',
+			'pyutil/gil.cpp'
 		]
 		# compile TesselationWrapper only if cgal is enabled
 		+(Split('triangulation/KinematicLocalisationAnalyser.cpp triangulation/Operations.cpp triangulation/RegularTriangulation.cpp triangulation/Timer.cpp triangulation/basicVTKwritter.cpp triangulation/FlowBoundingSphere.cpp triangulation/Deformation.cpp triangulation/Empilement.cpp triangulation/stdafx.cpp triangulation/Tenseur3.cpp triangulation/Tesselation.cpp triangulation/TesselationWrapper.cpp triangulation/test.cpp triangulation/TriaxialState.cpp') if 'cgal' in env['features'] else [])),

=== added file 'lib/pyutil/gil.cpp'
--- lib/pyutil/gil.cpp	1970-01-01 00:00:00 +0000
+++ lib/pyutil/gil.cpp	2010-01-03 20:30:24 +0000
@@ -0,0 +1,5 @@
+#include<yade/lib-pyutil/gil.hpp>
+void pyRunString(const std::string& cmd){
+	gilLock lock; PyRun_SimpleString(cmd.c_str());
+};
+

=== modified file 'lib/pyutil/gil.hpp'
--- lib/pyutil/gil.hpp	2010-01-01 15:21:30 +0000
+++ lib/pyutil/gil.hpp	2010-01-03 20:30:24 +0000
@@ -10,6 +10,4 @@
 };
 
 //! run string as python command; locks & unlocks GIL automatically
-void pyRunString(const std::string& cmd){
-	gilLock lock; PyRun_SimpleString(cmd.c_str());
-};
+void pyRunString(const std::string& cmd);

=== modified file 'pkg/common/Engine/Dispatcher/InteractionDispatchers.cpp'
--- pkg/common/Engine/Dispatcher/InteractionDispatchers.cpp	2010-01-01 15:21:30 +0000
+++ pkg/common/Engine/Dispatcher/InteractionDispatchers.cpp	2010-01-03 20:30:24 +0000
@@ -33,6 +33,7 @@
 		LOG_WARN("Interactions pending erase found (erased), no collider being used?");
 		alreadyWarnedNoCollider=true;
 	}
+	geomDispatcher->scene=physDispatcher->scene=lawDispatcher->scene=scene;
 	geomDispatcher->updateScenePtr();
 	physDispatcher->updateScenePtr();
 	lawDispatcher->updateScenePtr();

=== modified file 'pkg/common/Engine/GlobalEngine/SpheresFactory.cpp'
--- pkg/common/Engine/GlobalEngine/SpheresFactory.cpp	2009-12-18 09:48:16 +0000
+++ pkg/common/Engine/GlobalEngine/SpheresFactory.cpp	2010-01-03 20:30:24 +0000
@@ -16,6 +16,7 @@
 	#include<yade/pkg-common/SphereModel.hpp>
 #endif
 #include<yade/pkg-dem/BodyMacroParameters.hpp>
+#include<yade/lib-pyutil/gil.hpp>
 #include"SpheresFactory.hpp"
 #include<sstream>
 
@@ -104,10 +105,7 @@
 		{
 			ostringstream command;
 			command << pySpheresCreator << "((" << position[0] << ',' << position[1] << ',' << position[2] << ")," << r << ')';
-			PyGILState_STATE gstate;
-				gstate = PyGILState_Ensure();
-				PyRun_SimpleString(command.str().c_str()); 
-			PyGILState_Release(gstate);
+			pyRunString(command.str());
 		}
 		else
 		{

=== modified file 'pkg/common/Engine/ParallelEngine.cpp'
--- pkg/common/Engine/ParallelEngine.cpp	2009-12-18 20:55:02 +0000
+++ pkg/common/Engine/ParallelEngine.cpp	2010-01-03 20:30:24 +0000
@@ -4,7 +4,7 @@
 //#include<omp.h> // needed for omp_get_thread_num() (debugging)
 YADE_PLUGIN((ParallelEngine));
 
-void ParallelEngine::action(Scene* rootBody){
+void ParallelEngine::action(Scene*){
 	// openMP warns if the iteration variable is unsigned...
 	const int size=(int)slaves.size();
 	#ifdef YADE_OPENMP
@@ -15,7 +15,7 @@
 		FOREACH(const shared_ptr<Engine>& e, slaves[i]) {
 			//cerr<<"["<<omp_get_thread_num()<<":"<<e->getClassName()<<"]";
 			e->scene=scene;
-			if(e->isActivated(rootBody)) { e->action(rootBody); }
+			if(e->isActivated(scene)) { e->action(scene); }
 		}
 	}
 }

=== modified file 'pkg/common/Engine/PartialEngine/MomentEngine.cpp'
--- pkg/common/Engine/PartialEngine/MomentEngine.cpp	2009-12-25 14:46:48 +0000
+++ pkg/common/Engine/PartialEngine/MomentEngine.cpp	2010-01-03 20:30:24 +0000
@@ -1,46 +1,16 @@
-/*************************************************************************
-*  Copyright (C) 2008 by Janek Kozicki                                   *
-*  cosurgi@xxxxxxxxxx                                                    *
-*                                                                        *
-*  This program is free software; it is licensed under the terms of the  *
-*  GNU General Public License v2 or later. See file LICENSE for details. *
-*************************************************************************/
-
 #include"MomentEngine.hpp"
-#include<yade/pkg-common/ParticleParameters.hpp>
-
-
 #include<yade/core/Scene.hpp>
 
 
-MomentEngine::MomentEngine() : moment(Vector3r::ZERO)
-{
-}
-
-MomentEngine::~MomentEngine()
-{
-}
-
-
-
-void MomentEngine::applyCondition(Scene* ncb)
-{
-	
-	std::vector<int>::const_iterator ii = subscribedBodies.begin();
-	std::vector<int>::const_iterator iiEnd = subscribedBodies.end();
-	
-	for( ; ii!=iiEnd ; ++ii )
-	{
-		if(ncb->bodies->exists( *ii ))
-		{
-			ncb->forces.addTorque(*ii,moment);
-		} else {
-			std::cerr << "MomentEngine: body " << *ii << "doesn't exist, cannot apply moment.";
-		}
-        }
+MomentEngine::MomentEngine(): moment(Vector3r::ZERO){}
+MomentEngine::~MomentEngine(){}
+
+void MomentEngine::applyCondition(Scene* ncb){
+	FOREACH(const body_id_t id, subscribedBodies){
+		// check that body really exists?
+		scene->forces.addTorque(id,moment);
+	}
 }
 
 YADE_PLUGIN((MomentEngine));
 
-YADE_REQUIRE_FEATURE(PHYSPAR);
-

=== modified file 'pkg/common/Engine/PartialEngine/MomentEngine.hpp'
--- pkg/common/Engine/PartialEngine/MomentEngine.hpp	2009-12-09 17:11:51 +0000
+++ pkg/common/Engine/PartialEngine/MomentEngine.hpp	2010-01-03 20:30:24 +0000
@@ -10,21 +10,15 @@
 
 #include<yade/core/PartialEngine.hpp>
 
-
-class MomentEngine : public PartialEngine 
-{
+class MomentEngine: public PartialEngine{
 	public :
-		Vector3r		moment;
-
+		Vector3r moment;
 		MomentEngine();
 		virtual ~MomentEngine();
-	
 		virtual void applyCondition(Scene*);
 	REGISTER_ATTRIBUTES(PartialEngine,(moment));
-	REGISTER_CLASS_NAME(MomentEngine);
-	REGISTER_BASE_CLASS_NAME(PartialEngine);
+	REGISTER_CLASS_AND_BASE(MomentEngine,PartialEngine);
 };
-
 REGISTER_SERIALIZABLE(MomentEngine);
 
 

=== modified file 'pkg/common/Engine/PartialEngine/RotationEngine.cpp'
--- pkg/common/Engine/PartialEngine/RotationEngine.cpp	2009-12-09 17:11:51 +0000
+++ pkg/common/Engine/PartialEngine/RotationEngine.cpp	2010-01-03 20:30:24 +0000
@@ -43,49 +43,27 @@
 	}
 }
 
-RotationEngine::RotationEngine()
-{
+RotationEngine::RotationEngine(){
 	rotateAroundZero = false;
 	zeroPoint = Vector3r(0,0,0);
 }
 
 
 
-void RotationEngine::applyCondition(Scene *ncb)
-{
-    rotationAxis.Normalize();
-
-	shared_ptr<BodyContainer> bodies = ncb->bodies;
-
-	std::vector<int>::const_iterator ii = subscribedBodies.begin();
-	std::vector<int>::const_iterator iiEnd = subscribedBodies.end();
-
-	Real dt = Omega::instance().getTimeStep();
-
+void RotationEngine::applyCondition(Scene*){
+   rotationAxis.Normalize();
 	Quaternionr q;
-	q.FromAxisAngle(rotationAxis,angularVelocity*dt);
-
-	// Vector3r ax; Real an;
-	
-	for(;ii!=iiEnd;++ii)
-	{
-		State* rb=Body::byId(*ii,ncb)->state.get();
-
-		rb->angVel	= rotationAxis*angularVelocity;
-
-		if(rotateAroundZero)
-        {
-            const Vector3r l = rb->pos-zeroPoint;
-			rb->pos	= q*l+zeroPoint; 
-            rb->vel		= rb->angVel.Cross(l);
+	q.FromAxisAngle(rotationAxis,angularVelocity*scene->dt);
+	FOREACH(body_id_t id,subscribedBodies){
+		State* rb=Body::byId(id,scene)->state.get();
+		rb->angVel=rotationAxis*angularVelocity;
+		if(rotateAroundZero){
+			const Vector3r l=rb->pos-zeroPoint;
+			rb->pos=q*l+zeroPoint; 
+			rb->vel=rb->angVel.Cross(l);
 		}
-			
-		rb->ori	= q*rb->ori;
+		rb->ori=q*rb->ori;
 		rb->ori.Normalize();
-		//rb->ori.ToAxisAngle(ax,an);
-		
 	}
-
-
 }
 

=== modified file 'pkg/common/Engine/PartialEngine/Se3Interpolator.cpp'
--- pkg/common/Engine/PartialEngine/Se3Interpolator.cpp	2009-12-04 23:07:34 +0000
+++ pkg/common/Engine/PartialEngine/Se3Interpolator.cpp	2010-01-03 20:30:24 +0000
@@ -1,6 +1,7 @@
 
 #include"Se3Interpolator.hpp"
 #include<yade/pkg-common/PeriodicEngines.hpp>
+#include<yade/lib-pyutil/gil.hpp>
 
 YADE_PLUGIN((Se3Interpolator))CREATE_LOGGER(Se3Interpolator);
 
@@ -31,7 +32,7 @@
 	if(t>=1.){
 		done=true;
 		LOG_DEBUG("Goal reached.");
-		if(!goalHook.empty()){ PyGILState_STATE gstate; gstate=PyGILState_Ensure(); PyRun_SimpleString(goalHook.c_str()); PyGILState_Release(gstate); }
+		if(!goalHook.empty()) PyRunString(goalHook);
 	}
 }
 

=== modified file 'pkg/dem/DataClass/Clump.cpp'
--- pkg/dem/DataClass/Clump.cpp	2009-12-18 09:48:16 +0000
+++ pkg/dem/DataClass/Clump.cpp	2010-01-03 20:30:24 +0000
@@ -67,7 +67,7 @@
 	shared_ptr<Body> subBody=Body::byId(subId);
 
 	// preconditions
-	assert(subBody->isDynamic);
+	//assert(subBody->isDynamic);
 	assert(state);
 	assert(members.count(subId)==0);
 	assert(subId<getId());
@@ -226,6 +226,7 @@
 	TRVAR1(M);
 	TRWM3MAT(Ig);
 	TRWM3VEC(Sg);
+	if(M==0){ state->mass=0; state->inertia=Vector3r(0,0,0); isDynamic=false; return; }
 
 	state->pos=Sg/M; // clump's centroid
 	// this will calculate translation only, since rotation is zero

=== modified file 'pkg/dem/Engine/GlobalEngine/PeriIsoCompressor.cpp'
--- pkg/dem/Engine/GlobalEngine/PeriIsoCompressor.cpp	2009-12-31 15:22:20 +0000
+++ pkg/dem/Engine/GlobalEngine/PeriIsoCompressor.cpp	2010-01-03 20:30:24 +0000
@@ -6,6 +6,7 @@
 #include<yade/core/Scene.hpp>
 #include<yade/pkg-common/NormalShearInteractions.hpp>
 #include<yade/pkg-dem/DemXDofGeom.hpp>
+#include<yade/lib-pyutil/gil.hpp>
 #include<Wm3Math.h>
 
 using namespace std;
@@ -87,7 +88,7 @@
 			// sigmaGoal reached and packing stable
 			if(state==stresses.size()){ // no next stress to go for
 				LOG_INFO("Finished");
-				if(!doneHook.empty()){ LOG_DEBUG("Running doneHook: "<<doneHook); PyGILState_STATE gstate; gstate=PyGILState_Ensure(); PyRun_SimpleString(doneHook.c_str()); PyGILState_Release(gstate); }
+				if(!doneHook.empty()){ LOG_DEBUG("Running doneHook: "<<doneHook); pyRunString(doneHook); }
 			} else { LOG_INFO("Loaded to "<<sigmaGoal<<" done, going to "<<stresses[state]<<" now"); }
 		} else {
 			if((step%globalUpdateInt)==0) LOG_DEBUG("Stress="<<sigma<<", goal="<<sigmaGoal<<", unbalanced="<<currUnbalanced);
@@ -98,21 +99,24 @@
 void PeriTriaxController::strainStressStiffUpdate(){
 	// update strain first
 	//"Natural" strain, correct for large deformations, only used for comparison with goals
-	for ( int i=0; i<3; i++ ) strain[i]=Mathr::Log ( scene->cell->trsf[i][i] );
+	// → no logarithm here, I have code for strain-stress test that needs regular linear strain.
+	//	Why not set goals as logarithm, if you need it?
+	for ( int i=0; i<3; i++ ) strain[i]=(scene->cell->trsf[i][i]);
 
 	//stress tensor and stiffness
 	
 	//Compute volume of the deformed cell
 	// NOTE : needs refSize, could be generalized to arbitrary initial shapes using trsf*refHsize 
-	Real volume = ( scene->cell->trsf*Matrix3r ( scene->cell->refSize[0],0,0, 0,scene->cell->refSize[1],0,0,0,scene->cell->refSize[2] ) ).Determinant();
+	// → initial cell size is always box, and will be. The cell repeats  periodically, initial shape doesn't (shouldn't, at least) dinfluence interactions at all/
+	Real volume=scene->cell->trsf.Determinant()*scene->cell->refSize[0]*scene->cell->refSize[1]*scene->cell->refSize[2];
 
 	//Compute sum(fi*lj) and stiffness
 	stressTensor = Matrix3r::ZERO;
-	Vector3r sumStiff ( Vector3r::ZERO );
+	Vector3r sumStiff(Vector3r::ZERO);
 	int n=0;
-	//NOTE : This sort of loops on interactions could be removed if we had callbacks in e.g. constitutive laws
-	FOREACH ( const shared_ptr<Interaction>&I, *scene->interactions )
-	{
+	// NOTE : This sort of loops on interactions could be removed if we had callbacks in e.g. constitutive laws
+	// → very likely performance hit; do you have some concrete design in mind?
+	FOREACH(const shared_ptr<Interaction>&I, *scene->interactions){
 		if ( !I->isReal() ) continue;
 		NormalShearInteraction* nsi=YADE_CAST<NormalShearInteraction*> ( I->interactionPhysics.get() );
 		GenericSpheresContact* gsc=YADE_CAST<GenericSpheresContact*> ( I->interactionGeometry.get() );
@@ -124,22 +128,22 @@
 		Vector3r branch= ( reversedForces?-1.:1. ) *gsc->normal* ( gsc->refR1+gsc->refR2 );
 		// tensorial product f*branch
 		stressTensor+=Matrix3r ( f, branch );
-		if ( !dynCell )
+		if( !dynCell )
 		{
 			for ( int i=0; i<3; i++ ) sumStiff[i]+=abs ( gsc->normal[i] ) *nsi->kn+ ( 1-abs ( gsc->normal[i] ) ) *nsi->ks;
 			n++;
 		}
 	}
-	//Compute stressTensor=sum(fi*lj)/Volume (Love equation)
+	// Compute stressTensor=sum(fi*lj)/Volume (Love equation)
 	stressTensor /= volume;
-	for ( int axis=0; axis<3; axis++ ) stress[axis]=stressTensor[axis][axis];
+	for(int axis=0; axis<3; axis++) stress[axis]=stressTensor[axis][axis];
 	LOG_DEBUG ( "stressTensor : "<<endl
 				<<stressTensor[0][0]<<" "<<stressTensor[0][1]<<" "<<stressTensor[0][2]<<endl
 				<<stressTensor[1][0]<<" "<<stressTensor[1][1]<<" "<<stressTensor[1][2]<<endl
 				<<stressTensor[2][0]<<" "<<stressTensor[2][1]<<" "<<stressTensor[2][2]<<endl
 				<<"unbalanced = "<<Shop::unbalancedForce ( /*useMaxForce=*/false,scene ) );
 
-	if ( n>0 ) stiff= ( 1./n ) *sumStiff;
+	if (n>0) stiff=(1./n)*sumStiff;
 	else stiff=Vector3r::ZERO;
 }
 
@@ -148,93 +152,87 @@
 
 
 
-void PeriTriaxController::action ( Scene* )
+void PeriTriaxController::action(Scene*)
 {
-	if ( !scene->isPeriodic ) { throw runtime_error ( "PeriTriaxController run on aperiodic simulation." ); }
+	if (!scene->isPeriodic){ throw runtime_error("PeriTriaxController run on aperiodic simulation."); }
 	const Vector3r& cellSize=scene->cell->getSize();
-	Vector3r cellArea=Vector3r ( cellSize[1]*cellSize[2],cellSize[0]*cellSize[2],cellSize[0]*cellSize[1] );
+	Vector3r cellArea=Vector3r(cellSize[1]*cellSize[2],cellSize[0]*cellSize[2],cellSize[0]*cellSize[1]);
 	// initial updates
 	const Vector3r& refSize=scene->cell->refSize;
-	if ( maxBodySpan[0]<=0 )
-	{
-		FOREACH ( const shared_ptr<Body>& b,*scene->bodies )
-		{
-			if ( !b || !b->bound ) continue;
-			for ( int i=0; i<3; i++ ) maxBodySpan[i]=max ( maxBodySpan[i],b->bound->max[i]-b->bound->min[i] );
+	if (maxBodySpan[0]<=0){
+		FOREACH(const shared_ptr<Body>& b,*scene->bodies){
+			if(!b || !b->bound) continue;
+			for(int i=0; i<3; i++) maxBodySpan[i]=max(maxBodySpan[i],b->bound->max[i]-b->bound->min[i]);
 		}
 	}
 	// check current size
-	if ( 2.1*maxBodySpan[0]>cellSize[0] || 2.1*maxBodySpan[1]>cellSize[1] || 2.1*maxBodySpan[2]>cellSize[2] )
-	{
-		LOG_DEBUG ( "cellSize="<<cellSize<<", maxBodySpan="<<maxBodySpan );
-		throw runtime_error ( "Minimum cell size is smaller than 2.1*maxBodySpan (periodic collider requirement)" );
+	if(2.1*maxBodySpan[0]>cellSize[0] || 2.1*maxBodySpan[1]>cellSize[1] || 2.1*maxBodySpan[2]>cellSize[2]){
+		LOG_DEBUG("cellSize="<<cellSize<<", maxBodySpan="<<maxBodySpan);
+		throw runtime_error("Minimum cell size is smaller than 2.1*maxBodySpan (periodic collider requirement)");
 	}
-	bool doUpdate ( ( scene->currentIteration%globUpdate ) ==0 );
-	if ( doUpdate || min ( stiff[0],min ( stiff[1],stiff[2] ) ) <=0 || dynCell ) { strainStressStiffUpdate(); }
+	bool doUpdate((scene->currentIteration%globUpdate)==0);
+	if(doUpdate || min(stiff[0],min(stiff[1],stiff[2])) <=0 || dynCell){ strainStressStiffUpdate(); }
 
-	bool allOk=true; Vector3r cellGrow ( Vector3r::ZERO );
+	bool allOk=true; Vector3r cellGrow(Vector3r::ZERO);
 	// apply condition along each axis separately (stress or strain)
-	for ( int axis=0; axis<3; axis++ )
-	{
+	for(int axis=0; axis<3; axis++){
 		//NOTE (1): don't multiply by refSize here (see note (2))
-		Real maxGrow=/*refSize[axis]**/maxStrainRate[axis]*scene->dt;
-		if ( stressMask & ( 1<<axis ) )   // control stress
-		{
-			if ( !dynCell )
-			{
+		Real maxGrow=refSize[axis]*maxStrainRate[axis]*scene->dt;
+		if(stressMask & (1<<axis)){   // control stress
+			if(!dynCell){
+				// PLEASE keep formulas up-to-date if you change code...
+				//
 				// stiffness K=EA; σ₁=goal stress; Δσ wanted stress difference to apply
 				// ΔεE=(Δl/l₀)(K/A) = Δσ=σ₁-σ ↔ Δl=(σ₁-σ)l₀(A/K)
-				cellGrow[axis]= ( goal[axis]-stress[axis] ) */*refSize[axis]**/cellArea[axis]/ ( stiff[axis]>0?stiff[axis]:1. );
-				LOG_TRACE ( axis<<": stress="<<stress[axis]<<", goal="<<goal[axis]<<", cellGrow="<<cellGrow[axis] );
-			}
-			else  //accelerate the deformation using the density of the period, includes Cundall's damping
-			{
-				assert ( mass>0 );//user set
+				cellGrow[axis]=(goal[axis]-stress[axis])*refSize[axis]*cellArea[axis]/(stiff[axis]>0?stiff[axis]:1.);
+				LOG_TRACE(axis<<": stress="<<stress[axis]<<", goal="<<goal[axis]<<", cellGrow="<<cellGrow[axis]);
+			} else {  //accelerate the deformation using the density of the period, includes Cundall's damping
+				assert( mass>0 );//user set
 				Real dampFactor = 1 - growDamping*Mathr::Sign ( ( scene->cell->velGrad[axis][axis] ) * ( goal[axis]-stress[axis] ) );
 				scene->cell->velGrad[axis][axis]+=dampFactor*scene->dt* ( goal[axis]-stress[axis] ) /mass;
 				LOG_TRACE ( axis<<": stress="<<stress[axis]<<", goal="<<goal[axis]<<", velGrad="<<scene->cell->velGrad[axis][axis] );
 			}
-		}
-		else   // control strain
-		{
+		} else {    // control strain
 			///NOTE : everything could be generalized to 9 independant components by comparing F[i,i] vs. Matrix3r goal[i,i], but it would be simpler in that case to let the user set the prescribed loading rates velGrad[i,i] when [i,i] is not stress-controlled. This "else" would disappear.
-			cellGrow[axis]=Mathr::Exp ( goal[axis]-strain[axis] ) /**refSize[axis]*/-1;
+			// → sorry, exp removed, see comment about log above; fix formulas if you need it back
+			cellGrow[axis]=(goal[axis]-strain[axis])*refSize[axis];
 			LOG_TRACE ( axis<<": strain="<<strain[axis]<<", goal="<<goal[axis]<<", cellGrow="<<cellGrow[axis] );
 		}
 		// limit maximum strain rate
-		if ( abs ( cellGrow[axis] ) >maxGrow ) cellGrow[axis]=Mathr::Sign ( cellGrow[axis] ) *maxGrow;
+		if (abs(cellGrow[axis])>maxGrow) cellGrow[axis]=Mathr::Sign(cellGrow[axis])*maxGrow;
 		// do not shrink below minimum cell size (periodic collider condition), although it is suboptimal WRT resulting stress
 		/** NOTE : this is one place where size can't be removed (except for span tests). Commented out for now. Do we really need to handle this very special case here? The simulation will go crazy anyway, so we can as well throw at the next step. I'm trying to remove "size" when it's not needed, partly because I have in mind independant control on 9 components of stress/velGrad and it will be easier with a the matrix formalism (we dont have 9 sizes...). If one day size is not used anywhere, we can remove it. (B.C.)*/
-		//cellGrow[axis]=max(cellGrow[axis],-(cellSize[axis]-2.1*maxBodySpan[axis]));
+		/* → we need to handle this really:
+			1. cell size is defined exactly, no reason to hate it anymore. And the collider needs it as well.
+			2. automatic compressions (like pack.randomPeriPack) might create pathologic ratios of the box, but still need some result.
+			please check that the units are ok, since what is cellGrow now?
+		*/
+		cellGrow[axis]=max(cellGrow[axis],-(cellSize[axis]-2.1*maxBodySpan[axis]));
 
 		// steady evolution with fluctuations; see TriaxialStressController
-		cellGrow[axis]= ( 1-growDamping ) *cellGrow[axis]+.8*prevGrow[axis];
+		cellGrow[axis]=(1-growDamping)*cellGrow[axis]+.8*prevGrow[axis];
 		// crude way of predicting stress, for steps when it is not computed from intrs
-		if ( doUpdate ) LOG_DEBUG ( axis<<": cellGrow="<<cellGrow[axis]<<", new stress="<<stress[axis]<<", new strain="<<strain[axis] );
+		if(doUpdate) LOG_DEBUG(axis<<": cellGrow="<<cellGrow[axis]<<", new stress="<<stress[axis]<<", new strain="<<strain[axis]);
 		// signal if condition not satisfied
-		if ( stressMask & ( 1<<axis ) )
-		{
+		if(stressMask&(1<<axis)){
 			Real curr=stress[axis];
-			if ( ( goal[axis]!=0 && abs ( ( curr-goal[axis] ) /goal[axis] ) >relStressTol ) || abs ( curr-goal[axis] ) >absStressTol ) allOk=false;
-		}
-		else
-		{
+			if((goal[axis]!=0 && abs((curr-goal[axis])/goal[axis])>relStressTol) || abs(curr-goal[axis])>absStressTol) allOk=false;
+		}else{
 			Real curr=strain[axis];
 			// since strain is prescribed exactly, tolerances need just to accomodate rounding issues
-			if ( ( goal[axis]!=0 && abs ( ( curr-goal[axis] ) /goal[axis] ) >1e-6 ) || abs ( curr-goal[axis] ) >1e-6 )
-			{
+			if((goal[axis]!=0 && abs((curr-goal[axis])/goal[axis])>1e-6) || abs(curr-goal[axis])>1e-6){
 				allOk=false;
-				if ( doUpdate ) LOG_DEBUG ( "Strain not OK; "<<abs ( curr-goal[axis] ) <<">1e-6" );
+				if(doUpdate) LOG_DEBUG("Strain not OK; "<<abs(curr-goal[axis])<<">1e-6");
 			}
 		}
 	}
-	assert ( scene->dt>0. );
+	assert(scene->dt>0.);
 	// update stress and strain
 	if (!dynCell) for ( int axis=0; axis<3; axis++ )
 	{
 		// either prescribe velocity gradient
 		//NOTE (2) : ... and don't divide here
-		scene->cell->velGrad[axis][axis]=cellGrow[axis]/ ( scene->dt/**refSize[axis]*/ );
+		scene->cell->velGrad[axis][axis]=cellGrow[axis]/(scene->dt*refSize[axis]);
 		// or strain increment (but NOT both)
 		// strain[axis]+=cellGrow[axis]/refSize[axis];
 
@@ -249,20 +247,16 @@
 
 	strainRate=cellGrow/scene->dt;
 
-	if ( allOk )
-	{
-		if ( doUpdate || currUnbalanced<0 )
-		{
-			currUnbalanced=Shop::unbalancedForce ( /*useMaxForce=*/false,scene );
-			LOG_DEBUG ( "Stress/strain="<< ( stressMask&1?stress[0]:strain[0] ) <<","<< ( stressMask&2?stress[1]:strain[1] ) <<","<< ( stressMask&4?stress[2]:strain[2] ) <<", goal="<<goal<<", unbalanced="<<currUnbalanced );
+	if(allOk){
+		if(doUpdate || currUnbalanced<0){
+			currUnbalanced=Shop::unbalancedForce(/*useMaxForce=*/false,scene);
+			LOG_DEBUG("Stress/strain="<<(stressMask&1?stress[0]:strain[0])<<","<<(stressMask&2?stress[1]:strain[1])<<","<<(stressMask&4?stress[2]:strain[2])<<", goal="<<goal<<", unbalanced="<<currUnbalanced );
 		}
-		if ( currUnbalanced<maxUnbalanced )
-		{
+		if(currUnbalanced<maxUnbalanced){
 			// LOG_INFO("Goal reached, packing stable.");
-			if ( !doneHook.empty() )
-			{
+			if (!doneHook.empty()){
 				LOG_DEBUG ( "Running doneHook: "<<doneHook );
-				PyGILState_STATE gstate; gstate=PyGILState_Ensure(); PyRun_SimpleString ( doneHook.c_str() ); PyGILState_Release ( gstate );
+				pyRunString(doneHook);
 			}
 			else { Omega::instance().stopSimulationLoop(); }
 		}

=== modified file 'pkg/dem/meta/ConcretePM.cpp'
--- pkg/dem/meta/ConcretePM.cpp	2009-12-25 14:46:48 +0000
+++ pkg/dem/meta/ConcretePM.cpp	2010-01-03 20:30:24 +0000
@@ -16,46 +16,59 @@
 CREATE_LOGGER(Ip2_CpmMat_CpmMat_CpmPhys);
 
 void Ip2_CpmMat_CpmMat_CpmPhys::go(const shared_ptr<Material>& pp1, const shared_ptr<Material>& pp2, const shared_ptr<Interaction>& interaction){
-	if(interaction->interactionPhysics) return; 
-
-	Dem3DofGeom* contGeom=YADE_CAST<Dem3DofGeom*>(interaction->interactionGeometry.get());
-	assert(contGeom);
-
-	const shared_ptr<CpmMat>& mat1=YADE_PTR_CAST<CpmMat>(pp1);
-	const shared_ptr<CpmMat>& mat2=YADE_PTR_CAST<CpmMat>(pp2);
-
-	Real E12=2*mat1->young*mat2->young/(mat1->young+mat2->young); // harmonic Young's modulus average
-	//Real nu12=2*mat1->poisson*mat2->poisson/(mat1->poisson+mat2->poisson); // dtto for Poisson ratio 
-	Real minRad=(contGeom->refR1<=0?contGeom->refR2:(contGeom->refR2<=0?contGeom->refR1:min(contGeom->refR1,contGeom->refR2)));
-	Real S12=Mathr::PI*pow(minRad,2); // "surface" of interaction
-	//Real E=(E12 /* was here for Kn:  *S12/d0  */)*((1+alpha)/(beta*(1+nu12)+gamma*(1-alpha*nu12)));
-	//Real E=E12; // apply alpha, beta, gamma: garbage values of E !?
-
-	if(!neverDamage) { assert(!isnan(sigmaT)); }
-
-	shared_ptr<CpmPhys> contPhys(new CpmPhys());
-
-	contPhys->E=E12;
-	contPhys->G=E12*G_over_E;
-	contPhys->tanFrictionAngle=tan(.5*(mat1->frictionAngle+mat2->frictionAngle));
-	contPhys->undamagedCohesion=sigmaT;
-	contPhys->crossSection=S12;
-	contPhys->epsCrackOnset=epsCrackOnset;
-	contPhys->epsFracture=relDuctility*epsCrackOnset;
-	// inherited from NormalShearInteracion, used in the timestepper
-
-	// contPhys->kn, contPhys->ks assigned in the constitutive law, as they depend on area of the contact as well
-
-	if(neverDamage) contPhys->neverDamage=true;
-	if(cohesiveThresholdIter<0 || (Omega::instance().getCurrentIteration()<cohesiveThresholdIter)) contPhys->isCohesive=true;
-	else contPhys->isCohesive=false;
-	contPhys->dmgTau=dmgTau;
-	contPhys->dmgRateExp=dmgRateExp;
-	contPhys->plTau=plTau;
-	contPhys->plRateExp=plRateExp;
-	contPhys->isoPrestress=isoPrestress;
-
-	interaction->interactionPhysics=contPhys;
+	// no updates of an already existing contact necessary
+	if(interaction->interactionPhysics) return;
+	shared_ptr<CpmPhys> cpmPhys(new CpmPhys());
+	interaction->interactionPhysics=cpmPhys;
+	CpmMat* mat1=YADE_CAST<CpmMat*>(pp1.get());
+	CpmMat* mat2=YADE_CAST<CpmMat*>(pp2.get());
+
+	// check unassigned values
+	assert(!isnan(mat1->G_over_E));
+	if(!mat1->neverDamage) {
+		assert(!isnan(mat1->sigmaT));
+		assert(!isnan(mat1->epsCrackOnset));
+		assert(!isnan(mat1->relDuctility));
+		assert(!isnan(mat1->G_over_E));
+	}
+
+	// bodies sharing the same material; no averages necessary
+	if(mat1->id>=0 && mat1->id==mat2->id) {
+		cpmPhys->E=mat1->young;
+		cpmPhys->G=mat1->young*mat1->G_over_E;
+		cpmPhys->tanFrictionAngle=tan(mat1->frictionAngle);
+		cpmPhys->undamagedCohesion=mat1->sigmaT;
+		cpmPhys->epsFracture=mat1->relDuctility*mat1->epsCrackOnset;
+		cpmPhys->isCohesive=(cohesiveThresholdIter<0 || scene->currentIteration<cohesiveThresholdIter);
+		#define _CPATTR(a) cpmPhys->a=mat1->a
+			_CPATTR(epsCrackOnset);
+			_CPATTR(neverDamage);
+			_CPATTR(dmgTau);
+			_CPATTR(dmgRateExp);
+			_CPATTR(plTau);
+			_CPATTR(plRateExp);
+			_CPATTR(isoPrestress);
+		#undef _CPATTR
+	} else {
+		// averaging over both materials
+		#define _AVGATTR(a) cpmPhys->a=.5*(mat1->a+mat2->a)
+			cpmPhys->E=.5*(mat1->young+mat2->young);
+			cpmPhys->G=.5*(mat1->G_over_E+mat2->G_over_E)*.5*(mat1->young+mat2->young);
+			cpmPhys->tanFrictionAngle=tan(.5*(mat1->frictionAngle+mat2->frictionAngle));
+			cpmPhys->undamagedCohesion=.5*(mat1->sigmaT+mat2->sigmaT);
+			cpmPhys->epsFracture=.5*(mat1->relDuctility+mat2->relDuctility)*.5*(mat1->epsCrackOnset+mat2->epsCrackOnset);
+			cpmPhys->isCohesive=(cohesiveThresholdIter<0 || scene->currentIteration<cohesiveThresholdIter);
+			_AVGATTR(epsCrackOnset);
+			cpmPhys->neverDamage=(mat1->neverDamage || mat2->neverDamage);
+			_AVGATTR(dmgTau);
+			_AVGATTR(dmgRateExp);
+			_AVGATTR(plTau);
+			_AVGATTR(plRateExp);
+			_AVGATTR(isoPrestress);
+		#undef _AVGATTR
+	}
+	// NOTE: some params are not assigned until in Law2_Dem3DofGeom_CpmPhys_Cpm, since they need geometry as well; those are:
+	// 	crossSection, kn, ks
 }
 
 
@@ -140,6 +153,8 @@
 
 	// just the first time
 	if(I->isFresh(scene)){
+		Real minRad=(contGeom->refR1<=0?contGeom->refR2:(contGeom->refR2<=0?contGeom->refR1:min(contGeom->refR1,contGeom->refR2)));
+		BC->crossSection=Mathr::PI*pow(minRad,2);
 		BC->kn=BC->crossSection*BC->E/contGeom->refLength;
 		BC->ks=BC->crossSection*BC->G/contGeom->refLength;
 	}
@@ -365,15 +380,16 @@
 		const body_id_t id1=I->getId1(), id2=I->getId2();
 		Dem3DofGeom* geom=YADE_CAST<Dem3DofGeom*>(I->interactionGeometry.get());
 		
-		Vector3r stress=(1./phys->crossSection)*(phys->normalForce+phys->shearForce);
-		const Vector3r& p1(geom->se31.position); const Vector3r& cp(geom->contactPoint);
-		// force towards the body is negative, away from it is positive (compression/tension)
+		Vector3r normalStress=((1./phys->crossSection)*geom->normal.Dot(phys->normalForce))*geom->normal;
+		bodyStats[id1].sigma+=normalStress; bodyStats[id2].sigma+=normalStress;
+		Vector3r shearStress;
 		for(int i=0; i<3; i++){
-			stress[i]*=cp[i]>p1[i] ? 1. : -1.;
+			int ix1=(i+1)%3,ix2=(i+2)%3;
+			shearStress[i]=Mathr::Sign(geom->normal[ix1])*phys->shearForce[ix1]+Mathr::Sign(geom->normal[ix2])*phys->shearForce[ix2];
+			shearStress[i]/=phys->crossSection;
 		}
-		bodyStats[id1].sigma+=stress; bodyStats[id2].sigma+=stress;
-		bodyStats[id1].tau+=stress.Cross(cp-geom->se31.position);
-		bodyStats[id2].tau+=stress.Cross(cp-geom->se32.position);
+		bodyStats[id1].tau+=shearStress;
+		bodyStats[id2].tau+=shearStress;
 		bodyStats[id1].nLinks++; bodyStats[id2].nLinks++;
 		
 		if(!phys->isCohesive) continue;

=== modified file 'pkg/dem/meta/ConcretePM.hpp'
--- pkg/dem/meta/ConcretePM.hpp	2009-12-13 20:11:31 +0000
+++ pkg/dem/meta/ConcretePM.hpp	2010-01-03 20:30:24 +0000
@@ -84,10 +84,21 @@
 /* This class holds information associated with each body */
 class CpmMat: public GranularMat {
 	public:
-		CpmMat() { createIndex(); density=4800; };
+		/* nonelastic material parameters; meaning clarified in CpmPhys, under same names */
+		Real sigmaT, epsCrackOnset, relDuctility, G_over_E, dmgTau, dmgRateExp, plTau, plRateExp, isoPrestress;
+		//! Contacts won't receive any damage (CpmPhys::neverDamage=true); defaults to false
+		bool neverDamage;
+		CpmMat() {
+			createIndex(); density=4800;
+			// init to signaling_NaN to force crash if not initialized (better than unknowingly using garbage values)
+			sigmaT=epsCrackOnset=relDuctility=G_over_E=std::numeric_limits<Real>::signaling_NaN();
+			neverDamage=false;
+			dmgTau=-1; dmgRateExp=0; plTau=-1; plRateExp=-1; // disable visco-damage and visco-plasticity
+			isoPrestress=0;
+		};
 		virtual shared_ptr<State> newAssocState() const { return shared_ptr<State>(new CpmState); }
 		virtual bool stateTypeOk(State* s) const { return (bool)dynamic_cast<CpmState*>(s); }
-		REGISTER_ATTRIBUTES(GranularMat,);
+		REGISTER_ATTRIBUTES(GranularMat,(G_over_E)(sigmaT)(neverDamage)(epsCrackOnset)(relDuctility)(dmgTau)(dmgRateExp)(plTau)(plRateExp)(isoPrestress));
 		REGISTER_CLASS_AND_BASE(CpmMat,GranularMat);
 		REGISTER_CLASS_INDEX(CpmMat,GranularMat);
 };
@@ -214,41 +225,16 @@
 class Ip2_CpmMat_CpmMat_CpmPhys: public InteractionPhysicsFunctor{
 	private:
 	public:
-		/* nonelastic material parameters */
-		/* alternatively (and more cleanly), we would have subclass of ElasticBodyParameters,
-		 * which would define just those in addition to the elastic ones.
-		 * This might be done later, for now hardcode that here. */
-		/* uniaxial tension resistance, bending parameter of the damage evolution law, whear weighting constant for epsT in the strain seminorm (kappa) calculation. Default to NaN so that user gets loudly notified it was not set.
-		
-		*/
-		Real sigmaT, epsCrackOnset, relDuctility, G_over_E, tau, expDmgRate, dmgTau, dmgRateExp, plTau, plRateExp, isoPrestress;
 		//! Should new contacts be cohesive? They will before this iter#, they will not be afterwards. If 0, they will never be. If negative, they will always be created as cohesive.
 		long cohesiveThresholdIter;
-		//! Create contacts that don't receive any damage (CpmPhys::neverDamage=true); defaults to false
-		bool neverDamage;
 
 		Ip2_CpmMat_CpmMat_CpmPhys(){
-			// init to signaling_NaN to force crash if not initialized (better than unknowingly using garbage values)
-			sigmaT=epsCrackOnset=relDuctility=G_over_E=std::numeric_limits<Real>::signaling_NaN();
-			neverDamage=false;
-			cohesiveThresholdIter=10;
-			dmgTau=-1; dmgRateExp=0; plTau=-1; plRateExp=-1;
-			isoPrestress=0;
+			cohesiveThresholdIter=10; // create cohesive interactions in first 10 steps by default
 		}
 
 		virtual void go(const shared_ptr<Material>& pp1, const shared_ptr<Material>& pp2, const shared_ptr<Interaction>& interaction);
 		REGISTER_ATTRIBUTES(InteractionPhysicsFunctor,
 			(cohesiveThresholdIter)
-			(G_over_E)
-			(sigmaT)
-			(neverDamage)
-			(epsCrackOnset)
-			(relDuctility)
-			(dmgTau)
-			(dmgRateExp)
-			(plTau)
-			(plRateExp)
-			(isoPrestress)
 		);
 
 		FUNCTOR2D(CpmMat,CpmMat);

=== modified file 'py/pack.py'
--- py/pack.py	2009-12-25 14:46:48 +0000
+++ py/pack.py	2010-01-03 20:30:24 +0000
@@ -215,7 +215,7 @@
 		if predicate(s[0],s[1]): ret+=[utils.sphere(s[0],radius=s[1],**kw)]
 	return ret
 
-def randomDensePack(predicate,radius,material=0,dim=None,cropLayers=0,rRelFuzz=0.,spheresInCell=0,memoizeDb=None,useOBB=True,memoDbg=False):
+def randomDensePack(predicate,radius,material=0,dim=None,cropLayers=0,rRelFuzz=0.,spheresInCell=0,memoizeDb=None,useOBB=True,memoDbg=False,color=None):
 	"""Generator of random dense packing with given geometry properties, using TriaxialTest (aperiodic)
 	or PeriIsoCompressor (periodic). The priodicity depens on whether	the spheresInCell parameter is given.
 
@@ -310,7 +310,7 @@
 		#print x1,y1,z1,radius,rRelFuzz
 		O.materials.append(GranularMat(young=3e10,density=2400))
 		num=sp.makeCloud(Vector3().ZERO,O.cell.refSize,radius,rRelFuzz,spheresInCell,True)
-		O.engines=[ForceResetter(),BoundDispatcher([Bo1_Sphere_Aabb()]),InsertionSortCollider(nBins=5,sweepLength=.05*radius),InteractionDispatchers([ef2_Sphere_Sphere_Dem3DofGeom()],[SimpleElasticRelationships()],[Law2_Dem3Dof_Elastic_Elastic()]),PeriIsoCompressor(charLen=2*radius,stresses=[-100e9,-1e8],maxUnbalanced=1e-2,doneHook='O.pause();',globalUpdateInt=5,keepProportions=True),NewtonIntegrator(damping=.6)]
+		O.engines=[ForceResetter(),BoundDispatcher([Bo1_Sphere_Aabb()]),InsertionSortCollider(nBins=5,sweepLength=.05*radius),InteractionDispatchers([Ig2_Sphere_Sphere_Dem3DofGeom()],[SimpleElasticRelationships()],[Law2_Dem3Dof_Elastic_Elastic()]),PeriIsoCompressor(charLen=2*radius,stresses=[-100e9,-1e8],maxUnbalanced=1e-2,doneHook='O.pause();',globalUpdateInt=5,keepProportions=True),NewtonIntegrator(damping=.6)]
 		O.materials.append(GranularMat(young=30e9,frictionAngle=.5,poisson=.3,density=1e3))
 		for s in sp: O.bodies.append(utils.sphere(s[0],s[1]))
 		O.dt=utils.PWaveTimeStep()
@@ -349,7 +349,7 @@
 	if orientation:
 		sp.cellSize=(0,0,0); # reset periodicity to avoid warning when rotating periodic packing
 		sp.rotate(*orientation.ToAxisAngle())
-	return filterSpherePack(predicate,sp,material=material)
+	return filterSpherePack(predicate,sp,material=material,color=color)
 
 # compatibility with the deprecated name, can be removed in the future
 def triaxialPack(*args,**kw):

=== modified file 'py/post2d.py'
--- py/post2d.py	2009-12-15 23:09:07 +0000
+++ py/post2d.py	2010-01-03 20:30:24 +0000
@@ -164,7 +164,7 @@
 	nDim=0
 	for b in O.bodies:
 		if onlyDynamic and not b.dynamic: continue
-		if b.mold.name!='Sphere': continue
+		if b.shape.name!='Sphere': continue
 		xy,d=flattener(b),extractor(b)
 		if xy==None or d==None: continue
 		if nDim==0: nDim=1 if isinstance(d,float) else 2
@@ -176,7 +176,7 @@
 			dd1.append(d1); dd2.append(d2)
 		else:
 			raise RuntimeError("Extractor must return float or 2 or 3 (not %d) floats"%nDim)
-		xx.append(xy[0]); yy.append(xy[1]); rr.append(b.mold['radius'])
+		xx.append(xy[0]); yy.append(xy[1]); rr.append(b.shape['radius'])
 	if stDev==None:
 		bbox=(min(xx),min(yy)),(max(xx),max(yy))
 		if nDim==1: return {'type':'rawScalar','x':xx,'y':yy,'val':dd1,'radii':rr,'bbox':bbox}

=== modified file 'py/system.py'
--- py/system.py	2009-12-25 14:46:48 +0000
+++ py/system.py	2010-01-03 20:30:24 +0000
@@ -39,8 +39,8 @@
 	'CpmPhysDamageColorizer':'CpmStateUpdater', # renamed 10.10.2009
 	'GLDraw_Dem3DofGeom_FacetSphere':'Gl1_Dem3DofGeom_FacetSphere', # renamed 15.11.2009
 	'PeriodicInsertionSortCollider':'InsertionSortCollider',	# integrated 25.11.2009
-	'BoundingVolumeMetaEngine':'BoundingDispatcher', # Tue Dec  1 14:28:29 2009, vaclav@flux  ## was BoundingVolumeDispatcher, generating double warning
-	'BoundingVolumeEngineUnit':'BoundingFunctor', # Tue Dec  1 14:39:53 2009, vaclav@flux ## was BoundingVolumeFunctor, generating double warning
+	'BoundingVolumeMetaEngine':'BoundDispatcher', # Tue Dec  1 14:28:29 2009, vaclav@flux  ## was BoundingVolumeDispatcher, generating double warning
+	'BoundingVolumeEngineUnit':'BoundFunctor', # Tue Dec  1 14:39:53 2009, vaclav@flux ## was BoundingVolumeFunctor, generating double warning
 	'InteractionGeometryMetaEngine':'InteractionGeometryDispatcher', # Tue Dec  1 14:40:36 2009, vaclav@flux
 	'InteractionPhysicsMetaEngine':'InteractionPhysicsDispatcher', # Tue Dec  1 14:40:53 2009, vaclav@flux
 	'InteractionPhysicsEngineUnit':'InteractionPhysicsFunctor', # Tue Dec  1 14:41:19 2009, vaclav@flux

=== modified file 'py/utils.py'
--- py/utils.py	2009-12-25 14:46:48 +0000
+++ py/utils.py	2010-01-03 20:30:24 +0000
@@ -509,29 +509,29 @@
 
 def _deprecatedUtilsFunction(old,new):
 	import warnings
-	warnings.warn('Function utils.%s is deprecated, use %s instead.'%(old,new),stacklevel=2,category='DeprecationWarning')
+	warnings.warn('Function utils.%s is deprecated, use %s instead.'%(old,new),stacklevel=2,category=DeprecationWarning)
 
 def sumBexForces(*args,**kw):
-	_deprecatedUtilsFunction(func.__name__,'utils.sumForces')
+	_deprecatedUtilsFunction('sumBexForces','utils.sumForces')
 	return sumForces(*args,**kw)
 def sumBexTorques(*args,**kw):
-	_deprecatedUtilsFunction(func.__name__,'utils.sumTorques')
+	_deprecatedUtilsFunction('sumBexTorques','utils.sumTorques')
 	return sumTorques(*args,**kw)
 
 def spheresFromFile(*args,**kw):
-	_deprecatedUtilsFunction(func.__name__,'yade.import.text')
+	_deprecatedUtilsFunction('spheresFromFile','yade.import.text')
 	import yade.ymport
 	return yade.ymport.text(*args,**kw)
 def import_stl_geometry(*args,**kw):
-	_deprecatedUtilsFunction(func.__name__,'yade.import.stl')
+	_deprecatedUtilsFunction('import_stl_geometry','yade.import.stl')
 	import yade.ymport
 	return yade.ymport.stl(*args,**kw)
 def import_mesh_geometry(*args,**kw):
-	_deprecatedUtilsFunction(func.__name__,'yade.import.gmsh')
+	_deprecatedUtilsFunction('import_mesh_geometry','yade.import.gmsh')
 	import yade.ymport
 	return yade.ymport.stl(*args,**kw)
 def import_LSMGenGeo_geometry(*args,**kw):
-	_deprecatedUtilsFunction(func.__name__,'yade.import.gengeo')
+	_deprecatedUtilsFunction('import_LSMGenGeo_geometry','yade.import.gengeo')
 	import yade.ymport
 	return yade.ymport.gengeo(*args,**kw)
 

=== modified file 'py/yadeWrapper/yadeWrapper.cpp'
--- py/yadeWrapper/yadeWrapper.cpp	2009-12-30 20:10:59 +0000
+++ py/yadeWrapper/yadeWrapper.cpp	2010-01-03 20:30:24 +0000
@@ -25,6 +25,7 @@
 
 #include<yade/lib-base/Logging.hpp>
 #include<yade/lib-serialization-xml/XMLFormatManager.hpp>
+#include<yade/lib-pyutil/gil.hpp>
 #include<yade/core/Omega.hpp>
 #include<yade/core/ThreadRunner.hpp>
 #include<yade/core/FileGenerator.hpp>
@@ -321,15 +322,13 @@
 		#endif
 		FOREACH(const shared_ptr<Engine>& e, OMEGA.getScene()->engines){
 			if(!e->label.empty()){
-				PyGILState_STATE gstate; gstate = PyGILState_Ensure();
-				PyRun_SimpleString(("__builtins__."+e->label+"=Omega().labeledEngine('"+e->label+"')").c_str());
-				PyGILState_Release(gstate);
+				pyRunString("__builtins__."+e->label+"=Omega().labeledEngine('"+e->label+"')");
 			}
 			if(isChildClassOf(e->getClassName(),"Dispatcher")){
 				shared_ptr<Dispatcher> ee=dynamic_pointer_cast<Dispatcher>(e);
 				FOREACH(const shared_ptr<Functor>& f, ee->functorArguments){
 					if(!f->label.empty()){
-						PyGILState_STATE gstate; gstate = PyGILState_Ensure(); PyRun_SimpleString(("__builtins__."+f->label+"=Omega().labeledEngine('"+f->label+"')").c_str()); PyGILState_Release(gstate);
+						pyRunString("__builtins__."+f->label+"=Omega().labeledEngine('"+f->label+"')");
 					}
 				}
 			}
@@ -341,7 +340,7 @@
 				FOREACH(const shared_ptr<Functor>& eu,ee->lawDispatcher->functorArguments) eus.push_back(eu);
 				FOREACH(const shared_ptr<Functor>& eu,eus){
 					if(!eu->label.empty()){
-						PyGILState_STATE gstate; gstate = PyGILState_Ensure(); PyRun_SimpleString(("__builtins__."+eu->label+"=Omega().labeledEngine('"+eu->label+"')").c_str()); PyGILState_Release(gstate);
+						pyRunString("__builtins__."+eu->label+"=Omega().labeledEngine('"+eu->label+"')");
 					}
 				}
 			}
@@ -538,7 +537,7 @@
 		Omega::instance().cleanupTemps();
 		exit(status);
 	}
-	void runEngine(const shared_ptr<Engine>& e){ e->action(OMEGA.getScene().get()); }
+	void runEngine(const shared_ptr<Engine>& e){ LOG_WARN("Omega().runEngine(): deprecated, use __call__ method of the engine instance directly instead; will be removed in the future."); e->scene=OMEGA.getScene().get(); e->action(OMEGA.getScene().get()); }
 };
 
 class pySTLImporter : public STLImporter {};
@@ -546,6 +545,7 @@
 
 TimingInfo::delta Engine_timingInfo_nsec_get(const shared_ptr<Engine>& e){return e->timingInfo.nsec;}; void Engine_timingInfo_nsec_set(const shared_ptr<Engine>& e, TimingInfo::delta d){ e->timingInfo.nsec=d;}
 long Engine_timingInfo_nExec_get(const shared_ptr<Engine>& e){return e->timingInfo.nExec;}; void Engine_timingInfo_nExec_set(const shared_ptr<Engine>& e, long d){ e->timingInfo.nExec=d;}
+void Engine_action(const shared_ptr<Engine>& e){ e->scene=Omega::instance().getScene().get(); e->action(e->scene); }
 
 shared_ptr<InteractionDispatchers> InteractionDispatchers_ctor_lists(const std::vector<shared_ptr<InteractionGeometryFunctor> >& gff, const std::vector<shared_ptr<InteractionPhysicsFunctor> >& pff, const std::vector<shared_ptr<LawFunctor> >& cff){
 	shared_ptr<InteractionDispatchers> instance(new InteractionDispatchers);
@@ -758,7 +758,8 @@
 	python::class_<Engine, shared_ptr<Engine>, python::bases<Serializable>, noncopyable >("Engine",python::no_init)
 		.add_property("execTime",&Engine_timingInfo_nsec_get,&Engine_timingInfo_nsec_set)
 		.add_property("execCount",&Engine_timingInfo_nExec_get,&Engine_timingInfo_nExec_set)
-		.def_readonly("timingDeltas",&Engine::timingDeltas);
+		.def_readonly("timingDeltas",&Engine::timingDeltas)
+		.def("__call__",&Engine_action);
 	python::class_<GlobalEngine,shared_ptr<GlobalEngine>, python::bases<Engine>, noncopyable>("GlobalEngine").def("__init__",python::raw_constructor(Serializable_ctor_kwAttrs<GlobalEngine>));
 	python::class_<PartialEngine,shared_ptr<PartialEngine>, python::bases<Engine>, noncopyable>("PartialEngine").def("__init__",python::raw_constructor(Serializable_ctor_kwAttrs<PartialEngine>));
 	python::class_<Functor, shared_ptr<Functor>, python::bases<Serializable>, noncopyable >("Functor",python::no_init)