← Back to team overview

yade-dev team mailing list archive

[Branch ~yade-dev/yade/trunk] Rev 2524: 1. Add warning for missing ForceResetter in NewtonIntegrator (based step forces were last reset)

 

------------------------------------------------------------
revno: 2524
committer: Václav Šmilauer <eudoxos@xxxxxxxx>
branch nick: trunk
timestamp: Sat 2010-10-30 19:08:51 +0200
message:
  1. Add warning for missing ForceResetter in NewtonIntegrator (based step forces were last reset)
  2. Rename *Spiral*  to *Helix* (suggested by Jan, thanks!)
  3. Generalize the post2d module to handle interactions (not just particles)
modified:
  core/ForceContainer.hpp
  examples/gts-horse/gts-horse.py
  pkg/common/ForceResetter.cpp
  pkg/common/RotationEngine.cpp
  pkg/common/RotationEngine.hpp
  pkg/dem/NewtonIntegrator.cpp
  pkg/dem/NewtonIntegrator.hpp
  pkg/dem/SpherePack.cpp
  pkg/dem/SpherePack.hpp
  py/_eudoxos.cpp
  py/post2d.py
  py/system.py
  py/utils.py


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

Your team Yade developers is subscribed to branch lp:yade.
To unsubscribe from this branch go to https://code.launchpad.net/~yade-dev/yade/trunk/+edit-subscription
=== modified file 'core/ForceContainer.hpp'
--- core/ForceContainer.hpp	2010-08-27 08:28:50 +0000
+++ core/ForceContainer.hpp	2010-10-30 17:08:51 +0000
@@ -74,7 +74,7 @@
 		// dummy function to avoid template resolution failure
 		friend class boost::serialization::access; template<class ArchiveT> void serialize(ArchiveT & ar, unsigned int version){}
 	public:
-		ForceContainer(): size(0), synced(true),moveRotUsed(false),syncCount(0){
+		ForceContainer(): size(0), synced(true),moveRotUsed(false),syncCount(0), lastReset(0){
 			nThreads=omp_get_max_threads();
 			for(int i=0; i<nThreads; i++){
 				_forceData.push_back(vvector()); _torqueData.push_back(vvector());
@@ -120,7 +120,8 @@
 			}
 			synced=true; syncCount++;
 		}
-		unsigned long syncCount; 
+		unsigned long syncCount;
+		long lastReset;
 
 		/* Change size of containers (number of bodies).
 		 * Locks globalMutex, since on threads modifies other threads' data.
@@ -140,7 +141,7 @@
 		}
 		/*! Reset all data, also reset summary forces/torques and mark the container clean. */
 		// perhaps should be private and friend Scene or whatever the only caller should be
-		void reset(){
+		void reset(long iter){
 			for(int thread=0; thread<nThreads; thread++){
 				memset(&_forceData [thread][0],0,sizeof(Vector3r)*size);
 				memset(&_torqueData[thread][0],0,sizeof(Vector3r)*size);
@@ -156,6 +157,7 @@
 				memset(&_rot   [0], 0,sizeof(Vector3r)*size);
 			}
 			synced=true; moveRotUsed=false;
+			lastReset=iter;
 		}
 		//! say for how many threads we have allocated space
 		const int& getNumAllocatedThreads() const {return nThreads;}
@@ -180,7 +182,7 @@
 		// dummy function to avoid template resolution failure
 		friend class boost::serialization::access; template<class ArchiveT> void serialize(ArchiveT & ar, unsigned int version){}
 	public:
-		ForceContainer(): size(0), moveRotUsed(false), syncCount(0){}
+		ForceContainer(): size(0), moveRotUsed(false), syncCount(0), lastReset(0){}
 		const Vector3r& getForce(Body::id_t id){ensureSize(id); return _force[id];}
 		void  addForce(Body::id_t id,const Vector3r& f){ensureSize(id); _force[id]+=f;}
 		const Vector3r& getTorque(Body::id_t id){ensureSize(id); return _torque[id];}
@@ -196,7 +198,7 @@
 		const Vector3r& getRotSingle   (Body::id_t id){ ensureSize(id); return _rot   [id]; }
 
 		//! Set all forces to zero
-		void reset(){
+		void reset(long iter){
 			memset(&_force [0],0,sizeof(Vector3r)*size);
 			memset(&_torque[0],0,sizeof(Vector3r)*size);
 			if(moveRotUsed){
@@ -204,10 +206,13 @@
 				memset(&_rot   [0],0,sizeof(Vector3r)*size);
 				moveRotUsed=false;
 			}
+			lastReset=iter;
 		}
 		//! No-op for API compatibility with the threaded version
 		void sync(){return;}
 		unsigned long syncCount;
+		// interaction in which the container was last reset; used by NewtonIntegrator to detect whether ForceResetter was not forgotten
+		long lastReset;
 		/*! Resize the container; this happens automatically,
 		 * but you may want to set the size beforehand to avoid resizes as the simulation grows. */
 		void resize(size_t newSize){

=== modified file 'examples/gts-horse/gts-horse.py'
--- examples/gts-horse/gts-horse.py	2010-10-29 10:12:44 +0000
+++ examples/gts-horse/gts-horse.py	2010-10-30 17:08:51 +0000
@@ -44,16 +44,14 @@
 		[Law2_Dem3DofGeom_FrictPhys_CundallStrack()],
 	),
 	GravityEngine(gravity=[0,0,-1e4]),
-	NewtonIntegrator(damping=.1)
+	NewtonIntegrator(damping=.1),
+	PyRunner(iterPeriod=10000,command='timing.stats(); O.pause();')
 ]
 collider.sweepLength,collider.nBins,collider.binCoeff=.1*dim0/30.5,10,2
 O.dt=1.5*utils.PWaveTimeStep()
 O.saveTmp()
 O.timingEnabled=True
 
+from yade import timing
 from yade import qt
 qt.View()
-
-from yade import timing
-O.run(10000,True)
-timing.stats()

=== modified file 'pkg/common/ForceResetter.cpp'
--- pkg/common/ForceResetter.cpp	2010-10-29 10:12:44 +0000
+++ pkg/common/ForceResetter.cpp	2010-10-30 17:08:51 +0000
@@ -4,7 +4,7 @@
 YADE_PLUGIN((ForceResetter));
 
 void ForceResetter::action(){
-	scene->forces.reset();
+	scene->forces.reset(scene->iter);
 	if(scene->trackEnergy) scene->energy->resetResettables();
 }
 

=== modified file 'pkg/common/RotationEngine.cpp'
--- pkg/common/RotationEngine.cpp	2010-10-13 16:23:08 +0000
+++ pkg/common/RotationEngine.cpp	2010-10-30 17:08:51 +0000
@@ -9,16 +9,16 @@
 
 #include<yade/pkg-common/LinearInterpolate.hpp>
 
-YADE_PLUGIN((RotationEngine)(SpiralEngine)(InterpolatingSpiralEngine));
+YADE_PLUGIN((RotationEngine)(HelixEngine)(InterpolatingHelixEngine));
 
-void InterpolatingSpiralEngine::action(){
+void InterpolatingHelixEngine::action(){
 	Real virtTime=wrap ? Shop::periodicWrap(scene->time,*times.begin(),*times.rbegin()) : scene->time;
 	angularVelocity=linearInterpolate<Real,Real>(virtTime,times,angularVelocities,_pos);
 	linearVelocity=angularVelocity*slope;
-	SpiralEngine::action();
+	HelixEngine::action();
 }
 
-void SpiralEngine::action(){
+void HelixEngine::action(){
 	const Real& dt=scene->dt;
 	axis.normalize();
 	Quaternionr q(AngleAxisr(angularVelocity*dt,axis));

=== modified file 'pkg/common/RotationEngine.hpp'
--- pkg/common/RotationEngine.hpp	2010-10-13 16:23:08 +0000
+++ pkg/common/RotationEngine.hpp	2010-10-30 17:08:51 +0000
@@ -23,12 +23,12 @@
 };
 REGISTER_SERIALIZABLE(RotationEngine);
 
-/* Engine applying both rotation and translation, along the same axis, whence the name SpiralEngine
+/* Engine applying both rotation and translation, along the same axis, whence the name HelixEngine
  */
-class SpiralEngine:public PartialEngine{
+class HelixEngine:public PartialEngine{
 	public:
 	virtual void action();
-	YADE_CLASS_BASE_DOC_ATTRS(SpiralEngine,PartialEngine,"Engine applying both rotation and translation, along the same axis, whence the name SpiralEngine",
+	YADE_CLASS_BASE_DOC_ATTRS(HelixEngine,PartialEngine,"Engine applying both rotation and translation, along the same axis, whence the name HelixEngine",
 		((Real,angularVelocity,0,,"Angular velocity [rad/s]"))
 		((Real,linearVelocity,0,,"Linear velocity [m/s]"))
 		((Vector3r,axis,Vector3r::UnitX(),,"Axis of translation and rotation; will be normalized by the engine."))
@@ -36,7 +36,7 @@
 		((Real,angleTurned,0,,"How much have we turned so far. |yupdate| [rad]"))
 	);
 };
-REGISTER_SERIALIZABLE(SpiralEngine);
+REGISTER_SERIALIZABLE(HelixEngine);
 
 /*! Engine applying spiral motion, finding current angular velocity by linearly interpolating in
  * times and velocities and translation by using slope parameter.
@@ -45,12 +45,12 @@
  * after the last time point. If wrap is specified, time will wrap around the last times value to the first one (note that no interpolation
  * between last and first values is done).
  * */
-class InterpolatingSpiralEngine: public SpiralEngine{
+class InterpolatingHelixEngine: public HelixEngine{
 	//! holder of interpolation state, should not be touched by the user.
 	size_t _pos;
 	public:
 		virtual void action();
-	YADE_CLASS_BASE_DOC_ATTRS_CTOR(InterpolatingSpiralEngine,SpiralEngine,"Engine applying spiral motion, finding current angular velocity by linearly interpolating in times and velocities and translation by using slope parameter. \n\n The interpolation assumes the margin value before the first time point and last value after the last time point. If wrap is specified, time will wrap around the last times value to the first one (note that no interpolation between last and first values is done).",
+	YADE_CLASS_BASE_DOC_ATTRS_CTOR(InterpolatingHelixEngine,HelixEngine,"Engine applying spiral motion, finding current angular velocity by linearly interpolating in times and velocities and translation by using slope parameter. \n\n The interpolation assumes the margin value before the first time point and last value after the last time point. If wrap is specified, time will wrap around the last times value to the first one (note that no interpolation between last and first values is done).",
 		((vector<Real>,times,,,"List of time points at which velocities are given; must be increasing [s]"))
 		((vector<Real>,angularVelocities,,,"List of angular velocities; manadatorily of same length as times. [rad/s]"))
 		((bool,wrap,false,,"Wrap t if t>times_n, i.e. t_wrapped=t-N*(times_n-times_0)"))
@@ -58,7 +58,7 @@
 		/*ctor*/ _pos=0;
 	);
 };
-REGISTER_SERIALIZABLE(InterpolatingSpiralEngine);
+REGISTER_SERIALIZABLE(InterpolatingHelixEngine);
 
 
 

=== modified file 'pkg/dem/NewtonIntegrator.cpp'
--- pkg/dem/NewtonIntegrator.cpp	2010-10-26 13:41:30 +0000
+++ pkg/dem/NewtonIntegrator.cpp	2010-10-30 17:08:51 +0000
@@ -62,7 +62,8 @@
 void NewtonIntegrator::action()
 {
 	scene->forces.sync();
-	Real dt=scene->dt;
+	if(warnNoForceReset && scene->forces.lastReset<scene->iter) LOG_WARN("O.forces last reset in step "<<scene->forces.lastReset<<", while the current step is "<<scene->iter<<". Did you forget to include ForceResetter in O.engines?");
+	const Real& dt=scene->dt;
 	if(scene->isPeriodic && homotheticCellResize>=0){
 		LOG_WARN("Newton.homotheticCellResize is deprecated, use Cell.homoDeform instead. Setting Cell.homoDeform for you now, but the compatibility interface will be removed in the future.");
 		scene->cell->homoDeform=(homotheticCellResize==0?Cell::HOMO_NONE:(homotheticCellResize==1?Cell::HOMO_VEL:Cell::HOMO_VEL_2ND));

=== modified file 'pkg/dem/NewtonIntegrator.hpp'
--- pkg/dem/NewtonIntegrator.hpp	2010-10-26 13:41:30 +0000
+++ pkg/dem/NewtonIntegrator.hpp	2010-10-30 17:08:51 +0000
@@ -55,6 +55,7 @@
 		((Matrix3r,prevVelGrad,Matrix3r::Zero(),,"Store previous velocity gradient (:yref:`Cell::velGrad`) to track acceleration. |yupdate|"))
 		((vector<shared_ptr<BodyCallback> >,callbacks,,,"List (std::vector in c++) of :yref:`BodyCallbacks<BodyCallback>` which will be called for each body as it is being processed."))
 		((Vector3r,prevCellSize,Vector3r(NaN,NaN,NaN),Attr::hidden,"cell size from previous step, used to detect change and find max velocity"))
+		((bool,warnNoForceReset,true,,"Warn when forces were not resetted in this step by :yref:`ForceResetter`; this mostly points to :yref:`ForceResetter` being forgotten incidentally and should be disabled only with a good reason."))
 		,
 		/*ctor*/
 			#ifdef YADE_OPENMP

=== modified file 'pkg/dem/SpherePack.cpp'
--- pkg/dem/SpherePack.cpp	2010-10-13 16:23:08 +0000
+++ pkg/dem/SpherePack.cpp	2010-10-30 17:08:51 +0000
@@ -273,4 +273,3 @@
 	return pack.size();
 }
 
-

=== modified file 'pkg/dem/SpherePack.hpp'
--- pkg/dem/SpherePack.hpp	2010-10-13 16:23:08 +0000
+++ pkg/dem/SpherePack.hpp	2010-10-30 17:08:51 +0000
@@ -93,6 +93,10 @@
 		Vector3r mid=midPt(); Quaternionr q(AngleAxisr(angle,axis)); FOREACH(Sph& s, pack) s.c=q*(s.c-mid)+mid;
 	}
 	void scale(Real scale){ Vector3r mid=midPt(); cellSize*=scale; FOREACH(Sph& s, pack) {s.c=scale*(s.c-mid)+mid; s.r*=abs(scale); } }
+	#if 0
+		void shrinkMaxRelOverlap(Real maxRelOverlap);
+		Real maxRelOverlap();
+	#endif
 
 	// iteration 
 	size_t len() const{ return pack.size(); }

=== modified file 'py/_eudoxos.cpp'
--- py/_eudoxos.cpp	2010-09-30 18:00:41 +0000
+++ py/_eudoxos.cpp	2010-10-30 17:08:51 +0000
@@ -137,12 +137,12 @@
 #endif
 #include<yade/lib-smoothing/WeightedAverage2d.hpp>
 /* Fastly locate interactions within given distance from a point in 2d (projected to plane) */
-struct SpiralInteractionLocator2d{
+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;
-	SpiralInteractionLocator2d(Real dH_dTheta, int _axis, Real periodStart, Real theta0, Real thetaMin, Real thetaMax): axis(_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);
@@ -324,13 +324,13 @@
 		.add_property("count",&InteractionLocator::getCnt,"Number of interactions held")
 	;
 #endif
-	py::class_<SpiralInteractionLocator2d>("SpiralInteractionLocator2d",
+	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",&SpiralInteractionLocator2d::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",&SpiralInteractionLocator2d::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\nAdditionaly, 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",&SpiralInteractionLocator2d::getLo,"Return lower corner of the rectangle containing all interactions.")
-		.add_property("hi",&SpiralInteractionLocator2d::getHi,"Return upper corner of the rectangle containing all interactions.");
+		.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\nAdditionaly, 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/post2d.py'
--- py/post2d.py	2010-05-05 21:36:25 +0000
+++ py/post2d.py	2010-10-30 17:08:51 +0000
@@ -2,18 +2,22 @@
 # 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
 """
 Module for 2d postprocessing, containing classes to project points from 3d to 2d in various ways,
-providing basic but flexible framework for extracting arbitrary scalar values from bodies and plotting the
-results. There are 2 basic components: flatteners and extractors.
+providing basic but flexible framework for extracting arbitrary scalar values from bodies/interactions
+and plotting the results. There are 2 basic components: flatteners and extractors.
+
+The algorithms operate on bodies (default) or interactions, depending on the ``intr`` parameter
+of post2d.data.
 
 Flatteners
 ==========
 Instance of classes that convert 3d (model) coordinates to 2d (plot) coordinates. Their interface is
-defined by the Flatten class (__call__, planar, normal).
+defined by the :yref:`yade.post2d.Flatten` class (``__call__``, ``planar``, ``normal``).
 
 Extractors
 ==========
-Callable objects returning scalar or vector value, given a body object. If a 3d vector is returned,
-Flattener.planar is called, which should return only in-plane components of the vector.
+Callable objects returning scalar or vector value, given a body/interaction object.
+If a 3d vector is returned, Flattener.planar is called, which should return only in-plane
+components of the vector.
 
 Example
 =======
@@ -60,29 +64,23 @@
 	"""Abstract class for converting 3d point into 2d. Used by post2d.data2d."""
 	def __init__(self): pass
 	def __call__(self,b):
-		"""Given a Body instance, should return either 2d coordinates as a 2-tuple, or None if the Body should be discarded.""" 
+		"Given a :yref:`Body` / :yref:`Interaction` instance, should return either 2d coordinates as a 2-tuple, or None if the Body should be discarded." 
 		pass
 	def planar(self,pos,vec):
 		"Given position and vector value, project the vector value to the flat plane and return its 2 in-plane components."
 	def normal(self,pos,vec):
 		"Given position and vector value, return lenght of the vector normal to the flat plane."
 
-class SpiralFlatten(Flatten):
-	"""Class converting 3d point to 2d based on projection from spiral.
+class HelixFlatten(Flatten):
+	"""Class converting 3d point to 2d based on projection from helix.
 	The y-axis in the projection corresponds to the rotation axis"""
 	def __init__(self,useRef,thetaRange,dH_dTheta,axis=2,periodStart=0):
 		"""
-		:parameters:
-			`useRef`: bool
-				use reference positions rather than actual positions
-			`thetaRange`: (thetaMin,thetaMax) tuple
-				bodies outside this range will be discarded
-			`dH_dTheta`:float
-				inclination of the spiral (per radian)
-			`axis`: {0,1,2}
-				axis of rotation of the spiral
-			`periodStart`: float
-				height of the spiral for zero angle
+		:param bool useRef:       use reference positions rather than actual positions
+		:param (θmin,θmax) thetaRange: bodies outside this range will be discarded
+		:param float dH_dTheta:   inclination of the spiral (per radian)
+		:param {0,1,2} axis:      axis of rotation of the spiral
+		:param float periodStart: height of the spiral for zero angle
 		"""
 		self.useRef,self.thetaRange,self.dH_dTheta,self.axis,self.periodStart=useRef,thetaRange,dH_dTheta,axis,periodStart
 		self.ax1,self.ax2=(axis+1)%3,(axis+2)%3
@@ -105,7 +103,7 @@
 		
 
 class CylinderFlatten(Flatten):
-	"""Class for converting 3d point to 2d based on projection from circle.
+	"""Class for converting 3d point to 2d based on projection onto plane from circle.
 	The y-axis in the projection corresponds to the rotation axis; the x-axis is distance form the axis.
 	"""
 	def __init__(self,useRef,axis=2):
@@ -135,46 +133,39 @@
 		
 
 class AxisFlatten(Flatten):
-	def __init__(self,useRef,axis=2):
+	def __init__(self,useRef=False,axis=2):
 		"""
-		:parameters:
-			`useRef`: bool
-				use reference positions rather than actual positions.
-			`axis`: {0,1,2}
-				axis normal to the plane; the return value will be simply position with this component dropped.
+		:param bool useRef: use reference positions rather than actual positions (only meaningful when operating on Bodies)
+		:param {0,1,2}	axis: axis normal to the plane; the return value will be simply position with this component dropped.
 		"""
 		if axis not in (0,1,2): raise IndexError("axis must be one of 0,1,2 (not %d)"%axis)
 		self.useRef,self.axis=useRef,axis
 		self.ax1,self.ax2=(self.axis+1)%3,(self.axis+2)%3
 	def __call__(self,b):
-		p=b.state.refPos if self.useRef else b.state.pos
+		p=((b.state.refPos if self.useRef else b.state.pos) if isinstance(b,Body) else b.geom.contactPoint)
 		return (p[self.ax1],p[self.ax2])
 	def planar(self,pos,vec):
 		return vec[self.ax1],vec[self.ax2]
 	def normal(self,pos,vec):
 		return vec[self.axis]
 
-def data(extractor,flattener,onlyDynamic=True,stDev=None,relThreshold=3.,div=(50,50),margin=(0,0)):
-	"""Filter all bodies (spheres only), project them to 2d and extract required scalar value;
+def data(extractor,flattener,intr=False,onlyDynamic=True,stDev=None,relThreshold=3.,div=(50,50),margin=(0,0),radius=1):
+	"""Filter all bodies/interactions, project them to 2d and extract required scalar value;
 	return either discrete array of positions and values, or smoothed data, depending on whether the stDev
 	value is specified.
 
-	:parameters:
-		`extractor`: callable
-			receives Body instance, should return scalar, a 2-tuple (vector fields) or None (to skip that body)
-		`flattener`: callable
-			receives Body instance and returns its 2d coordinates or None (to skip that body)
-		`onlyDynamic`: bool
-			skip all non-dynamic bodies
-		`stDev`: float or *None*
-			standard deviation for averaging, enables smoothing; None (default) means raw mode.
-		`relThreshold`: float
-			threshold for the gaussian weight function relative to stDev (smooth mode only)
-		`div`: (int,int)
-			number of cells for the gaussian grid (smooth mode only)
-		`margin`: (float,float)
-			margin around bounding box for data (smooth mode only)
+	The ``intr`` parameter determines whether we operate on bodies or interactions;
+	the extractor provided should expect to receive body/interaction.
 
+	:param callable extractor: receives :yref:`Body` (or :yref:`Interaction`, if ``intr`` is ``True``) instance, should return scalar, a 2-tuple (vector fields) or None (to skip that body/interaction)
+	:param callable flattener: :yref:`yade.post2d.Flatten` instance, receiving body/interaction, returns its 2d coordinates or ``None`` (to skip that body/interaction)
+	:param bool intr: operate on interactions rather than bodies
+	:param bool onlyDynamic: skip all non-dynamic bodies
+	:param float/None stDev: standard deviation for averaging, enables smoothing; ``None`` (default) means raw mode, where discrete points are returned
+	:param float relThreshold: threshold for the gaussian weight function relative to stDev (smooth mode only)
+	:param (int,int) div: number of cells for the gaussian grid (smooth mode only)
+	:param (float,float) margin: x,y margins around bounding box for data (smooth mode only)
+	:param float/callable radius: Fallback value for radius (for raw plotting) for non-spherical bodies or interactions; if a callable, receives body/interaction and returns radius
 	:return: dictionary
 	
 	Returned dictionary always containing keys 'type' (one of 'rawScalar','rawVector','smoothScalar','smoothVector', depending on value of smooth and on return value from extractor), 'x', 'y', 'bbox'.
@@ -186,9 +177,9 @@
 	from miniEigen import Vector3
 	xx,yy,dd1,dd2,rr=[],[],[],[],[]
 	nDim=0
-	for b in O.bodies:
-		if onlyDynamic and not b.dynamic: continue
-		if not isinstance(b.shape,Sphere): continue
+	objects=O.interactions if intr else O.bodies
+	for b in objects:
+		if not intr and onlyDynamic and not b.dynamic: 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
@@ -200,7 +191,11 @@
 			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.shape.radius)
+		if stDev==None: # radii are needed in the raw mode exclusively
+			if not intr and isinstance(b.shape,Sphere): r=b.shape.radius
+			else: r=(radius(b) if callable(radius) else radius)
+			rr.append(r)
+		xx.append(xy[0]); yy.append(xy[1]);
 	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}
@@ -226,7 +221,7 @@
 	if nDim==1: return {'type':'smoothScalar','x':xxx,'y':yyy,'val':ddd,'bbox':(llo,hhi)} 
 	else: return {'type':'smoothVector','x':xxx,'y':yyy,'valX':ddd,'valY':ddd2,'bbox':(llo,hhi)}
 	
-def plot(data,axes=None,alpha=.5,clabel=True,**kw):
+def plot(data,axes=None,alpha=.5,clabel=True,cbar=False,**kw):
 	"""Given output from post2d.data, plot the scalar as discrete or smooth plot.
 
 	For raw discrete data, plot filled circles with radii of particles, colored by the scalar value.
@@ -235,15 +230,12 @@
 
 	For vector data (raw or smooth), plot quiver (vector field), with arrows colored by the magnitude.
 
-	:parameters:
-		`axes`: matplotlib.axes instance
-			axes where the figure will be plotted; if None, will be created from scratch.
-		`data`:
-			value returned by :yref:`yade.post2d.data`
-		`clable`: bool
-			show contour labels (smooth mode only)
+	:param axes: matplotlib.axes\ instance where the figure will be plotted; if None, will be created from scratch.
+	:param data: value returned by :yref:`yade.post2d.data`
+	:param bool clabel: show contour labels (smooth mode only)
+	:param bool cbar: show colorbar (equivalent to calling pylab.colorbar(mappable) on the returned mappable)
 
-	:return: tuple of (axes,mappable); mappable can be used in further calls to pylab.colorbar.
+	:return: tuple of ``(axes,mappable)``; mappable can be used in further calls to pylab.colorbar.
 	"""
 	import pylab,math
 	if not axes: axes=pylab.gca()
@@ -258,6 +250,7 @@
 		bb=coll.get_datalim(coll.get_transform())
 		axes.add_collection(coll)
 		axes.set_xlim(bb.xmin,bb.xmax); axes.set_ylim(bb.ymin,bb.ymax)
+		if cbar: axes.get_figure().colorbar(coll)
 		axes.grid(True); axes.set_aspect('equal')
 		return axes,coll
 	elif data['type']=='smoothScalar':
@@ -267,6 +260,7 @@
 		axes.update_datalim(loHi)
 		if clabel: axes.clabel(ct,inline=1,fontsize=10)
 		axes.set_xlim(loHi[0][0],loHi[1][0]); axes.set_ylim(loHi[0][1],loHi[1][1])
+		if cbar: axes.get_figure().colorbar(img)
 		axes.grid(True); axes.set_aspect('equal')
 		return axes,img
 	elif data['type'] in ('rawVector','smoothVector'):
@@ -278,6 +272,7 @@
 		quiv=axes.quiver(data['x'],data['y'],data['valX'],data['valY'],scalars,**kw)
 		#axes.update_datalim(loHi)
 		axes.set_xlim(loHi[0][0],loHi[1][0]); axes.set_ylim(loHi[0][1],loHi[1][1])
+		if cbar: axes.get_figure().colorbar(coll)
 		axes.grid(True); axes.set_aspect('equal')
 		return axes,quiv
 

=== modified file 'py/system.py'
--- py/system.py	2010-10-26 13:41:30 +0000
+++ py/system.py	2010-10-30 17:08:51 +0000
@@ -145,6 +145,9 @@
 	'Law2_ScGeom_FrictPhys_Basic':'Law2_ScGeom_FrictPhys_CundallStrack', # Wed Oct 13 17:40:42 2010, bchareyre@dt-rv020
 	'Law2_Dem3DofGeom_FrictPhys_Basic':'Law2_Dem3DofGeom_FrictPhys_CundallStrack', # Wed Oct 13 17:45:32 2010, bchareyre@dt-rv020
 	'Law2_ScGeom_CohFrictPhys_ElasticPlastic':'Law2_ScGeom_CohFrictPhys_CohesionMoment', # Wed Oct 13 17:47:09 2010, bchareyre@dt-rv020
+	'SpiralEngine':'HelixEngine', # Sat Oct 30 05:52:06 2010, vaclav@flux
+	'InterpolatingSpiralEngine':'InterpolatingHelixEngine', # Sat Oct 30 05:52:21 2010, vaclav@flux
+	'SpiralInteractionLocator2d':'HelixInteractionLocator2d', # Sat Oct 30 05:53:04 2010, vaclav@flux
 	### END_RENAMED_CLASSES_LIST ### (do not delete this line; scripts/rename-class.py uses it
 }
 

=== modified file 'py/utils.py'
--- py/utils.py	2010-10-18 19:27:07 +0000
+++ py/utils.py	2010-10-30 17:08:51 +0000
@@ -350,35 +350,21 @@
 	Create arbitrarily-aligned cylinder composed of facets, with given center, radius, height and orientation.
 	Return List of facets forming the cylinder;
 	
-	:Parameters:
-			`center`: Vector3
-				center of the created cylinder
-			`radius`: float
-				cylinder radius
-			`height`: float
-				cylinder height
-			`orientation`: Quaternion
-				orientation of the cylinder
-			`segmentsNumber`: int
-				number of edges on the cylinder surface (>=5)
-			`wallMask`: bitmask
-				determines which walls will be created, in the order up (1), down (2), side (4). The numbers are ANDed; the default 7 means to create all walls;
-			`angleRange`: this variable allows to create only part of cylinder, 2.0*math.pi means the whole cylinder, 1.0*math.pi - the half etc;
-			`**kw`: (unused keyword arguments)
-				passed to utils.facet;
+	:param Vector3 center: center of the created cylinder
+	:param float radius:  cylinder radius
+	:param float height: cylinder height
+	:param Quaternion orientation: orientation of the cylinder; the reference orientation has axis along the $+x$ axis.
+	:param int segmentsNumber: number of edges on the cylinder surface (>=5)
+	:param bitmask wallMask: determines which walls will be created, in the order up (1), down (2), side (4). The numbers are ANDed; the default 7 means to create all walls
+	:param float angleRange: allows to create only part of cylinder, 2.0*math.pi means the whole cylinder, 1.0*math.pi - the half etc;
+	:param **kw: (unused keyword arguments) passed to utils.facet;
 	"""
 	
-	#Defense from zero dimensions
-	if (segmentsNumber<3):
-		raise RuntimeError("The segmentsNumber should be at least 3");
-	if (height<=0):
-		raise RuntimeError("The height should have the positive value");
-	if (radius<=0):
-		raise RuntimeError("The radius should have the positive value");
-	if (wallMask>7):
-		print "wallMask must be 7 or less"
-		wallMask=7
-	# ___________________________
+	# check zero dimentions
+	if (segmentsNumber<3): raise RuntimeError("The segmentsNumber should be at least 3");
+	if (height<=0): raise RuntimeError("The height should have the positive value");
+	if (radius<=0): raise RuntimeError("The radius should have the positive value");
+
 	import numpy
 	anglesInRad = numpy.linspace(0, angleRange, segmentsNumber+1, endpoint=True)
 	P1=[]; P2=[]