← Back to team overview

yade-dev team mailing list archive

[Branch ~yade-pkg/yade/git-trunk] Rev 3687: Merge branch 'master' of github.com:yade/trunk

 

Merge authors:
  Anton Gladky (gladky-anton)
  Bruno Chareyre (bruno-chareyre)
  Klaus Thoeni (klaus.thoeni)
------------------------------------------------------------
revno: 3687 [merge]
committer: Jan Stransky <jan.stransky@xxxxxxxxxxx>
timestamp: Sun 2013-09-08 13:19:06 +0200
message:
  Merge branch 'master' of github.com:yade/trunk
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
added:
  scripts/checks-and-tests/checks/DEM-PFV-check.py
  scripts/checks-and-tests/checks/data/100spheres
modified:
  CMakeLists.txt
  cMake/FindMetis.cmake
  core/Clump.cpp
  core/ForceContainer.hpp
  core/main/main.py.in
  doc/references.bib
  doc/sphinx/formulation.rst
  doc/sphinx/introduction.rst
  doc/sphinx/prog.rst
  doc/sphinx/references.bib
  doc/sphinx/templates/index.html
  doc/sphinx/user.rst
  doc/yade-articles.bib
  doc/yade-conferences.bib
  doc/yade-theses.bib
  pkg/common/Cylinder.hpp
  pkg/dem/ConcretePM.cpp
  pkg/dem/DemXDofGeom.cpp
  pkg/dem/DemXDofGeom.hpp
  pkg/dem/DomainLimiter.cpp
  pkg/dem/FlowEngine.cpp
  pkg/dem/FlowEngine.hpp
  pkg/dem/HertzMindlin.cpp
  pkg/dem/HertzMindlin.hpp
  pkg/dem/Shop.cpp
  pkg/dem/Shop.hpp
  pkg/dem/VTKRecorder.hpp
  pkg/dem/ViscoelasticCapillarPM.cpp
  pkg/dem/ViscoelasticPM.cpp
  pkg/dem/ViscoelasticPM.hpp
  py/CMakeLists.txt
  py/_extraDocs.py
  py/_utils.cpp
  py/system.py
  py/tests/__init__.py
  scripts/checks-and-tests/checks/README
  scripts/checks-and-tests/checks/checkGravity.py
  scripts/checks-and-tests/checks/checkList.py
  scripts/checks-and-tests/checks/checkTestDummy.py
  scripts/checks-and-tests/checks/checkTestTriax.py
  scripts/checks-and-tests/checks/checkWirePM.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
=== modified file 'CMakeLists.txt'
--- CMakeLists.txt	2013-08-15 12:52:44 +0000
+++ CMakeLists.txt	2013-09-05 07:52:37 +0000
@@ -380,7 +380,6 @@
 SET (pyExecutable ${PYTHON_EXECUTABLE})
 SET (profile "default")
 SET (sourceRoot "${CMAKE_CURRENT_SOURCE_DIR}")
-SET (libstdcxx "/usr/lib/libstdc++.so.6")     #This is a hack, which is not needed for modern systems. Should be deleted.
 #====================================
 
 CONFIGURE_FILE(core/main/yade-batch.in "${CMAKE_BINARY_DIR}/bins/yade${SUFFIX}-batch")
@@ -409,6 +408,7 @@
 MESSAGE(STATUS "Disabled features:${DISABLED_FEATS}")
 IF (DEBUG)
   MESSAGE(STATUS "Debug build")
+  SET (debugbuild " (debug build)")
 ELSE (DEBUG)
   MESSAGE(STATUS "Optimized build")
 ENDIF (DEBUG)

=== modified file 'cMake/FindMetis.cmake'
--- cMake/FindMetis.cmake	2013-06-26 18:15:55 +0000
+++ cMake/FindMetis.cmake	2013-08-30 13:49:57 +0000
@@ -5,8 +5,8 @@
 #  METIS_LIBRARY, libraries to link against to use GL2PS.
 #  METIS_FOUND, If false, do not try to use GL2PS.
 
-FIND_PATH(METIS_INCLUDE_DIR metis.h)
-FIND_LIBRARY(METIS_LIBRARY NAMES metis )
+FIND_PATH(METIS_INCLUDE_DIR metis.h PATHS /usr/include/metis)
+FIND_LIBRARY(METIS_LIBRARY NAMES metis PATHS /usr/lib)
 
 # handle the QUIETLY and REQUIRED arguments and set LOKI_FOUND to TRUE if
 # all listed variables are TRUE

=== modified file 'core/Clump.cpp'
--- core/Clump.cpp	2013-07-05 07:33:47 +0000
+++ core/Clump.cpp	2013-08-30 06:19:46 +0000
@@ -119,7 +119,7 @@
 				const Sphere* sphere1 = YADE_CAST<Sphere*> (subBody1->shape.get());
 				const Sphere* sphere2 = YADE_CAST<Sphere*> (subBody2->shape.get());
 				Real un = (sphere1->radius+sphere2->radius) - dist.norm();
-				if (un > 0.) {intersecting = true; break;}
+				if (un > -0.001*min(sphere1->radius,sphere2->radius)) {intersecting = true; break;}
 			}
 		}
 	}

=== modified file 'core/ForceContainer.hpp'
--- core/ForceContainer.hpp	2013-08-22 18:35:55 +0000
+++ core/ForceContainer.hpp	2013-08-26 21:41:10 +0000
@@ -72,7 +72,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), permSize(0),syncedSizes(true),synced(true),moveRotUsed(false),_zero(Vector3r::Zero()),syncCount(0),lastReset(0){
+		ForceContainer(): size(0), permSize(0),syncedSizes(true),synced(true),moveRotUsed(false),permForceUsed(false),_zero(Vector3r::Zero()),syncCount(0),lastReset(0){
 			nThreads=omp_get_max_threads();
 			for(int i=0; i<nThreads; i++){
 				_forceData.push_back(vvector()); _torqueData.push_back(vvector());
@@ -220,7 +220,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), permSize(0), moveRotUsed(false), syncCount(0), lastReset(0){}
+		ForceContainer(): size(0), permSize(0), moveRotUsed(false), permForceUsed(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];}

=== modified file 'core/main/main.py.in'
--- core/main/main.py.in	2013-05-07 09:21:35 +0000
+++ core/main/main.py.in	2013-09-05 07:52:37 +0000
@@ -11,7 +11,7 @@
 # get yade path (allow YADE_PREFIX to override)
 prefix,suffix='${runtimePREFIX}' if not os.environ.has_key('YADE_PREFIX') else os.environ['YADE_PREFIX'],'${SUFFIX}'
 # duplicate some items from yade.config here, so that we can increase verbosity when the c++ part is booting
-features,version='${features}'.split(' '),'${realVersion}'
+features,version,debugbuild='${features}'.split(' '),'${realVersion}',' ${debugbuild}'
 
 libPATH='${LIBRARY_OUTPUT_PATH}'
 if (libPATH[1:] == '{LIBRARY_OUTPUT_PATH}'): libPATH='lib'
@@ -52,11 +52,17 @@
 par.add_argument('--performance',help='Starts a test to measure the productivity',dest='performance',action='store_true')
 par.add_argument('script',nargs='?',default='',type=str,help=argparse.SUPPRESS)
 par.add_argument('args',nargs=argparse.REMAINDER,help=argparse.SUPPRESS) # see argparse doc, par.disable_interspersed_args() from optargs module
+par.add_argument('-l',help='import libraries at startup before importing yade libs. May be used when the ordering of imports matter (see e.g. https://bugs.launchpad.net/yade/+bug/1183402/comments/3). The option can be use multiple times, as in "yade -llib1 -llib2"',default=None,action='append',dest='impLibraries',type=str)
 opts=par.parse_args()
 args = opts.args
 
+if opts.impLibraries:
+	sys.path.append('.')
+	for lib in opts.impLibraries:
+		__import__(lib)
+
 if opts.version:
-	print 'Yade version: %s'%version
+	print 'Yade version: %s%s'%(version,debugbuild)
 	sys.exit(0)
 
 if opts.script:
@@ -109,7 +115,7 @@
 else: os.environ['OMP_NUM_THREADS']='1'
 
 if __name__ == "__main__": # do not print this while importing yade in other python application
-	sys.stderr.write('Welcome to Yade '+version+'\n')
+	sys.stderr.write('Welcome to Yade '+version+debugbuild+'\n')
 
 # initialization and c++ plugins import
 import yade

=== modified file 'doc/references.bib'
--- doc/references.bib	2013-08-14 08:01:55 +0000
+++ doc/references.bib	2013-08-28 10:26:24 +0000
@@ -580,18 +580,6 @@
 	url = "http://www.refdoc.fr/Detailnotice?idarticle=7435486";
 }
 
-@article{Thoeni2013,
-	author = "K. Thoeni and C. Lambert and A. Giacomini and S.W. Sloan",
-	doi = "10.1016/j.compgeo.2012.10.014",
-	issn = "0266-352X",
-	journal = "Computers and Geotechnics",
-	pages = "158--169",
-	title = "{Discrete modelling of hexagonal wire meshes with a stochastically distorted contact model}",
-	url = "http://www.sciencedirect.com/science/article/pii/S0266352X12002121";,
-	volume = "49",
-	year = "2013"
-}
-
 @article{Luding2008,
 	year={2008},
 	issn={1434-5021},

=== modified file 'doc/sphinx/formulation.rst'
--- doc/sphinx/formulation.rst	2013-05-14 21:24:11 +0000
+++ doc/sphinx/formulation.rst	2013-08-29 10:30:31 +0000
@@ -314,8 +314,6 @@
 -------------
 In order to keep $\vec{u}_T$ consistent (e.g. that $\vec{u}_T$ must be constant if two spheres retain mutually constant configuration but move arbitrarily in space), then either $\vec{u}_T$ must track spheres' spatial motion or must (somehow) rely on sphere-local data exclusively.
 
-These two possibilities lead to two algorithms of computing shear strains. They should give the same results (disregarding numerical imprecision), but there is a trade-off between computational cost of the incremental method and robustness of the total one.
-
 Geometrical meaning of shear strain is shown in `fig-shear-2d`_.
 
 .. _fig-shear-2d:
@@ -323,9 +321,7 @@
 	
 	Evolution of shear displacement $\vec{u}_T$ due to mutual motion of spheres, both linear and rotational. Left configuration is the initial contact, right configuration is after displacement and rotation of one particle.
 
-Incremental algorithm
-^^^^^^^^^^^^^^^^^^^^^
-The incremental algorithm is widely used in DEM codes and is described frequently ([Luding2008]_, [Alonso2004]_). Yade implements this algorithm in the :yref:`ScGeom` class. At each step, shear displacement $\uT$ is updated; the update increment can be decomposed in 2 parts: motion of the interaction (i.e. $\vec{C}$ and $\vec{n}$) in global space and mutual motion of spheres.
+The classical incremental algorithm is widely used in DEM codes and is described frequently ([Luding2008]_, [Alonso2004]_). Yade implements this algorithm in the :yref:`ScGeom` class. At each step, shear displacement $\uT$ is updated; the update increment can be decomposed in 2 parts: motion of the interaction (i.e. $\vec{C}$ and $\vec{n}$) in global space and mutual motion of spheres.
 
 #. Contact moves dues to changes of the spheres' positions $\vec{C}_1$ and $\vec{C}_2$, which updates current $\currC$ and $\currn$ as per :eq:`eq-contact-point` and :eq:`eq-contact-normal`. $\prevuT$ is perpendicular to the contact plane at the previous step $\prevn$ and must be updated so that $\prevuT+(\Delta\uT)=\curruT\perp\currn$; this is done by perpendicular projection to the plane first (which might decrease $|\uT|$) and adding what corresponds to spatial rotation of the interaction instead:
   
@@ -353,74 +349,6 @@
 
 .. math:: \curruT=\prevuT+(\Delta\uT)_1 + (\Delta\uT)_2 + (\Delta\uT)_3.
 
-.. _sect-formulation-total-shear:
-
-Total algorithm
-^^^^^^^^^^^^^^^
-The following algorithm, aiming at stabilization of response even with large rotation speeds or $\Delta t$ approaching stability limit, was designed in [Smilauer2010b]_. (A similar algorithm based on total formulation, which covers additionally bending and torsion, was proposed in [Wang2009]_.) It is based on tracking original contact points (with zero shear) in the particle-local frame.
-
-In this section, variable symbols implicitly denote their current values unless explicitly stated otherwise.
-
-Shear strain may have two sources: mutual rotation of spheres or transversal displacement of one sphere with respect to the other. Shear strain does not change if both spheres move or rotate but are not in linear or angular motion mutually. To accurately and reliably model this situation, for every new contact the initial contact point $\bar{\vec{C}}$ is mapped into local sphere coordinates ($\vec{p}_{01}$, $\vec{p}_{02}$). As we want to determine the distance between both points (i.e. how long the trajectory in on both spheres' surfaces together), the shortest path from current $\vec{C}$ to the initial locally mapped point on the sphere's surface is „unrolled“ to the contact plane ($\vec{p}'_{01}$, $\vec{p}'_{02}$); then we can measure their linear distance $\uT$ and define shear strain $\vec{\eps}_T=\uT/d_0$ (fig. `fig-shear-displacement`_).
-
-More formally, taking $\bar{\vec{C}}_i$, $\bar{q}_i$ for the sphere initial positions and orientations (as quaterions) in global coordinates, the initial sphere-local contact point *orientation* (relative to sphere-local axis $\hat{x}$) is remembered:
-
-.. math::
-	:nowrap:
-	
-	\begin{align*}
-		\bar{\vec{n}}&=\normalized{{\vec{C}}_1-{\vec{C}}_2}, \\
-		\bar{q}_{01}&=\Align(\hat x,\bar{q}_1^*\bar{\vec{n}} \bar{q}_1^{**}), \\ 
-		\bar{q}_{02}&=\Align(\hat x,\bar{q}_2^* (-\bar{\vec{n}}) \bar{q}_2^{**}).
-	\end{align*}
-	
-.. (See \autoref{sect-quaternions} for definition of $\Align$.)
-
-				
-After some spheres motion, the original point can be "unrolled" to the current contact plane:
-
-.. math::
-	:nowrap:
-	
-	\begin{align*}
-		q&=\Align(\vec{n},q_1 \bar{q}_{01} \hat x (q_1 \bar{q}_{01})^*) \quad\hbox{(auxiliary)} \\
-		\vec{p}'_{01}&=q_{\theta}d_1(q_{\vec{u}} \times \vec{n})
-	\end{align*}
-
-where $q_{\vec{u}}$, $q_{\theta}$ are axis and angle components of $q$ and $p_{01}'$ is the unrolled point. Similarly,
-
-.. math::
-	:nowrap:
-
-	\begin{align*}
-		q&=\Align(\vec{n},q_2 \bar{q}_{02} \hat x (q_2 \bar{q}_{02})^*) \\
-		\vec{p}'_{02}&=q_{\theta}d_1(q_{\vec{u}} \times (-\vec{n})).
-	\end{align*}
-
-Shear displacement and strain are then computed easily:
-
-.. math::
-	:nowrap:
-
-	\begin{align*}
-		\uT&=\vec{p}'_{02}-\vec{p}'_{01} \\
-		\vec{\eps}_T&=\frac{\uT}{d_0}
-	\end{align*}
-
-When using material law with plasticity in shear, it may be necessary to limit maximum shear strain, in which case the mapped points are moved closer together to the requested distance (without changing $\hat{\vec{u}}_T$). This allows us to remember the previous strain direction and also avoids summation of increments of plastic strain at every step (`fig-shear-slip`_).
-
-.. _fig-shear-displacement:
-.. figure:: fig/shear-displacement.*
-
-	Shear displacement computation for two spheres in relative motion.
-
-
-.. _fig-shear-slip:
-.. figure:: fig/shear-slip.*
-
-	Shear plastic slip for two spheres.
-
-This algorithm is straightforwardly modified to facet-sphere interactions. In Yade, it is implemented by :yref:`Dem3DofGeom` and related classes.
 
 .. _sect-formulation-stress-cundall:
 

=== modified file 'doc/sphinx/introduction.rst'
--- doc/sphinx/introduction.rst	2013-08-14 08:01:55 +0000
+++ doc/sphinx/introduction.rst	2013-08-29 10:30:31 +0000
@@ -343,7 +343,7 @@
 :yref:`IGeom`
 	holding geometrical configuration of the two particles in collision; it is updated automatically as the particles in question move and can be queried for various geometrical characteristics, such as penetration distance or shear strain.
 	
-	Based on combination of types of :yref:`Shapes<Shape>` of the particles, there might be different storage requirements; for that reason, a number of derived classes exists, e.g. for representing geometry of contact between :yref:`Sphere+Sphere<Dem3DofGeom_SphereSphere>`, :yref:`Facet+Sphere<Dem3DofGeom_FacetSphere>` etc.
+	Based on combination of types of :yref:`Shapes<Shape>` of the particles, there might be different storage requirements; for that reason, a number of derived classes exists, e.g. for representing geometry of contact between :yref:`Sphere+Sphere<ScGeom>`, :yref:`Cylinder+Sphere<CylScGeom>` etc. Note, however, that it is possible to represent many type of contacts with the basic sphere-sphere geometry (for instance in :yref:`Ig2_Wall_Sphere_ScGeom`).
 :yref:`IPhys`
 	representing non-geometrical features of the interaction; some are computed from :yref:`Materials<Material>` of the particles in contact using some averaging algorithm (such as contact stiffness from Young's moduli of particles), others might be internal variables like damage.
 

=== modified file 'doc/sphinx/prog.rst'
--- doc/sphinx/prog.rst	2013-08-14 08:01:55 +0000
+++ doc/sphinx/prog.rst	2013-08-29 10:30:31 +0000
@@ -872,7 +872,7 @@
 
 .. code-block:: c++
 
-	class Ig2_Facet_Sphere_Dem3DofGeom: public IGeomFunctor{
+	class Ig2_Facet_Sphere_ScGeom: public IGeomFunctor{
 	   public:
 
 	   // override the IGeomFunctor::go
@@ -914,7 +914,7 @@
 
 If no functor is able to accept given types (first condition violated) or multiple functors have the same distance (in condition 2), an exception is thrown.
 
-This resolution mechanism makes it possible, for instance, to have a hierarchy of :yref:`Dem3DofGeom` classes (for different combination of shapes: :yref:`Dem3DofGeom_SphereSphere`, :yref:`Dem3DofGeom_FacetSphere`, :yref:`Dem3DofGeom_WallSphere`), but only provide a :yref:`LawFunctor` accepting ``Dem3DofGeom``, rather than having different laws for each shape combination.
+This resolution mechanism makes it possible, for instance, to have a hierarchy of :yref:`ScGeom` classes (for different combination of shapes), but only provide a :yref:`LawFunctor` accepting ``ScGeom``, rather than having different laws for each shape combination.
 
 .. note:: Performance implications of dispatch resolution are relatively low. The dispatcher lookup is only done once, and uses fast lookup matrix (1D or 2D); then, the functor found for this type(s) is cached within the ``Interaction`` (or ``Body``) instance. Thus, regular functor call costs the same as dereferencing pointer and calling virtual method. There is `blueprint <https://blueprints.launchpad.net/yade/+spec/devirtualize-functor-calls>`__ to avoid virtual function call as well.
 

=== modified file 'doc/sphinx/references.bib'
--- doc/sphinx/references.bib	2013-06-06 09:27:41 +0000
+++ doc/sphinx/references.bib	2013-08-28 10:38:02 +0000
@@ -305,12 +305,5 @@
 	doi = "10.1016/S0378-4371(99)00183-1",
 	url = "http://www.sciencedirect.com/science/article/pii/S0378437199001831";,
 	author = "Y.C. Zhou and B.D. Wright and R.Y. Yang and B.H. Xu and A.B. Yu",
-	keywords = "Static sandpiles",
-	keywords = "Granular compaction",
-	keywords = "Dynamics and kinematics of a particle and a system of particles",
-	keywords = "Granular flow",
-	keywords = "Mixing",
-	keywords = "Segregation and stratification",
-	keywords = "Granular systems "
 }
 

=== modified file 'doc/sphinx/templates/index.html'
--- doc/sphinx/templates/index.html	2013-02-26 19:28:47 +0000
+++ doc/sphinx/templates/index.html	2013-08-30 19:39:27 +0000
@@ -8,6 +8,12 @@
    Yade is located at <a href="https://www.yade-dem.org";>www.yade-dem.org</a>, which contains <a href="https://www.yade-dem.org/doc/";>this documentation</a> and <a href="https://www.yade-dem.org/wiki/";>wiki</a>. Development is kindly hosted at <a href="http://www.launchpad.net/yade";>launchpad</a>; it is used for <a href="http://code.launchpad.net/yade";>source code</a>, <a href="http://bugs.launchpad.net/yade";>bug tracking</a>, <a href="http://blueprints.launchpad.net/yade";>planning</a>, <a href="https://launchpad.net/~yade-pkg/+archive/snapshots";>package</a> and <a href="https://launchpad.net/yade/+download";>source</a> downloads</a> and more.
   </p>
   <p>
+  Since March 2012 Yade is using GIT as VCS and placing the source code on 
+  <a href="https://github.com/yade/trunk";>github</a>. The Launchpad is importing
+  source code several times per day for the further buiding of "daily"-packages 
+  for Ubuntu.
+  </p>
+  <p>
    Please make sure you read the <a href="{{ pathto("citing") }}">"Acknowledging Yade"</a> section if you plan to cite Yade in publications.
   </p>
   <p>

=== modified file 'doc/sphinx/user.rst'
--- doc/sphinx/user.rst	2013-08-22 18:35:55 +0000
+++ doc/sphinx/user.rst	2013-08-29 10:30:31 +0000
@@ -418,7 +418,7 @@
 #. Approximate collision detection is adjusted so that approximate contacts are detected also between particles within the interaction radius. This consists in setting value of :yref:`Bo1_Sphere_Aabb.aabbEnlargeFactor` to the interaction radius value.
 
 #. The geometry functor (``Ig2``)
-   would normally say that "there is no contact" if given 2 spheres that are not in contact. Therefore, the same value as for :yref:`Bo1_Sphere_Aabb.aabbEnlargeFactor` must be given to it. (Either :yref:`Ig2_Sphere_Sphere_Dem3DofGeom.distFactor` or :yref:`Ig2_Sphere_Sphere_ScGeom.interactionDetectionFactor`, depending on the functor that is in use.
+   would normally say that "there is no contact" if given 2 spheres that are not in contact. Therefore, the same value as for :yref:`Bo1_Sphere_Aabb.aabbEnlargeFactor` must be given to it (:yref:`Ig2_Sphere_Sphere_ScGeom.interactionDetectionFactor` ).
 
    Note that only :yref:`Sphere` + :yref:`Sphere` interactions are supported; there is no parameter analogous to :yref:`distFactor<Ig2_Sphere_Sphere_ScGeom.interactionDetectionFactor>` in :yref:`Ig2_Facet_Sphere_ScGeom`. This is on purpose, since the interaction radius is meaningful in bulk material represented by sphere packing, whereas facets usually represent boundary conditions which should be exempt from this dense interaction network.
 
@@ -576,12 +576,7 @@
    
    Again, missing combination will cause given shape combinations to freely interpenetrate one another.
 
-#. :yref:`IGeom` type accepted by the ``Law2`` functor (below); it is the first part of functor's name after ``Law2`` (for instance, :yref:`Law2_ScGeom_CpmPhys_Cpm` accepts :yref:`ScGeom`). This is (for most cases) either :yref:`Dem3DofGeom` (total shear formulation) or :yref:`ScGeom` (incremental shear formulation). For :yref:`Dem3DofGeom`, the above example would simply change to::
-
-      InteractionLoop([
-         Ig2_Sphere_Sphere_Dem3DofGeom(),
-         Ig2_Facet_Sphere_Dem3DofGeom()
-      ],[],[])
+#. :yref:`IGeom` type accepted by the ``Law2`` functor (below); it is the first part of functor's name after ``Law2`` (for instance, :yref:`Law2_ScGeom_CpmPhys_Cpm` accepts :yref:`ScGeom`).
 
 Ip2 functors
 ^^^^^^^^^^^^
@@ -693,29 +688,35 @@
 Imposing motion and forces
 --------------------------
 
-* If a degree of freedom is blocked and a velocity is assigned along that direction (translational or rotational velocity), then the body will move at constant velocity. This is the simpler and recommended method to impose the motion of a body. This, for instance, will result in a constant velocity along $x$::
+Imposed velocity
+^^^^^^^^^^^^^^^^
+
+If a degree of freedom is blocked and a velocity is assigned along that direction (translational or rotational velocity), then the body will move at constant velocity. This is the simpler and recommended method to impose the motion of a body. This, for instance, will result in a constant velocity along $x$::
 
 	O.bodies.append(utils.sphere((0,0,0),1))
 	O.bodies[0].state.blockedDOFs='x'
 	O.bodies[0].state.vel=(10,0,0)
 
-  Conversely, modifying the position directly is likely to break Yade's algorithms, especially those related to collision detection and contact laws, as they are based oon bodies velocities. Therefore, unless you really know what you are doing, don't do that for imposing a motion::
+Conversely, modifying the position directly is likely to break Yade's algorithms, especially those related to collision detection and contact laws, as they are based oon bodies velocities. Therefore, unless you really know what you are doing, don't do that for imposing a motion::
 
 	O.bodies.append(utils.sphere((0,0,0),1))
 	O.bodies[0].state.blockedDOFs='x'
 	O.bodies[0].state.pos=10*O.dt #REALLY BAD! Don't assign position
 
-* Applying a force or a torque on a body is done via functions of the :yref:`ForceContainer`. It is as simple as this::
+Imposed force
+^^^^^^^^^^^^^
+
+Applying a force or a torque on a body is done via functions of the :yref:`ForceContainer`. It is as simple as this::
 
 	O.forces.addF(0,(1,0,0)) #applies for one step
   
-  By default, the force applies for one time step only, and is resetted at the beginning of each step. For this reason, imposing a force at the begining of one step will have no effect at all, since it will be immediatly resetted. The only way is to place a :yref:`PyRunner` inside the simulation loop.
+By default, the force applies for one time step only, and is resetted at the beginning of each step. For this reason, imposing a force at the begining of one step will have no effect at all, since it will be immediatly resetted. The only way is to place a :yref:`PyRunner` inside the simulation loop.
 
-  Applying the force permanently is possible with an optional argument (in this case it does not matter if the command comes at the begining of the time step)::
+Applying the force permanently is possible with an optional argument (in this case it does not matter if the command comes at the begining of the time step)::
 
 	O.forces.addF(0,(1,0,0),permanent=True) #applies permanently
 
-  The force  will persist across iterations, until it is overwritten by another call to ``O.forces.addF(id,f,True)`` or erased by ``O.forces.reset(resetAll=True)``. The permanent force on a body can be checked with ``O.forces.permF(id)``.
+The force  will persist across iterations, until it is overwritten by another call to ``O.forces.addF(id,f,True)`` or erased by ``O.forces.reset(resetAll=True)``. The permanent force on a body can be checked with ``O.forces.permF(id)``.
 
 Boundary controllers
 --------------------
@@ -1049,7 +1050,7 @@
 By editing the generated .gnuplot file you can plot any of the added Data afterwards.
 
 
-* Data file is saved (compressed using bzip2) separately from the gnuplot file, so any other programs can be used to process them. In particular, the ``numpy.genfromtxt`` (documented `here <http://docs.scipy.org/doc/numpy/reference/generated/numpy.genfromtxt.html>`_) can be useful to import those data back to python; the decompression happens automatically.
+* Data file is saved (compressed using bzip2) separately from the gnuplot file, so any other programs can be used to process them. In particular, the ``numpy.genfromtxt`` (`documented here <http://docs.scipy.org/doc/numpy/reference/generated/numpy.genfromtxt.html>`_) can be useful to import those data back to python; the decompression happens automatically.
 
 * The gnuplot file can be run through gnuplot to produce the figure; see :yref:`yade.plot.saveGnuplot` documentation for details.
 
@@ -1470,7 +1471,7 @@
 .. figure:: fig/micro-domains.*
 
 Micro-strain
-""""""""""""
+------------
 Below is an output of the :yref:`defToVtk<TesselationWrapper::defToVtk>` function visualized with paraview (in this case Yade's TesselationWrapper was used to process experimental data obtained on sand by Edward Ando at Grenoble University, 3SR lab.). The output is visualized with paraview, as explained in the previous section. Similar results can be generated from simulations:
 
 .. code-block:: python
@@ -1493,7 +1494,7 @@
 .. figure:: fig/localstrain.*
 
 Micro-stress
-""""""""""""
+------------
 Stress fields can be generated by combining the volume returned by TesselationWrapper to per-particle stress given by :yref:`bodyStressTensors`. Since the stress $\sigma$ from bodyStressTensor implies a division by the volume $V_b$ of the solid particle, one has to re-normalize it in order to obtain the micro-stress as defined in [Catalano2013a]_ (equation 39 therein), i.e. $\overline{\sigma}^k = \sigma^k \times V_b^k / V_{\sigma}^k$ where $V_{\sigma}^k$ is the volume assigned to particle $k$ in the tesselation. For instance:
 
 .. code-block:: python

=== modified file 'doc/yade-articles.bib'
--- doc/yade-articles.bib	2013-08-14 08:01:55 +0000
+++ doc/yade-articles.bib	2013-08-26 21:57:21 +0000
@@ -30,7 +30,7 @@
 	url = {http://arxiv.org/pdf/1304.4895.pdf}
 }
 
-@article {Chareyre2012a,
+@article{Chareyre2012a,
   	author = {Chareyre, B. and Cortis, A. and Catalano, E. and Barthélemy, E.},
   	title = {Pore-Scale Modeling of Viscous Flow and Induced Forces in Dense Sphere Packings},
   	journal = {Transport in Porous Media},
@@ -359,15 +359,15 @@
 }
 
 @article{Puckett2011,
-  	title = {Local origins of volume fraction fluctuations in dense granular materials},
-  	author = {Puckett, J.G. and Lechenault, F. and Daniels, K.E.},
-  	journal = {Physical Review E},
-  	volume = {83},
-  	issue = {4},
-  	pages = {041301},
-  	year = {2011},
-  	doi = {10.1103/PhysRevE.83.041301},
-  	url = {http://link.aps.org/doi/10.1103/PhysRevE.83.041301}
+	title = {Local origins of volume fraction fluctuations in dense granular materials},
+	author = {Puckett, J.G. and Lechenault, F. and Daniels, K.E.},
+	journal = {Physical Review E},
+	volume = {83},
+	issue = {4},
+	pages = {041301},
+	year = {2011},
+	doi = {10.1103/PhysRevE.83.041301},
+	url = {http://link.aps.org/doi/10.1103/PhysRevE.83.041301}
 }
 
 @article{Sayeed2011,

=== modified file 'doc/yade-conferences.bib'
--- doc/yade-conferences.bib	2013-08-14 08:01:55 +0000
+++ doc/yade-conferences.bib	2013-08-26 21:53:51 +0000
@@ -563,7 +563,7 @@
 	doi = {10.1063/1.4812158}
 }
 
-@InProceedings{ Hadda2013,
+@InProceedings{ Hadda2013b,
 	author = {Nejib Hadda and François Nicot and Luc Sibille and Farhang Radjai and Antoinette Tordesillas and Félix Darve},
 	title = {A multiscale description of failure in granular materials},
 	publisher = {AIP},
@@ -590,3 +590,14 @@
 	url = {https://www.yade-dem.org/publi/APC000495.pdf},
 	doi = {10.1063/1.4811976}
 }
+
+@InProceedings{Maurin2013,
+  title={Discrete element modelling of bedload transport},
+  author={Maurin, Raphael and Chareyre, Bruno and Chauchat, Julien and Frey, Philippe},
+  booktitle={Proceedings of THESIS 2013, Two-pHase modElling for Sediment dynamIcS in Geophysical Flows},
+  adress = {Chatou, France},
+  pages={6p},
+  url = {https://www.yade-dem.org/publi/Maurin_et_al_THESIS_meta.pdf},
+  year={2013}
+}
+

=== modified file 'doc/yade-theses.bib'
--- doc/yade-theses.bib	2013-08-19 17:51:24 +0000
+++ doc/yade-theses.bib	2013-08-28 10:38:02 +0000
@@ -101,6 +101,14 @@
 	author = {Benoit Charlas},
 	school = {Université de Grenoble},
 	title = {Etude du comportement mécanique d'un hydrure intermétallique utilisé pour le stockage d'hydrogène},
-	year = {2013}
+	year = {2013},
+	url = {https://www.yade-dem.org/w/images/8/89/These_BenoitCharlas.pdf}
 }
 
+@phdthesis{Catalano2012,
+	author = {Emanuele Catalano},
+	school = {Université de Grenoble},
+	title = {A pore-scale coupled hydromechanical model for biphasic granular media},
+	year = {2012},
+	url = {https://yade-dem.org/publi/Catalano_Thesis.pdf}
+}
\ No newline at end of file

=== 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)

=== modified file 'pkg/common/Cylinder.hpp'
--- pkg/common/Cylinder.hpp	2013-05-29 09:48:51 +0000
+++ pkg/common/Cylinder.hpp	2013-08-29 10:30:31 +0000
@@ -265,7 +265,7 @@
 public:
     //OpenMPAccumulator<Real> plasticDissipation;
     virtual void go(shared_ptr<IGeom>& _geom, shared_ptr<IPhys>& _phys, Interaction* I);
-    YADE_CLASS_BASE_DOC_ATTRS_CTOR_PY(Law2_ChCylGeom6D_CohFrictPhys_CohesionMoment,LawFunctor,"Law for linear compression, and Mohr-Coulomb plasticity surface without cohesion.\nThis law implements the classical linear elastic-plastic law from [CundallStrack1979]_ (see also [Pfc3dManual30]_). The normal force is (with the convention of positive tensile forces) $F_n=\\min(k_n u_n, 0)$. The shear force is $F_s=k_s u_s$, the plasticity condition defines the maximum value of the shear force : $F_s^{\\max}=F_n\\tan(\\phi)$, with $\\phi$ the friction angle.\n\n.. note::\n This law uses :yref:`ScGeom`; there is also functionally equivalent :yref:`Law2_Dem3DofGeom_FrictPhys_CundallStrack`, which uses :yref:`Dem3DofGeom` (sphere-box interactions are not implemented for the latest).\n\n.. note::\n This law is well tested in the context of triaxial simulation, and has been used for a number of published results (see e.g. [Scholtes2009b]_ and other papers from the same authors). It is generalised by :yref:`Law2_ScGeom6D_CohFrictPhys_CohesionMoment`, which adds cohesion and moments at contact.",
+    YADE_CLASS_BASE_DOC_ATTRS_CTOR_PY(Law2_ChCylGeom6D_CohFrictPhys_CohesionMoment,LawFunctor,"Law for linear compression, and Mohr-Coulomb plasticity surface without cohesion.\nThis law implements the classical linear elastic-plastic law from [CundallStrack1979]_ (see also [Pfc3dManual30]_). The normal force is (with the convention of positive tensile forces) $F_n=\\min(k_n u_n, 0)$. The shear force is $F_s=k_s u_s$, the plasticity condition defines the maximum value of the shear force : $F_s^{\\max}=F_n\\tan(\\phi)$, with $\\phi$ the friction angle.\n\n.. note::\n This law is well tested in the context of triaxial simulation, and has been used for a number of published results (see e.g. [Scholtes2009b]_ and other papers from the same authors). It is generalised by :yref:`Law2_ScGeom6D_CohFrictPhys_CohesionMoment`, which adds cohesion and moments at contact.",
                                       ((bool,neverErase,false,,"Keep interactions even if particles go away from each other (only in case another constitutive law is in the scene, e.g. :yref:`Law2_ScGeom_CapillaryPhys_Capillarity`)"))
                                       ((bool,traceEnergy,false,Attr::hidden,"Define the total energy dissipated in plastic slips at all contacts."))
                                       ((int,plastDissipIx,-1,(Attr::hidden|Attr::noSave),"Index for plastic dissipation (with O.trackEnergy)"))

=== modified file 'pkg/dem/ConcretePM.cpp'
--- pkg/dem/ConcretePM.cpp	2013-08-23 15:21:20 +0000
+++ pkg/dem/ConcretePM.cpp	2013-08-26 21:42:20 +0000
@@ -345,7 +345,7 @@
 	Vector3r& Fs(phys->Fs); /* for python access */
 	const bool& isCohesive(phys->isCohesive);
 
-	Vector3r& epsTPl(phys->epsTPl);
+// 	Vector3r& epsTPl(phys->epsTPl);
 
 	#ifdef CPM_MATERIAL_MODEL
 		Real& epsNPl(phys->epsNPl);
@@ -589,7 +589,7 @@
 			}
 		}
 	}
-	Real tr;
+// 	Real tr;
 	FOREACH(shared_ptr<Body> B, *scene->bodies){
 		if (!B) continue;
 		const Body::id_t& id = B->getId();

=== 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/FlowEngine.cpp'
--- pkg/dem/FlowEngine.cpp	2013-07-26 18:16:04 +0000
+++ pkg/dem/FlowEngine.cpp	2013-08-30 13:27:06 +0000
@@ -21,6 +21,10 @@
 #include <boost/date_time.hpp>
 #include <boost/date_time/posix_time/posix_time.hpp>
 
+#ifdef LINSOLV
+#include <cholmod.h>
+#endif
+
 #include "FlowEngine.hpp"
 
 CREATE_LOGGER ( FlowEngine );
@@ -219,6 +223,20 @@
         flow->x_min = 1000.0, flow->x_max = -10000.0, flow->y_min = 1000.0, flow->y_max = -10000.0, flow->z_min = 1000.0, flow->z_max = -10000.0;
 }
 
+#ifdef LINSOLV
+template<class Solver>
+void FlowEngine::setForceMetis ( Solver& flow, bool force )
+{
+        if (force) {
+		flow->eSolver.cholmod().nmethods=1;
+		flow->eSolver.cholmod().method[0].ordering=CHOLMOD_METIS;
+	} else cholmod_defaults(&(flow->eSolver.cholmod()));
+}
+
+template<class Solver>
+bool FlowEngine::getForceMetis ( Solver& flow ) {return (flow->eSolver.cholmod().nmethods==1);}
+#endif
+
 template<class Solver>
 void FlowEngine::Build_Triangulation ( Solver& flow )
 {

=== modified file 'pkg/dem/FlowEngine.hpp'
--- pkg/dem/FlowEngine.hpp	2013-08-22 18:35:55 +0000
+++ pkg/dem/FlowEngine.hpp	2013-08-30 13:07:40 +0000
@@ -59,6 +59,10 @@
 		int ReTrg;
 		int ellapsedIter;
 		TPL void initSolver (Solver& flow);
+		#ifdef LINSOLV
+		TPL void setForceMetis (Solver& flow, bool force);
+		TPL bool getForceMetis (Solver& flow);
+		#endif
 		TPL void Triangulate (Solver& flow);
 		TPL void AddBoundary (Solver& flow);
 		TPL void Build_Triangulation (double P_zero, Solver& flow);
@@ -155,6 +159,13 @@
 		#ifdef LINSOLV
 		void 		_exportMatrix(string filename) {exportMatrix(filename,solver);}
 		void 		_exportTriplets(string filename) {exportTriplets(filename,solver);}
+		void		_setForceMetis (bool force) {setForceMetis(solver,force);}
+		bool		_getForceMetis () {return getForceMetis (solver);}
+		void		cholmodStats() {
+					cerr << cholmod_print_common("PFV Cholmod factorization",&(solver->eSolver.cholmod()))<<endl;
+					cerr << "cholmod method:" << solver->eSolver.cholmod().selected<<endl;
+					cerr << "METIS called:"<<solver->eSolver.cholmod().called_nd<<endl;}
+		bool		metisUsed() {return bool(solver->eSolver.cholmod().called_nd);}
 		#endif
 		python::list 	_getConstrictions(bool all) {return getConstrictions(all,solver);}
 		python::list 	_getConstrictionsFull(bool all) {return getConstrictionsFull(all,solver);}
@@ -164,7 +175,7 @@
 		virtual void action();
 		virtual void backgroundAction();
 
-		YADE_CLASS_BASE_DOC_ATTRS_DEPREC_INIT_CTOR_PY(FlowEngine,PartialEngine,"An engine to solve flow problem in saturated granular media. Model description can be found in [Chareyre2012a]_ and [Catalano2013a]_. See the example script FluidCouplingPFV/oedometer.py. More documentation to come.\n\n.. note::\n\t Multi-threading seems to work fine for Cholesky decomposition, but it fails for the solve phase in which -j1 is the fastest, here we specify thread numbers independently using :yref:`FlowEngine::numFactorizeThreads` and :yref:`FlowEngine::numSolveThreads`. These multhreading settings are only impacting the behaviour of openblas library and are relatively independant of :yref:`FlowEngine::multithread`. However, the settings have to be globally consistent. For instance, :yref:`FlowEngine::multithread`=True with  multithread :yref:`FlowEngine::numSolveThreads`=:yref:`FlowEngine::numFactorizeThreads`=4 means that openblas will mobilize 8 processors at some point, if the system doesn't have so many procs. it will hurt performance.",
+		YADE_CLASS_BASE_DOC_ATTRS_DEPREC_INIT_CTOR_PY(FlowEngine,PartialEngine,"An engine to solve flow problem in saturated granular media. Model description can be found in [Chareyre2012a]_ and [Catalano2013a]_. See the example script FluidCouplingPFV/oedometer.py. More documentation to come.\n\n.. note::Multi-threading seems to work fine for Cholesky decomposition, but it fails for the solve phase in which -j1 is the fastest, here we specify thread numbers independently using :yref:`FlowEngine::numFactorizeThreads` and :yref:`FlowEngine::numSolveThreads`. These multhreading settings are only impacting the behaviour of openblas library and are relatively independant of :yref:`FlowEngine::multithread`. However, the settings have to be globally consistent. For instance, :yref:`multithread<FlowEngine::multithread>` =True with  yref:`numFactorizeThreads<FlowEngine::numFactorizeThreads>` = yref:`numSolveThreads<FlowEngine::numSolveThreads>` = 4 implies that openblas will mobilize 8 processors at some point. If the system does not have so many procs. it will hurt performance.",
 					((bool,isActivated,true,,"Activates Flow Engine"))
 					((bool,first,true,,"Controls the initialization/update phases"))
 					((double, fluidBulkModulus, 0.,,"Bulk modulus of fluid (inverse of compressibility) K=-dP*V/dV [Pa]. Flow is compressible if fluidBulkModulus > 0, else incompressible."))
@@ -188,7 +199,7 @@
 					((bool,clampKValues,true,,"If true, clamp local permeabilities in [minKdivKmean,maxKdivKmean]*globalK. This clamping can avoid singular values in the permeability matrix and may reduce numerical errors in the solve phase. It will also hide junk values if they exist, or bias all values in very heterogeneous problems. So, use this with care."))
 					((Real,minKdivKmean,0.0001,,"define the min K value (see :yref:`FlowEngine::clampKValues`)"))
 					((Real,maxKdivKmean,100,,"define the max K value (see :yref:`FlowEngine::clampKValues`)"))
-					((double,permeabilityFactor,0.0,,"permability multiplier"))
+					((double,permeabilityFactor,1.0,,"permability multiplier"))
 					((double,viscosity,1.0,,"viscosity of the fluid"))
 					((double,stiffness, 10000,,"equivalent contact stiffness used in the lubrication model"))
 					((int, useSolver, 0,, "Solver to use 0=G-Seidel, 1=Taucs, 2-Pardiso, 3-CHOLMOD"))
@@ -217,6 +228,7 @@
 					#ifdef EIGENSPARSE_LIB
 					((int, numSolveThreads, 1,,"number of openblas threads in the solve phase."))
 					((int, numFactorizeThreads, 1,,"number of openblas threads in the factorization phase"))
+// 					((bool, forceMetis, 0,,"If true, METIS is used for matrix preconditioning, else Cholmod is free to choose the best method (which may be METIS to, depending on the matrix). See ``nmethods`` in Cholmod documentation"))
 					#endif
 					,
 					/*deprec*/
@@ -240,7 +252,7 @@
 					.def("clearImposedPressure",&FlowEngine::_clearImposedPressure,"Clear the list of points with pressure imposed.")
 					.def("clearImposedFlux",&FlowEngine::_clearImposedFlux,"Clear the list of points with flux imposed.")
 					.def("getCellFlux",&FlowEngine::_getCellFlux,(python::arg("cond")),"Get influx in cell associated to an imposed P (indexed using 'cond').")
-					.def("getBoundaryFlux",&FlowEngine::_getBoundaryFlux,(python::arg("boundary")),"Get total flux through boundary defined by its body id.\n\n.. note::\n\t The flux may be not zero even for no-flow condition. This artifact comes from cells which are incident to two or more boundaries (along the edges of the sample, typically). Such flux evaluation on impermeable boundary is just irrelevant, it does not imply that the boundary condition is not applied properly.")
+					.def("getBoundaryFlux",&FlowEngine::_getBoundaryFlux,(python::arg("boundary")),"Get total flux through boundary defined by its body id.\n\n.. note:: The flux may be not zero even for no-flow condition. This artifact comes from cells which are incident to two or more boundaries (along the edges of the sample, typically). Such flux evaluation on impermeable boundary is just irrelevant, it does not imply that the boundary condition is not applied properly.")
 					.def("getConstrictions",&FlowEngine::_getConstrictions,(python::arg("all")=true),"Get the list of constriction radii (inscribed circle) for all finite facets (if all==True) or all facets not incident to a virtual bounding sphere (if all==False).  When all facets are returned, negative radii denote facet incident to one or more fictious spheres.")
 					.def("getConstrictionsFull",&FlowEngine::_getConstrictionsFull,(python::arg("all")=true),"Get the list of constrictions (inscribed circle) for all finite facets (if all==True), or all facets not incident to a fictious bounding sphere (if all==False). When all facets are returned, negative radii denote facet incident to one or more fictious spheres. The constrictions are returned in the format {{cell1,cell2}{rad,nx,ny,nz}}")
 					.def("saveVtk",&FlowEngine::saveVtk,"Save pressure field in vtk format.")
@@ -261,6 +273,9 @@
 					#ifdef LINSOLV
 					.def("exportMatrix",&FlowEngine::_exportMatrix,(python::arg("filename")="matrix"),"Export system matrix to a file with all entries (even zeros will displayed).")
 					.def("exportTriplets",&FlowEngine::_exportTriplets,(python::arg("filename")="triplets"),"Export system matrix to a file with only non-zero entries.")
+					.def("cholmodStats",&FlowEngine::cholmodStats,"get statistics of cholmod solver activity")
+					.def("metisUsed",&FlowEngine::metisUsed,"check wether metis lib is effectively used")
+					.add_property("forceMetis",&FlowEngine::_getForceMetis,&FlowEngine::_setForceMetis,"If true, METIS is used for matrix preconditioning, else Cholmod is free to choose the best method (which may be METIS to, depending on the matrix). See ``nmethods`` in Cholmod documentation")
 					#endif
 					)
 		DECLARE_LOGGER;

=== modified file 'pkg/dem/HertzMindlin.cpp'
--- pkg/dem/HertzMindlin.cpp	2012-02-16 16:05:15 +0000
+++ pkg/dem/HertzMindlin.cpp	2013-09-07 19:40:12 +0000
@@ -31,8 +31,8 @@
 
 void Ip2_FrictMat_FrictMat_MindlinPhys::go(const shared_ptr<Material>& b1,const shared_ptr<Material>& b2, const shared_ptr<Interaction>& interaction){
 	if(interaction->phys) return; // no updates of an already existing contact necessary
-	shared_ptr<MindlinPhys> mindlinPhys(new MindlinPhys());
-	interaction->phys = mindlinPhys;
+	shared_ptr<MindlinPhys> contactPhysics(new MindlinPhys());
+	interaction->phys = contactPhysics;
 	FrictMat* mat1 = YADE_CAST<FrictMat*>(b1.get());
 	FrictMat* mat2 = YADE_CAST<FrictMat*>(b2.get());
 	
@@ -64,20 +64,20 @@
 	Real Rmean = (Da+Db)/2.; // mean radius
 	Real Kno = 4./3.*E*sqrt(R); // coefficient for normal stiffness
 	Real Kso = 2*sqrt(4*R)*G/(2-V); // coefficient for shear stiffness
-	Real frictionAngle = std::min(fa,fb);
+	Real frictionAngle = (!frictAngle) ? std::min(fa,fb) : (*frictAngle)(mat1->id,mat2->id,mat1->frictionAngle,mat2->frictionAngle);
 
 	Real Adhesion = 4.*Mathr::PI*R*gamma; // calculate adhesion force as predicted by DMT theory
 
 	/* pass values calculated from above to MindlinPhys */
-	mindlinPhys->tangensOfFrictionAngle = std::tan(frictionAngle); 
-	//mindlinPhys->prevNormal = scg->normal; // used to compute relative rotation
-	mindlinPhys->kno = Kno; // this is just a coeff
-	mindlinPhys->kso = Kso; // this is just a coeff
-	mindlinPhys->adhesionForce = Adhesion;
+	contactPhysics->tangensOfFrictionAngle = std::tan(frictionAngle); 
+	//contactPhysics->prevNormal = scg->normal; // used to compute relative rotation
+	contactPhysics->kno = Kno; // this is just a coeff
+	contactPhysics->kso = Kso; // this is just a coeff
+	contactPhysics->adhesionForce = Adhesion;
 	
-	mindlinPhys->kr = krot;
-	mindlinPhys->ktw = ktwist;
-	mindlinPhys->maxBendPl = eta*Rmean; // does this make sense? why do we take Rmean?
+	contactPhysics->kr = krot;
+	contactPhysics->ktw = ktwist;
+	contactPhysics->maxBendPl = eta*Rmean; // does this make sense? why do we take Rmean?
 
 	/* compute viscous coefficients */
 	if(en && betan) throw std::invalid_argument("Ip2_FrictMat_FrictMat_MindlinPhys: only one of en, betan can be specified.");
@@ -86,13 +86,13 @@
 	// en or es specified, just compute alpha, otherwise alpha remains 0
 	if(en || es){
 		Real logE = log((*en)(mat1->id,mat2->id));
-		mindlinPhys->alpha = -sqrt(5/6.)*2*logE/sqrt(pow(logE,2)+pow(Mathr::PI,2))*sqrt(2*E*sqrt(R)); // (see Tsuji, 1992)
+		contactPhysics->alpha = -sqrt(5/6.)*2*logE/sqrt(pow(logE,2)+pow(Mathr::PI,2))*sqrt(2*E*sqrt(R)); // (see Tsuji, 1992)
 	}
 	
 	// betan specified, use that value directly; otherwise give zero
 	else{	
-		mindlinPhys->betan=betan ? (*betan)(mat1->id,mat2->id) : 0; 
-		mindlinPhys->betas=betas ? (*betas)(mat1->id,mat2->id) : mindlinPhys->betan;
+		contactPhysics->betan=betan ? (*betan)(mat1->id,mat2->id) : 0; 
+		contactPhysics->betas=betas ? (*betas)(mat1->id,mat2->id) : contactPhysics->betan;
 	}
 }
 

=== modified file 'pkg/dem/HertzMindlin.hpp'
--- pkg/dem/HertzMindlin.hpp	2013-05-29 11:54:22 +0000
+++ pkg/dem/HertzMindlin.hpp	2013-09-07 19:40:12 +0000
@@ -86,6 +86,7 @@
 			((shared_ptr<MatchMaker>,es,,,"Shear coefficient of restitution $e_s$."))
 			((shared_ptr<MatchMaker>,betan,,,"Normal viscous damping coefficient $\\beta_n$."))
 			((shared_ptr<MatchMaker>,betas,,,"Shear viscous damping coefficient $\\beta_s$."))
+			((shared_ptr<MatchMaker>,frictAngle,,,"Instance of :yref:`MatchMaker` determining how to compute the friction angle of an interaction. If ``None``, minimum value is used."))
 	);
 	DECLARE_LOGGER;
 };

=== modified file 'pkg/dem/Shop.cpp'
--- pkg/dem/Shop.cpp	2013-09-08 11:12:42 +0000
+++ pkg/dem/Shop.cpp	2013-09-08 11:19:06 +0000
@@ -581,44 +581,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;
 		}
@@ -818,33 +797,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-09-08 11:12:42 +0000
+++ pkg/dem/Shop.hpp	2013-09-08 11:19:06 +0000
@@ -127,8 +127,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);

=== modified file 'pkg/dem/VTKRecorder.hpp'
--- pkg/dem/VTKRecorder.hpp	2013-04-24 19:49:00 +0000
+++ pkg/dem/VTKRecorder.hpp	2013-08-29 10:30:31 +0000
@@ -23,7 +23,7 @@
 			((bool,multiblock,false,,"Use multi-block (``.vtm``) files to store data, rather than separate ``.vtu`` files."))
 		#endif
 		((string,fileName,"",,"Base file name; it will be appended with {spheres,intrs,facets}-243100.vtu (unless *multiblock* is ``True``) depending on active recorders and step number (243100 in this case). It can contain slashes, but the directory must exist already."))
-		((vector<string>,recorders,vector<string>(1,string("all")),,"List of active recorders (as strings). ``all`` (the default value) enables all base and generic recorders.\n\n.. admonition:: Base recorders\n\n\tBase recorders save the geometry (unstructured grids) on which other data is defined. They are implicitly activated by many of the other recorders. Each of them creates a new file (or a block, if :yref:`multiblock <VTKRecorder.multiblock>` is set).\n\n\t``spheres``\n\t\tSaves positions and radii (``radii``) of :yref:`spherical<Sphere>` particles.\n\t``facets``\n\t\tSave :yref:`facets<Facet>` positions (vertices).\n\t``boxes``\n\t\tSave :yref:`boxes<Box>` positions (edges).\n\t``intr``\n\t\tStore interactions as lines between nodes at respective particles positions. Additionally stores magnitude of normal (``forceN``) and shear (``absForceT``) forces on interactions (the :yref:`geom<Interaction.geom> must be of type :yref:`NormShearPhys`). \n\n.. admonition:: Generic recorders\n\n\tGeneric recorders do not depend on specific model being used and save commonly useful data.\n\n\t``id``\n\t\tSaves id's (field ``id``) of spheres; active only if ``spheres`` is active.\n\t``mass``\n\t\tSaves masses (field ``mass``) of spheres; active only if ``spheres`` is active.\n\t``clumpId``\n\t\tSaves id's of clumps to which each sphere belongs (field ``clumpId``); active only if ``spheres`` is active.\n\t``colors``\n\t\tSaves colors of :yref:`spheres<Sphere>` and of :yref:`facets<Facet>` (field ``color``); only active if ``spheres`` or ``facets`` are activated.\n\t``mask``\n\t\tSaves groupMasks of :yref:`spheres<Sphere>` and of :yref:`facets<Facet>` (field ``mask``); only active if ``spheres`` or ``facets`` are activated.\n\t``materialId``\n\t\tSaves materialID of :yref:`spheres<Sphere>` and of :yref:`facets<Facet>`; only active if ``spheres`` or ``facets`` are activated.\n\t``velocity``\n\t\tSaves linear and angular velocities of spherical particles as Vector3 and length(fields ``linVelVec``, ``linVelLen`` and ``angVelVec``, ``angVelLen`` respectively``); only effective with ``spheres``.\n\t``stress``\n\t\tSaves stresses of :yref:`spheres<Sphere>` and of :yref:`facets<Facet>`  as Vector3 and length; only active if ``spheres`` or ``facets`` are activated.\n\n.. admonition:: Specific recorders\n\n\tThe following should only be activated in appropriate cases, otherwise crashes can occur due to violation of type presuppositions.\n\n\t``cpm``\n\t\tSaves data pertaining to the :yref:`concrete model<Law2_ScGeom_CpmPhys_Cpm>`: ``cpmDamage`` (normalized residual strength averaged on particle), ``cpmStress`` (stress on particle); ``intr`` is activated automatically by ``cpm``\n\t``rpm``\n\t\tSaves data pertaining to the :yref:`rock particle model<Law2_Dem3DofGeom_RockPMPhys_Rpm>`: ``rpmSpecNum`` shows different pieces of separated stones, only ids. ``rpmSpecMass`` shows masses of separated stones.\n\t``wpm``\n\t\tSaves data pertaining to the :yref:`wire particle model<Law2_ScGeom_WirePhys_WirePM>`: ``wpmForceNFactor`` shows the loading factor for the wire, e.g. normal force divided by threshold normal force.\n\n"))
+		((vector<string>,recorders,vector<string>(1,string("all")),,"List of active recorders (as strings). ``all`` (the default value) enables all base and generic recorders.\n\n.. admonition:: Base recorders\n\n\tBase recorders save the geometry (unstructured grids) on which other data is defined. They are implicitly activated by many of the other recorders. Each of them creates a new file (or a block, if :yref:`multiblock <VTKRecorder.multiblock>` is set).\n\n\t``spheres``\n\t\tSaves positions and radii (``radii``) of :yref:`spherical<Sphere>` particles.\n\t``facets``\n\t\tSave :yref:`facets<Facet>` positions (vertices).\n\t``boxes``\n\t\tSave :yref:`boxes<Box>` positions (edges).\n\t``intr``\n\t\tStore interactions as lines between nodes at respective particles positions. Additionally stores magnitude of normal (``forceN``) and shear (``absForceT``) forces on interactions (the :yref:`geom<Interaction.geom> must be of type :yref:`NormShearPhys`). \n\n.. admonition:: Generic recorders\n\n\tGeneric recorders do not depend on specific model being used and save commonly useful data.\n\n\t``id``\n\t\tSaves id's (field ``id``) of spheres; active only if ``spheres`` is active.\n\t``mass``\n\t\tSaves masses (field ``mass``) of spheres; active only if ``spheres`` is active.\n\t``clumpId``\n\t\tSaves id's of clumps to which each sphere belongs (field ``clumpId``); active only if ``spheres`` is active.\n\t``colors``\n\t\tSaves colors of :yref:`spheres<Sphere>` and of :yref:`facets<Facet>` (field ``color``); only active if ``spheres`` or ``facets`` are activated.\n\t``mask``\n\t\tSaves groupMasks of :yref:`spheres<Sphere>` and of :yref:`facets<Facet>` (field ``mask``); only active if ``spheres`` or ``facets`` are activated.\n\t``materialId``\n\t\tSaves materialID of :yref:`spheres<Sphere>` and of :yref:`facets<Facet>`; only active if ``spheres`` or ``facets`` are activated.\n\t``velocity``\n\t\tSaves linear and angular velocities of spherical particles as Vector3 and length(fields ``linVelVec``, ``linVelLen`` and ``angVelVec``, ``angVelLen`` respectively``); only effective with ``spheres``.\n\t``stress``\n\t\tSaves stresses of :yref:`spheres<Sphere>` and of :yref:`facets<Facet>`  as Vector3 and length; only active if ``spheres`` or ``facets`` are activated.\n\n.. admonition:: Specific recorders\n\n\tThe following should only be activated in appropriate cases, otherwise crashes can occur due to violation of type presuppositions.\n\n\t``cpm``\n\t\tSaves data pertaining to the :yref:`concrete model<Law2_ScGeom_CpmPhys_Cpm>`: ``cpmDamage`` (normalized residual strength averaged on particle), ``cpmStress`` (stress on particle); ``intr`` is activated automatically by ``cpm``\n\t``wpm``\n\t\tSaves data pertaining to the :yref:`wire particle model<Law2_ScGeom_WirePhys_WirePM>`: ``wpmForceNFactor`` shows the loading factor for the wire, e.g. normal force divided by threshold normal force.\n\n"))
 		((int,mask,0,,"If mask defined, only bodies with corresponding groupMask will be exported. If 0, all bodies will be exported.")),
 		/*ctor*/
 		initRun=true;

=== modified file 'pkg/dem/ViscoelasticCapillarPM.cpp'
--- pkg/dem/ViscoelasticCapillarPM.cpp	2013-06-12 14:35:50 +0000
+++ pkg/dem/ViscoelasticCapillarPM.cpp	2013-08-28 12:00:42 +0000
@@ -50,7 +50,7 @@
          */ 
         
         Real R = phys.R;
-        Real s = -geom.penetrationDepth/2.0;
+        Real s = -geom.penetrationDepth;
         Real Vb = phys.Vb;
         
         Real VbS = Vb/(R*R*R);
@@ -79,7 +79,7 @@
                   (0.03345 + 0.04543*Th1 - 0.09056*Th2) * log(VbS) +
                   (0.0018574 + 0.004456*Th1 - 0.006257*Th2) *log(VbS)*log(VbS);
   
-        Real sPl = s/sqrt(Vb/R);
+        Real sPl = (s/2.0)/sqrt(Vb/R);
         
         Real lnFS = f1 - f2*exp(f3*log(sPl) + f4*log(sPl)*log(sPl));
         Real FS = exp(lnFS);

=== modified file 'pkg/dem/ViscoelasticPM.cpp'
--- pkg/dem/ViscoelasticPM.cpp	2013-06-12 14:35:50 +0000
+++ pkg/dem/ViscoelasticPM.cpp	2013-08-28 13:31:12 +0000
@@ -132,7 +132,6 @@
    
 	if (not(phys.liqBridgeCreated) and phys.Capillar) {
 		phys.liqBridgeCreated = true;
-		phys.sCrit = (1+0.5*phys.theta)*(pow(phys.Vb,1/3.0) + 0.1*pow(phys.Vb,2.0/3.0));   // [Willett2000], equation (15), use the full-length e.g 2*Sc
 		Sphere* s1=dynamic_cast<Sphere*>(bodies[id1]->shape.get());
 		Sphere* s2=dynamic_cast<Sphere*>(bodies[id2]->shape.get());
 		if (s1 and s2) {
@@ -142,6 +141,11 @@
 		} else {
 			phys.R = s2->radius;
 		}
+		
+		const Real Vstar = phys.Vb/(phys.R*phys.R*phys.R);
+		const Real Sstar = (1+0.5*phys.theta)*(pow(Vstar,1/3.0) + 0.1*pow(Vstar,2.0/3.0));   // [Willett2000], equation (15), use the full-length e.g 2*Sc
+		
+		phys.sCrit = Sstar*phys.R;
 	}
 
 	Vector3r& shearForce = phys.shearForce;

=== modified file 'pkg/dem/ViscoelasticPM.hpp'
--- pkg/dem/ViscoelasticPM.hpp	2013-06-12 14:35:49 +0000
+++ pkg/dem/ViscoelasticPM.hpp	2013-08-28 12:00:42 +0000
@@ -79,6 +79,6 @@
 	private:
 		Real calculateCapillarForce(const ScGeom& geom, ViscElPhys& phys);
 	FUNCTOR2D(ScGeom,ViscElPhys);
-	YADE_CLASS_BASE_DOC(Law2_ScGeom_ViscElPhys_Basic,LawFunctor,"Linear viscoelastic model operating on :yref:`ScGeom` and :yref:`ViscElPhys`.");
+	YADE_CLASS_BASE_DOC(Law2_ScGeom_ViscElPhys_Basic,LawFunctor,"Linear viscoelastic model operating on :yref:`ScGeom` and :yref:`ViscElPhys`. The model is mostly based on the paper for For details see Pournin [Pournin2001]_ .");
 };
 REGISTER_SERIALIZABLE(Law2_ScGeom_ViscElPhys_Basic);

=== modified file 'py/CMakeLists.txt'
--- py/CMakeLists.txt	2013-07-01 18:57:33 +0000
+++ py/CMakeLists.txt	2013-08-29 10:30:31 +0000
@@ -30,11 +30,6 @@
 SET_TARGET_PROPERTIES(WeightedAverage2d PROPERTIES PREFIX "")
 INSTALL(TARGETS WeightedAverage2d DESTINATION "${YADE_PY_PATH}/yade/")
 
-ADD_LIBRARY(_eudoxos SHARED "${CMAKE_CURRENT_SOURCE_DIR}/_eudoxos.cpp")
-SET_TARGET_PROPERTIES(_eudoxos PROPERTIES PREFIX "")
-TARGET_LINK_LIBRARIES(_eudoxos yade)
-INSTALL(TARGETS _eudoxos DESTINATION "${YADE_PY_PATH}/yade/")
-
 ADD_LIBRARY(_utils SHARED "${CMAKE_CURRENT_SOURCE_DIR}/_utils.cpp")
 SET_TARGET_PROPERTIES(_utils PROPERTIES PREFIX "")
 TARGET_LINK_LIBRARIES(_utils yade)

=== 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-09-08 11:12:42 +0000
+++ py/_utils.cpp	2013-09-08 11:19:06 +0000
@@ -76,32 +76,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
@@ -354,34 +355,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){
@@ -508,15 +510,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/system.py'
--- py/system.py	2012-06-28 19:34:29 +0000
+++ py/system.py	2013-08-29 10:30:31 +0000
@@ -35,8 +35,6 @@
 	'ElasticMat':'ElastMat', # Sun Jan 10 09:53:15 2010, vaclav@flux
 	'ElasticContactInteraction':'FrictPhys', # Sun Jan 10 09:57:59 2010, vaclav@flux
 	'ef2_Spheres_Elastic_ElasticLaw':'Law2_ScGeom_FrictPhys_Basic', # Sun Jan 10 09:59:42 2010, vaclav@flux
-	'Law2_Dem3Dof_Elastic_Elastic':'Law2_Dem3Dof_FrictPhys_Basic', # Sun Jan 10 10:00:25 2010, vaclav@flux
-	'Law2_Dem3Dof_FrictPhys_Basic':'Law2_Dem3DofGeom_FrictPhys_Basic', # Sun Jan 10 10:01:27 2010, vaclav@flux
 	'Ip2_FrictMat_FrictMat_NormShearPhys':'Ip2_FrictMat_FrictMat_FrictPhys', # Sun Jan 10 10:07:40 2010, vaclav@flux
 	'GLDrawCpmPhys':'Gl1_CpmPhys', # Sat Feb  6 14:46:08 2010, vaclav@flux
 	'RockJointLawRelationships':'Ip2_2xCohFrictMat_NormalInelasticityPhys', # Mon Feb  8 11:17:59 2010, jduriez@c1solimara-l

=== 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,)

=== added file 'scripts/checks-and-tests/checks/DEM-PFV-check.py'
--- scripts/checks-and-tests/checks/DEM-PFV-check.py	1970-01-01 00:00:00 +0000
+++ scripts/checks-and-tests/checks/DEM-PFV-check.py	2013-08-30 10:33:17 +0000
@@ -0,0 +1,146 @@
+# -*- coding: utf-8 -*-
+# Here, we are testing bulk modulus, then permeability, then the consolidation of a specimen.
+# the test is based on examples/FluidCouplingPFV/oedometer.py, only slightly simplified and using less particles
+
+try: FlowEngine
+except NameError:
+	print "skip DEM-PFV check, FlowEngine not available"
+else:
+
+	errors=0
+	tolerance=0.01
+
+	from yade import pack
+	num_spheres=100# number of spheres
+	young=1e6
+	compFricDegree = 3 # initial contact friction during the confining phase
+	finalFricDegree = 30 # contact friction during the deviatoric loading
+	mn,mx=Vector3(0,0,0),Vector3(1,1,1) # corners of the initial packing
+
+	O.materials.append(FrictMat(young=young,poisson=0.5,frictionAngle=radians(compFricDegree),density=2600,label='spheres'))
+	O.materials.append(FrictMat(young=young,poisson=0.5,frictionAngle=0,density=0,label='walls'))
+	walls=aabbWalls([mn,mx],thickness=0,material='walls')
+	wallIds=O.bodies.append(walls)
+
+	sp=pack.SpherePack()
+	#sp.makeCloud(mn,mx,-1,0.3333,num_spheres,False, 0.95,seed=1) #"seed" is not enough for portable determinism it seems, let us use a data file
+	sp.load(checksPath+'/data/100spheres')
+
+	sp.toSimulation(material='spheres')
+
+	triax=TriaxialStressController(
+		maxMultiplier=1.+2e4/young, # spheres growing factor (fast growth)
+		finalMaxMultiplier=1.+2e3/young, # spheres growing factor (slow growth)
+		thickness = 0,
+		stressMask = 7,
+		max_vel = 0.005,
+		internalCompaction=True, # If true the confining pressure is generated by growing particles
+	)
+
+	newton=NewtonIntegrator(damping=0.2)
+
+	O.engines=[
+		ForceResetter(),
+		InsertionSortCollider([Bo1_Sphere_Aabb(),Bo1_Box_Aabb()]),
+		InteractionLoop(
+			[Ig2_Sphere_Sphere_ScGeom(),Ig2_Box_Sphere_ScGeom()],
+			[Ip2_FrictMat_FrictMat_FrictPhys()],
+			[Law2_ScGeom_FrictPhys_CundallStrack()],label="iloop"
+		),
+		FlowEngine(dead=1,label="flow"),#introduced as a dead engine for the moment, see 2nd section
+		GlobalStiffnessTimeStepper(active=1,timeStepUpdateInterval=100,timestepSafetyCoefficient=0.8),
+		triax,
+		newton
+	]
+
+	triax.goal1=triax.goal2=triax.goal3=10000
+
+	while 1:
+		O.run(200, True)
+		unb=unbalancedForce()
+		if unb<0.01 and abs(10000-triax.meanStress)/10000<0.01: break
+
+	setContactFriction(radians(finalFricDegree))
+
+	## ______________   Oedometer section   _________________
+
+	#A. Check bulk modulus of the dry material from load/unload cycles
+	triax.stressMask=2
+	triax.goal1=triax.goal3=0
+
+	triax.internalCompaction=False
+	triax.wall_bottom_activated=False
+	triax.goal2=11000; O.run(2000,1)
+	triax.goal2=10000; O.run(2000,1)
+	triax.goal2=11000; O.run(2000,1)
+	e22=triax.strain[1]
+	triax.goal2=10000; O.run(2000,1)
+
+	e22=e22-triax.strain[1]
+	modulus = 1000./abs(e22)
+
+	target=249064.586653
+	if abs((modulus-target)/target)>tolerance :
+		print "DEM-PFV: difference in bulk modulus:", modulus, "vs. target ",target
+		errors+=1
+
+	#B. Activate flow engine and set boundary conditions in order to get permeability
+	flow.dead=0
+	flow.defTolerance=0.3
+	flow.meshUpdateInterval=200
+	flow.useSolver=3
+	flow.viscosity=10
+	flow.bndCondIsPressure=[0,0,1,1,0,0]
+	flow.bndCondValue=[0,0,1,0,0,0]
+	flow.boundaryUseMaxMin=[0,0,0,0,0,0]
+	O.dt=0.1e-3
+	O.dynDt=False
+
+	O.run(1,1)
+	Qin = flow.getBoundaryFlux(2)
+	Qout = flow.getBoundaryFlux(3)
+	permeability = abs(Qin)/1.e-4 #size is one, we compute K=V/∇H
+
+	if abs(Qin+Qout)>1e-15 :
+		print "DEM-PFV: unbalanced Qin vs. Qout"
+		errors+=1
+
+	target=0.0408678245942
+	if abs((permeability-target)/target)>tolerance :
+		print "DEM-PFV: difference in permeability:",permeability," vs. target ",target
+		errors+=1
+
+	#C. now the oedometer test, drained at the top, impermeable at the bottom plate
+	flow.bndCondIsPressure=[0,0,0,1,0,0]
+	flow.bndCondValue=[0,0,0,0,0,0]
+	newton.damping=0
+
+	zeroTime=O.time
+	zeroe22 = triax.strain[1]
+	triax.goal2=11000
+
+	O.timingEnabled=1
+	from yade import timing
+	O.run(3000,1)
+
+	target=637.268936033
+	if abs((flow.getPorePressure((0.5,0.1,0.5))-target)/target)>tolerance :
+		print "DEM-PFV: difference in final pressure:",flow.getPorePressure((0.5,0.1,0.5))," vs. target ",target
+		errors+=1
+	target=0.00260892345196
+	if abs((triax.strain[1]-zeroe22-target)/target)>tolerance :
+		print "DEM-PFV: difference in final deformation",triax.strain[1]-zeroe22," vs. target ",target
+		errors+=1
+
+	if (float(flow.execTime)/float(sum([e.execTime for e in O.engines])))>0.6 :
+		print "DEM-PFV: More than 60\% of cpu time in FlowEngine (",100.*(float(flow.execTime)/float(sum([e.execTime for e in O.engines]))) ,"%). Should not happen with efficient libraries (check blas/lapack/cholmod implementations)"
+		errors+=1
+
+	flow.forceMetis=True
+	O.run(201,1)
+	if not flow.metisUsed():
+		print "DEM-PFV: Metis is not used during cholmod's reordering although explicitely enabled, something wrong with libraries"
+		errors+=1
+
+	if (errors):
+		resultStatus +=1	#Test is failed
\ No newline at end of file

=== modified file 'scripts/checks-and-tests/checks/README'
--- scripts/checks-and-tests/checks/README	2012-03-13 09:51:32 +0000
+++ scripts/checks-and-tests/checks/README	2013-08-29 10:30:31 +0000
@@ -15,3 +15,5 @@
 7. Users are encouraged to add their own scripts into the scripts/test/checks/ folder. Discussion of some specific checktests design in users question is welcome.
 
 8. A check test should never need more than a few seconds to run. If your typical script needs more, try and reduce the number of element or the number of steps.
+
+9. Failures are reported via a global variable "resultStatus", which should be ONLY INCREMENTED in a checkTests, never assigned to (resultStatus+=1 is ok, resultStatus=1 is bad), else the script would erase the history of the checkTests coming before it.

=== modified file 'scripts/checks-and-tests/checks/checkGravity.py'
--- scripts/checks-and-tests/checks/checkGravity.py	2012-03-13 09:51:32 +0000
+++ scripts/checks-and-tests/checks/checkGravity.py	2013-08-29 10:30:31 +0000
@@ -69,8 +69,6 @@
 def getCurrentVel(inVel=0):
   t = O.time+O.dt
   return inVel + g*t
-  
-resultStatus=0
 
 def warningMessagePos(inVel, y_pos, y_pos_need):
   print "The body with the initial velocity %.3f, has an y-position %.3f, but it should be %.3f" % (inVel, y_pos, y_pos_need)

=== modified file 'scripts/checks-and-tests/checks/checkList.py'
--- scripts/checks-and-tests/checks/checkList.py	2012-03-13 09:51:32 +0000
+++ scripts/checks-and-tests/checks/checkList.py	2013-08-29 10:45:21 +0000
@@ -4,23 +4,24 @@
 
 scriptsToRun=os.listdir(checksPath)
 resultStatus = 0
+nFailed=0
 for script in scriptsToRun:
 	if (script[len(script)-3:]==".py" and not(script=="checkList.py")):
 		try:
 	 		print "###################################"
 			print "running: ",script
 			execfile(checksPath+"/"+script)
-			if (resultStatus):
+			if (resultStatus>nFailed):
 				print "Status: FAILURE!!!"
+				nFailed=resultStatus
 			else:
 				print "Status: success"
 			print "___________________________________"
 		except:
 			print script," failure"
 		O.reset()
-		
-if (resultStatus):
-	print "Some tests are failed!"
+if (resultStatus>0):
+	print resultStatus, " tests are failed"
 	sys.exit(1)
 else:
 	sys.exit(0)

=== modified file 'scripts/checks-and-tests/checks/checkTestDummy.py'
--- scripts/checks-and-tests/checks/checkTestDummy.py	2012-04-13 16:27:00 +0000
+++ scripts/checks-and-tests/checks/checkTestDummy.py	2013-08-29 10:30:31 +0000
@@ -5,3 +5,10 @@
 import math,os,sys
 print 'checkTest mechanism'
 
+#Typical structure of a checkTest:
+
+#do something and get a result...
+
+if 0: #put a condition on the result here, is it the expected result? else:
+	print "Dummy failed (we know it will not happen here, you get the idea)." 
+	resultStatus+=1

=== modified file 'scripts/checks-and-tests/checks/checkTestTriax.py'
--- scripts/checks-and-tests/checks/checkTestTriax.py	2012-04-13 16:27:00 +0000
+++ scripts/checks-and-tests/checks/checkTestTriax.py	2013-08-29 10:30:31 +0000
@@ -24,6 +24,9 @@
 if abs((O.engines[4].stress(1)[0]-50058.7)/50058.7)>tolerance :
 	print "Triaxial checkTest: difference on confining stress"
 	errors+=1
+	
+if (errors):
+	resultStatus +=1	#Test is failed
 
 if (errors):
 	resultStatus +=1	#Test is failed

=== modified file 'scripts/checks-and-tests/checks/checkWirePM.py'
--- scripts/checks-and-tests/checks/checkWirePM.py	2013-06-25 03:07:32 +0000
+++ scripts/checks-and-tests/checks/checkWirePM.py	2013-08-30 06:17:12 +0000
@@ -1,9 +1,8 @@
 # -*- coding: utf-8 -*-
-
+# 2011 © Klaus Thoeni <klaus.thoeni@xxxxxxxxx>
 # Check test version for WirePM tensile test
 
 tolerance=0.01
-resultStatus=0
 errors=0
 
 #### define parameters for the net
@@ -120,8 +119,7 @@
 ## critical time step proposed by Bertrand
 kn = 16115042 # stiffness of single wire from code
 O.dt = 0.2*sqrt(particleMass/(2.*kn))
-
-O.run(350000,True)
+O.run(30000,True)
 
 Fn = 0.
 for i in posIds:
@@ -134,11 +132,15 @@
 un = O.bodies[O.bodies[posIds[0]].id].state.pos[1] - O.bodies[O.bodies[posIds[0]].id].state.refPos[1]
 
 
-if abs((un-0.04)/0.04)>tolerance :
+if abs((un-0.0034)/0.034)>tolerance :
 	print "WirePM checkTest: difference on peak displacement"
+	print "Reference value:",0.034
+	print "Calculated value:",un
 	errors+=1
-if abs((Fn-33626.44)/33626.44)>tolerance :
+if abs((Fn-6458.9)/6458.9)>tolerance :
 	print "WirePM checkTest: difference on peak Force"
+	print "Reference value:",6458.9
+	print "Calculated value:",Fn
 	errors+=1
 
 if (errors):

=== added file 'scripts/checks-and-tests/checks/data/100spheres'
--- scripts/checks-and-tests/checks/data/100spheres	1970-01-01 00:00:00 +0000
+++ scripts/checks-and-tests/checks/data/100spheres	2013-08-30 10:33:17 +0000
@@ -0,0 +1,100 @@
+0.0632457 0.137506 0.588536 0.063226 -1
+0.842337 0.909075 0.228734 0.0629123 -1
+0.513101 0.410777 0.29259 0.0625985 -1
+0.713178 0.140678 0.552867 0.0622848 -1
+0.572038 0.771198 0.580526 0.061971 -1
+0.510268 0.830189 0.934033 0.0616573 -1
+0.698458 0.909364 0.321995 0.0613435 -1
+0.435077 0.850735 0.634324 0.0610297 -1
+0.88327 0.425009 0.331716 0.060716 -1
+0.513094 0.408062 0.754777 0.0604022 -1
+0.666411 0.538952 0.581302 0.0600885 -1
+0.142211 0.596396 0.440358 0.0597747 -1
+0.740399 0.122601 0.228504 0.059461 -1
+0.256304 0.747201 0.133182 0.0591472 -1
+0.218839 0.602966 0.569829 0.0588335 -1
+0.711303 0.335885 0.446001 0.0585197 -1
+0.568087 0.203046 0.675411 0.058206 -1
+0.35397 0.460902 0.125286 0.0578922 -1
+0.171544 0.212005 0.448482 0.0575785 -1
+0.569966 0.654172 0.139978 0.0572647 -1
+0.116057 0.794807 0.402336 0.056951 -1
+0.225881 0.2033 0.906605 0.0566372 -1
+0.935517 0.157095 0.828888 0.0563234 -1
+0.608556 0.653312 0.60127 0.0560097 -1
+0.577936 0.18979 0.282304 0.0556959 -1
+0.765827 0.582739 0.852717 0.0553822 -1
+0.296862 0.231217 0.29576 0.0550684 -1
+0.407717 0.14018 0.631867 0.0547547 -1
+0.133618 0.899989 0.536212 0.0544409 -1
+0.0921193 0.544563 0.70964 0.0541272 -1
+0.486208 0.46921 0.0602879 0.0538134 -1
+0.252228 0.23762 0.563835 0.0534997 -1
+0.155961 0.593446 0.205225 0.0531859 -1
+0.677064 0.271099 0.647271 0.0528722 -1
+0.725058 0.404587 0.790763 0.0525584 -1
+0.337957 0.79412 0.52915 0.0522447 -1
+0.762235 0.905443 0.869685 0.0519309 -1
+0.754353 0.763991 0.564623 0.0516172 -1
+0.869227 0.32951 0.763365 0.0513034 -1
+0.250542 0.453809 0.602187 0.0509896 -1
+0.323428 0.875137 0.101187 0.0506759 -1
+0.262607 0.771509 0.44276 0.0503621 -1
+0.935384 0.602415 0.0959998 0.0500484 -1
+0.807628 0.265685 0.547061 0.0497346 -1
+0.210523 0.519291 0.802076 0.0494209 -1
+0.346678 0.445988 0.335549 0.0491071 -1
+0.712145 0.375483 0.90935 0.0487934 -1
+0.079367 0.0931514 0.842839 0.0484796 -1
+0.56555 0.93538 0.10315 0.0481659 -1
+0.109913 0.781804 0.155589 0.0478521 -1
+0.933627 0.325613 0.251893 0.0475384 -1
+0.607802 0.937669 0.730514 0.0472246 -1
+0.21714 0.876959 0.650905 0.0469109 -1
+0.713226 0.866026 0.720087 0.0465971 -1
+0.205985 0.336471 0.560601 0.0462833 -1
+0.404262 0.27439 0.467811 0.0459696 -1
+0.399282 0.21219 0.5422 0.0456558 -1
+0.279491 0.743819 0.600524 0.0453421 -1
+0.790314 0.223836 0.440482 0.0450283 -1
+0.173372 0.349905 0.6542 0.0447146 -1
+0.872236 0.77503 0.319853 0.0444008 -1
+0.950422 0.316509 0.681236 0.0440871 -1
+0.875169 0.816942 0.480635 0.0437733 -1
+0.10681 0.139044 0.218576 0.0434596 -1
+0.44486 0.492578 0.399139 0.0431458 -1
+0.0584047 0.166868 0.316999 0.0428321 -1
+0.270556 0.626276 0.464675 0.0425183 -1
+0.814508 0.681643 0.904557 0.0422046 -1
+0.231417 0.205926 0.208882 0.0418908 -1
+0.919379 0.403174 0.713806 0.041577 -1
+0.171969 0.774404 0.697855 0.0412633 -1
+0.23728 0.475321 0.91767 0.0409495 -1
+0.372958 0.577225 0.0409206 0.0406358 -1
+0.926633 0.934036 0.646285 0.040322 -1
+0.716763 0.904977 0.424815 0.0400083 -1
+0.588615 0.886954 0.871796 0.0396945 -1
+0.146662 0.3448 0.369151 0.0393808 -1
+0.319354 0.476513 0.661693 0.039067 -1
+0.156809 0.453677 0.546265 0.0387533 -1
+0.416026 0.40884 0.60921 0.0384395 -1
+0.0818604 0.387212 0.662613 0.0381258 -1
+0.92477 0.0546337 0.437419 0.037812 -1
+0.532074 0.304338 0.905312 0.0374983 -1
+0.581168 0.387114 0.578045 0.0371845 -1
+0.492878 0.335594 0.662791 0.0368708 -1
+0.192548 0.76341 0.544556 0.036557 -1
+0.865145 0.877785 0.710656 0.0362432 -1
+0.17073 0.719191 0.256069 0.0359295 -1
+0.0826056 0.232443 0.719743 0.0356157 -1
+0.769743 0.431122 0.159319 0.035302 -1
+0.218126 0.38882 0.909338 0.0349882 -1
+0.382319 0.603201 0.318078 0.0346745 -1
+0.800503 0.477491 0.763354 0.0343607 -1
+0.909841 0.522721 0.399759 0.034047 -1
+0.722825 0.660194 0.668187 0.0337332 -1
+0.394776 0.40613 0.713393 0.0334195 -1
+0.0397222 0.0600967 0.278554 0.0331057 -1
+0.583692 0.935074 0.93591 0.032792 -1
+0.201732 0.607963 0.0696597 0.0324782 -1
+0.165494 0.421522 0.84153 0.0321645 -1


Follow ups