← Back to team overview

yade-dev team mailing list archive

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

 

Merge authors:
  Anton Gladky (gladky-anton)
  Anton Gladky (gladky-anton)
  Bruno Chareyre (bruno-chareyre)
  Chiara Modenese (chiara-modenese)
  Christian Jakob (jakob-ifgt)...

------------------------------------------------------------
revno: 3697 [merge]
committer: Jan Stransky <jan.stransky@xxxxxxxxxxx>
timestamp: Fri 2013-10-04 14:04:43 +0200
message:
  Merge branch 'master' of github.com:yade/trunk
removed:
  .kdev4/
  .kdev4/yade.kdev4
  Yade.kdevelop
  yade.kdev4
added:
  examples/jointedCohesiveFrictionalPM/gravityBis.py
  examples/jointedCohesiveFrictionalPM/identifBis.py
modified:
  .gitignore
  CMakeLists.txt
  ChangeLog
  core/Clump.cpp
  core/Clump.hpp
  core/ForceContainer.hpp
  core/Functor.hpp
  core/Scene.hpp
  doc/references.bib
  doc/sphinx/formulation.rst
  doc/sphinx/installation.rst
  doc/sphinx/introduction.rst
  doc/sphinx/templates/index.html
  doc/sphinx/user.rst
  examples/clumps/apply-buoyancy-clumps.py
  examples/jointedCohesiveFrictionalPM/README
  examples/jointedCohesiveFrictionalPM/identificationSpheresOnJoint.py
  examples/packs/packs.py
  lib/import/STLReader.hpp
  pkg/dem/FlowEngine.cpp
  pkg/dem/GlobalStiffnessTimeStepper.cpp
  pkg/dem/GlobalStiffnessTimeStepper.hpp
  pkg/dem/HertzMindlin.cpp
  pkg/dem/Ip2_ElastMat.cpp
  pkg/dem/JointedCohesiveFrictionalPM.cpp
  pkg/dem/JointedCohesiveFrictionalPM.hpp
  pkg/dem/NewtonIntegrator.hpp
  pkg/dem/Shop.cpp
  pkg/dem/Shop.hpp
  pkg/dem/SpherePack.cpp
  pkg/dem/Tetra.cpp
  pkg/dem/TriaxialTest.hpp
  py/_extraDocs.py
  py/_utils.cpp
  py/export.py
  py/pack/pack.py
  py/utils.py
  py/wrapper/yadeWrapper.cpp


--
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 '.gitignore'
--- .gitignore	2013-08-19 18:01:57 +0000
+++ .gitignore	2013-10-01 07:37:13 +0000
@@ -25,7 +25,7 @@
 doc/sphinx/yade.utils.rst
 doc/sphinx/yade.wrapper.rst
 doc/sphinx/yade.ymport.rst
-.kdev4/yade.kdev4
-yade.kdev4
+.kdev4/
+*.kdev4
 *.pyc
 

=== removed directory '.kdev4'
=== removed file '.kdev4/yade.kdev4'
--- .kdev4/yade.kdev4	2013-04-09 07:59:49 +0000
+++ .kdev4/yade.kdev4	1970-01-01 00:00:00 +0000
@@ -1,35 +0,0 @@
-[Buildset]
-BuildItems=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x01\x00\x00\x00\x0b\x00\x00\x00\x00\x01\x00\x00\x00\x08\x00y\x00a\x00d\x00e)
-
-[Launch]
-Launch Configurations=Launch Configuration 0
-
-[Launch][Launch Configuration 0]
-Configured Launch Modes=execute
-Configured Launchers=nativeAppLauncher
-Name=yade-debug
-Type=Native Application
-
-[Launch][Launch Configuration 0][Data]
-Arguments=\s/home/3S-LAB/bchareyre/yade/yade-test-kdev/bin/yade-true-true --debug -j 1  /home/3S-LAB/bchareyre2/yade/yade-test-kdev/yade/scripts/test/chained-cylinder-spring.py
-Debugger Shell=
-Dependencies=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x00)
-Dependency Action=Nothing
-Display Demangle Names=true
-Display Static Members=false
-EnvironmentGroup=default
-Executable=python
-GDB Path=gdb
-Remote GDB Config Script=
-Remote GDB Run Script=
-Remote GDB Shell Script=
-Try Setting Breakpoints On Loading Libraries=true
-Working Directory=
-isExecutable=true
-
-[MakeBuilder]
-Make Binary=scons
-Number Of Jobs=3
-
-[Project]
-VersionControlSupport=kdevgit

=== modified file 'CMakeLists.txt'
--- CMakeLists.txt	2013-09-05 07:52:37 +0000
+++ CMakeLists.txt	2013-09-30 16:52:38 +0000
@@ -63,7 +63,7 @@
 #===========================================================
 # Add possibility to use local boost installation (e.g. -DLocalBoost=1.46.1)
 
-FIND_PACKAGE(Boost ${LocalBoost} COMPONENTS python thread date_time filesystem iostreams regex serialization REQUIRED)
+FIND_PACKAGE(Boost ${LocalBoost} COMPONENTS python thread date_time filesystem iostreams regex serialization system REQUIRED)
 INCLUDE_DIRECTORIES (${Boost_INCLUDE_DIRS})
 # for checking purpose
 MESSAGE("--   Boost_VERSION: " ${Boost_VERSION})

=== modified file 'ChangeLog'
--- ChangeLog	2013-05-21 09:58:26 +0000
+++ ChangeLog	2013-09-29 22:06:07 +0000
@@ -1,4 +1,230 @@
 ==================================================
+yade-1.00.0
+Sun Sep 29 23:10:48 2013 +0200
+
+Anton Gladky (64):
+      Remove release file.
+      Add documentation, how to render particle with ParaView`s PointSprite plugin.
+      Fix spelling errors.
+      Add Changelog.
+      Add different capillar models into ViscoElasticPM.
+      Add links to equations, consider not only monodisperse particles.
+      Fix s parameter for Willet-formulation of capillar.
+      Add one more critical-calculation to capillar model.
+      Cleanings in viscoelastic capillar modell.
+      Move capillar calculation into another function not to overload VPM.
+      Modify Weigart`s model.
+      Update equations for Weigart`s capillar model.
+      Update capillar equations and names of schemas.
+      Move references to a references.bib.
+      Add comment on liquid bridges.
+      Fix some warnings (clang).
+      Fix compilation.
+      Implement rotational resistance in ViscoElasticPM.
+      Add massMultiply-parameter to ViscoElasticPM to have an opportunity to set kn, kt, cn and ct without multiplication on mass.
+      Implement Rabinovich`s capillar model.
+      Fix wrong calculation of the average rotational resistance.
+      Split ViscoelasticPM on capillar and dry parts.
+      Prevent devision by 0 in capillar Rabinovich model.
+      Prepare for flowengine compilation.
+      Merge libplugins, libsupport and libcore in libyade.
+      Fix FindCholmod.cmake.
+      Fix compilation of FlowBoundingSphere.ipp
+      Replace Cholmod-Feature by LinSolv.
+      Minor fix in CMakeList (FlowEnginge).
+      Implement PID controller to have a servo-engine.
+      Fix tests due to failing clumps-autotests.
+      Use combinedengine for ServoPIDController.
+      Fix hopefully clumps-autotests.
+      Add LudingPM.
+      Merge branch 'ndyck'
+      Add an example for LudingPM.
+      Use libyade again. Revert Bruno`s revert.
+      Fix configuration issue with CHUNKSIZE>0.
+      Drop RockPM.
+      Remove ParticleSizeDistrbutionRPMRecorder.
+      Remove CohesiveStateRPMRecorder.
+      Show PFVflow and LinSolv in disabled features, if they are disabled.
+      Include loki-library dirs and link against them. Fixes compilation on HPC TU Freiberg.
+      Set LinSolv and PFVFLOW ON by default.
+      Add recommended build-dependency for LinSolv and PFVFlow into documentation.
+      Replace ifndef/define-constructions by "#pragma once" in lib/triangulation, where it is possible.
+      Minor fix in capillary models in ViscoelasticPM.
+      Add [Pournin2001] into the description of ViscoelasticPM.
+      Minor fix in calculation s_crit in ViscoelasticPM.
+      Add information about github-hosting into the main page.
+      Add a notification to the screen, whether the current build is debugbuild.
+      Remove explicit linking of libstdcxx.
+      Use skipScripts variable to skip some scripts on check-tests.
+      Skip temporarly DEM-PFV-check.py to let daily-builds packages be built.
+      Remove kde-files from the trunk.
+      Minor fix in installation section of documentation.
+      Remove Fedora list package from documentation. The list is unsupported.
+      Add Antypov2011 reference and some links in Hertz-Mindlin model.
+      Fix some compilation warnings (GCC).
+      Replace libqglviewer-qt4-dev on libqglviewer-dev in installation section.
+      Fix errors in ForceContainer, detected by clang.
+      Fix compilation error.
+      Add export into LIGGGHTS-format.
+      1.00.0
+
+Bruno Chareyre (68):
+      +1 journal article
+      Add the color of the periodic cell a registered attribute.
+      - fix a bug that would let the capillary tables empty when postLoad was not triggered
+      Add function getCapillaryStress(), equivalent of getStress() but for capillary forces
+      -code cleaning
+      fix a latex equation
+      FlowEngine: exclude corner cases when listing constrictions sizes along the void path
+      +1 article
+      -fix url of an article
+      +4 journal papers
+      +1 journal article
+      - add "LINSOLV" source code for DEM-PFV coupling with direct sparse solvers
+      add strainRate attribute to TriaxialStressController + fix bug in example script
+      Revert "Merge libplugins, libsupport and libcore in libyade." Cause: the new cmake system breaks buildbot and does not work for chunkSize>0
+      - add getSceneAsString() to pass scenes between instances without going through the hard drive
+      fix CMakeList for chunkSize>=1
+      - enable load/save from/to python strings with O.sceneToString and O.stringToScene (for communication between parallel instances of yade)
+      -fix the return type of stringToScene()
+      clean the flow code (part 1)
+      cleaning the flow code (smallfix of part 1)
+      cleaning the flow code (part2)
+      cleaning the flow code (part3 and last)
+      -first example script for the fluid coupling with the DEM-PFV method
+      - new conference and journal papers
+      fixed reference
+      +1 PhD thesis
+      - more documentation of TesselationWrapper, with a section in user manual and pointer to published equations.
+      git ignore changes to .gitignore
+      undo previous change in gitignore, not the right way to fix
+      Turn a LOG_DEBUG into LOG_ERROR/return, to escape segfault. (ref: https://bugs.launchpad.net/bugs/1208878)
+      Add an optional argument to O.forces.f() and O.forces.t() to get correct forces on clumps.
+      doc improvement and more cross-links for TesselationWrapper and FlowEngine
+      -enable user defined forces on bodies applying permanently (with updated user manual)
+      +1 conference paper
+      -workaround https://bugs.launchpad.net/yade/+bug/1183402#3, allowing startup imports with optional argument     example: $yade -lscipy.interpolate
+      -fix '-l' command line option (no import lib was crashing)
+      fix uninitialized member of ForceContainer
+      fix compile warnings (unused variables)
+      - smallfixes in documentation
+      fix FlowEngine docstring
+      fix duplicate bib reference
+      small fix in bib entries
+      remove duplicate bib reference
+      commit small fix and update in bib files
+      make default FlowEngine::permeabilityFactor less absurd (crashing by default sucks)
+      regression (check-)test for FlowEngine
+      remove Dem3Dof form Yade (also eudoxos module, mostly based on Dem3Dof)
+      - remove Dem3Dof from documentation
+      remove eudoxos from build system (+ remove from VTKRecorder, that was left behind)
+      remove Dem3Dof from a docstring
+      remove Dem3Dof from alias
+      various fixes and improvements in checkTests
+      - increase verbosity of DEM-PFV checkTest
+      remove some debugging code left in chekList.py
+      make sure FlowEngine has been compiled before trying the checkTest DEM-PFV, as suggested by Klaus
+      make the DEM-PFV checktest fully determinist with a data file for initial positions
+      new attributes in FlowEngine to access low level cholmod/metis data
+      \#include <cholmod.h> in FlowEngine.cpp (why is it not needed on lucid?!)
+      add #ifdef LINSOLV guards in appropriate places in case someone (e.g. buildbot) compiles without cholmod
+      one more #ifdef LINSOLV guard
+      add a cmake path for metis.h on wheezy
+      Return a warning at startup if X rendering is unavailable despite gui is required.
+      User manual: correct the meaning of body.dynamic + remove utils. prefixes
+      Typo fix in prog.rst
+      Fix sphinx warning (no :gui: role)
+      yadeSphinx.py: remove eudoxos module from the build list
+      -remove empty section of doc: External modules
+      revert 3d7ca8577 (doc/current hyperlink), see also https://lists.launchpad.net/yade-dev/msg10035.html.
+
+Chiara Modenese (1):
+      Prevent the normal force become negative when viscous damping is applied.
+
+Christian Jakob (23):
+      added new example showing implementation of buoyancy
+      small fix in new example from previous commit
+      small fix of description in new buoyancy example
+      include integration scheme for inertia tensors of clumps; inertia/masses/volumes of clumps are updated automatically by call of updateProperties method; removed adaptClumpMasses method and example script
+      Merge branch 'master' of github.com:yade/trunk
+      make getRoundness() faster
+      shorten the code of Clump.cpp: switched getClumpVolumeAndAdaptInertia() method into updateProperties()
+      small fix of a comment
+      small fix in an example script
+      Merge branch 'master' of github.com:yade/trunk
+      remove unused #include in Clump.cpp
+      limit number of cubes for clump inertia integration scheme to 1000000; avoids worst case scenario with R_clump_member(s)<<R_clump
+      shorten code of Clump.cpp; improve inertia intergration scheme
+      undo unwanted changes in addToClump example from previous commit
+      bug fix of a previous commit
+      set maximum number of cubes for clump inertia integration scheme to 3375000 in Clump.cpp
+      fix inertia calculation and clump test
+      add output of inertia and mass to addToClump-example.py
+      Merge branch 'master' of github.com:yade/trunk
+      Merge branch 'master' of github.com:yade/trunk
+      Merge branch 'master' of github.com:yade/trunk
+      fix colors in releaseFromClump-example.py
+      improve addToClump() method, make it possible to add body lists
+
+Francois Kneib (3):
+      Fix bug #1161847 : Cannot create two clumpClouds in the same simulation (https://bugs.launchpad.net/yade/+bug/1161847).     Modified makeClumpCloud(...) in SpherePack.cpp : the random generator was wrong, fixed it.
+      Make the interaction between two Grids possible. It comes with a set of new classes, all in Grid.cpp/hpp :     - The geometry of interaction : GridCoGridCoGeom     - Its instanciation : Ig2_GridConnection_GridConnection_GridCoGridCoGeom     - An elastic frictional law : Law2_GridCoGridCoGeom_FrictPhys_CundallStrack
+      Lots of changes in the inelastic cohesive set of classes.     - correct a lot of bugs and comment the inelastic cohesive law : pkg/dem/Law2_ScGeom6D_InelastCohFrictPhys_CohesionMoment     - change some variables names and comments : pkg/dem/InelastCohFrictMat pkg/dem/InelastCohFrictPhys pkg/dem/Ip2_2xInelastCohFrictMat_InelastCohFrictPhys
+
+Jan Stránský (14):
+      added --diable-pynotify to yade-batch     Removed #include Shop.hpp from Cell.*pp     added area attribute to Facet
+      added triaxal test on cylinder example
+      Created classes for bubble interaction according to question #230574
+      Tetra modification (Ig2_Tetra_Tetra_TTtraSimpleGeom, Law2_TTetraSimpleGeom_NormPhys_Simple, modified GL functor, examples, utils.tetra)     added Ip2_ElastMat_... functors     fixed bug in utils.kineticEnergy for aspherical bodies
+      Merge branch 'master' of github.com:yade/trunk
+      added utils.UnstructuredGrid class for manipulating (external forces evaluation and positin changes) of FEM-like triangular and tetrahedral meshes     hopefully fixed CGAL compilation problem in pkg/dem/Tetra.*pp reported by Klaus
+      Improved documentation about O.load and O.save, motivated by question #230900
+      export.VTKExporter improvement (intaractions export), SVD matrix decomposition in python, Peri3dController improvement (compatibility with O.save/O.load)
+      doc improvement of Peri3dController
+      Merge branch 'master' of http://github.com/yade/trunk
+      midified exporter.VTKExporter for correct interactions export in periodic case
+      ConcretePM: modified damage tensor computetion, added elasticEnergy function, added export.VTKExporter.exportInteractions function, modified ymport.iges function
+      Merge branch 'master' of http://github.com/yade/trunk
+      Modifying code to enable compilation with QUAD_PRECISION without errors (does not work yet for CGAL enabled)
+
+Jerome Duriez (7):
+      - few changes in comments in JointedCohesiveFrictionalPM.*     - typos corrected in doxygen and sphinx docs of TriaxialTest (there was some "Trixial" instead of "Triaxial")     - correction of typo, broken links, and add of two precisions in the doc of a function of pack.py
+      Typo in NewtonIntegrator doc
+      Correction of link-syntax in doc of Law2_ScGeom_JCFpmPhys_JointedCohesiveFrictionalPM
+      Typo and redundancies corrected in doc of Functor.label
+      Typo in a figure legend
+      Precision in the doc relative to dt (6 is the maximal contact number in 2D)
+      Correction of a broken link in GSTS doc
+
+Klaus Thoeni (11):
+      various wire contact laws available now, add reference with details, add a check script for the wire model
+      various wire contact laws available now (new version), add reference with details
+      resolve clash between utils.box and box loaded from pylab
+      correct some spelling and make some example scripts working (more checks needed)
+      move one level up
+      use returnSpherePack=True in randomDensePack
+      fix some typos and links in documentation
+      Merge branch 'master' of github.com:yade/trunk
+      make script faster
+      introduce tolerence in overlap check for intersecting spheres
+      add MatchMaker for friction angle
+
+Luc Scholtes (4):
+      Merge branch 'master' of github.com:yade/trunk
+      cleanup in yade publications list
+      remove CohesiveFrictionalPM from trunk
+      add a new class for modelling jointed media (JointedCohesiveFrictionalPM) and examples to illustrate how to use it (examples/jointedCohesiveFrictionalPM/)
+      new reference added
+
+Nolan Dyck (2):
+      Updated function descriptions for BubbleMat
+      Merge branch 'master' of https://github.com/yade/trunk
+
+Raphaël Maurin (1):
+      Modify GlobalStiffnessTimeStepper for visco-elastic contact law.
+
+
+==================================================
 yade-0.97.0
 Sun May 12 14:48:29 2013 +0200
 

=== removed file 'Yade.kdevelop'
--- Yade.kdevelop	2010-09-30 09:05:24 +0000
+++ Yade.kdevelop	1970-01-01 00:00:00 +0000
@@ -1,229 +0,0 @@
-<?xml version = '1.0'?>
-<kdevelop>
-  <general>
-    <author>Vaclav Smilauer</author>
-    <email>eudoxos@xxxxxxxx</email>
-    <version>$VERSION$</version>
-    <projectmanagement>KDevCustomProject</projectmanagement>
-    <primarylanguage>C++</primarylanguage>
-    <ignoreparts/>
-    <projectname>Yade</projectname>
-    <projectdirectory>.</projectdirectory>
-    <absoluteprojectpath>false</absoluteprojectpath>
-    <description></description>
-    <defaultencoding></defaultencoding>
-    <versioncontrol/>
-  </general>
-  <kdevcustomproject>
-    <run>
-      <mainprogram>/usr/bin/python</mainprogram>
-      <directoryradio>executable</directoryradio>
-      <programargs>/home/chia/yade/inst/bin/yade-r2446</programargs>
-      <globaldebugarguments>/home/chia/yade/inst/bin/yade-r2446-dbg</globaldebugarguments>
-      <globalcwd>/tmp</globalcwd>
-      <useglobalprogram>false</useglobalprogram>
-      <terminal>true</terminal>
-      <autocompile>true</autocompile>
-      <autoinstall>true</autoinstall>
-      <autokdesu>false</autokdesu>
-      <envvars/>
-    </run>
-    <build>
-      <buildtool>make</buildtool>
-      <builddir></builddir>
-    </build>
-    <make>
-      <abortonerror>false</abortonerror>
-      <numberofjobs>4</numberofjobs>
-      <prio>0</prio>
-      <dontact>false</dontact>
-      <makebin>scons</makebin>
-      <defaulttarget></defaulttarget>
-      <makeoptions></makeoptions>
-      <selectedenvironment>default</selectedenvironment>
-      <environments>
-        <default>
-          <envvar value="localhost/1 192.168.27.125/2 192.168.27.91/1 192.168.23.204/2 192.168.27.201/2 192.168.27.118/2 194.254.65.169/2" name="DISTCC_HOSTS" />
-        </default>
-      </environments>
-    </make>
-    <filetypes>
-      <filetype>*.java</filetype>
-      <filetype>*.h</filetype>
-      <filetype>*.H</filetype>
-      <filetype>*.hh</filetype>
-      <filetype>*.hxx</filetype>
-      <filetype>*.hpp</filetype>
-      <filetype>*.c</filetype>
-      <filetype>*.C</filetype>
-      <filetype>*.cc</filetype>
-      <filetype>*.cpp</filetype>
-      <filetype>*.c++</filetype>
-      <filetype>*.cxx</filetype>
-      <filetype>Makefile</filetype>
-      <filetype>CMakeLists.txt</filetype>
-    </filetypes>
-    <blacklist/>
-    <other>
-      <prio>0</prio>
-      <otherbin>scons</otherbin>
-      <defaulttarget></defaulttarget>
-      <otheroptions></otheroptions>
-      <selectedenvironment>default</selectedenvironment>
-      <environments>
-        <default/>
-      </environments>
-    </other>
-  </kdevcustomproject>
-  <kdevdebugger>
-    <general>
-      <dbgshell></dbgshell>
-      <gdbpath></gdbpath>
-      <configGdbScript></configGdbScript>
-      <runShellScript></runShellScript>
-      <runGdbScript></runGdbScript>
-      <breakonloadinglibs>true</breakonloadinglibs>
-      <separatetty>false</separatetty>
-      <floatingtoolbar>false</floatingtoolbar>
-      <raiseGDBOnStart>false</raiseGDBOnStart>
-    </general>
-    <display>
-      <staticmembers>true</staticmembers>
-      <demanglenames>true</demanglenames>
-      <outputradix>10</outputradix>
-    </display>
-  </kdevdebugger>
-  <kdevdoctreeview>
-    <ignoretocs>
-      <toc>ada</toc>
-      <toc>ada_bugs_gcc</toc>
-      <toc>bash</toc>
-      <toc>bash_bugs</toc>
-      <toc>clanlib</toc>
-      <toc>fortran_bugs_gcc</toc>
-      <toc>gnome1</toc>
-      <toc>gnustep</toc>
-      <toc>gtk</toc>
-      <toc>gtk_bugs</toc>
-      <toc>haskell</toc>
-      <toc>haskell_bugs_ghc</toc>
-      <toc>java_bugs_gcc</toc>
-      <toc>java_bugs_sun</toc>
-      <toc>kde2book</toc>
-      <toc>opengl</toc>
-      <toc>pascal_bugs_fp</toc>
-      <toc>php</toc>
-      <toc>php_bugs</toc>
-      <toc>perl</toc>
-      <toc>perl_bugs</toc>
-      <toc>python</toc>
-      <toc>python_bugs</toc>
-      <toc>qt-kdev3</toc>
-      <toc>ruby</toc>
-      <toc>ruby_bugs</toc>
-      <toc>sdl</toc>
-      <toc>sw</toc>
-      <toc>w3c-dom-level2-html</toc>
-      <toc>w3c-svg</toc>
-      <toc>w3c-uaag10</toc>
-      <toc>wxwidgets_bugs</toc>
-    </ignoretocs>
-    <ignoreqt_xml>
-      <toc>Guide to the Qt Translation Tools</toc>
-      <toc>Qt Assistant Manual</toc>
-      <toc>Qt Designer Manual</toc>
-      <toc>Qt Reference Documentation</toc>
-      <toc>qmake User Guide</toc>
-    </ignoreqt_xml>
-    <ignoredoxygen>
-      <toc>KDE Libraries (Doxygen)</toc>
-    </ignoredoxygen>
-  </kdevdoctreeview>
-  <kdevfilecreate>
-    <filetypes/>
-    <useglobaltypes>
-      <type ext="ui" />
-      <type ext="cpp" />
-    </useglobaltypes>
-  </kdevfilecreate>
-  <kdevcppsupport>
-    <qt>
-      <used>false</used>
-      <version>3</version>
-      <includestyle>3</includestyle>
-      <root>/usr/share/qt3</root>
-      <designerintegration>EmbeddedKDevDesigner</designerintegration>
-      <qmake>/usr/bin/qmake-qt3</qmake>
-      <designer>/usr/bin/designer</designer>
-      <designerpluginpaths/>
-    </qt>
-    <codecompletion>
-      <automaticCodeCompletion>false</automaticCodeCompletion>
-      <automaticArgumentsHint>true</automaticArgumentsHint>
-      <automaticHeaderCompletion>true</automaticHeaderCompletion>
-      <codeCompletionDelay>250</codeCompletionDelay>
-      <argumentsHintDelay>400</argumentsHintDelay>
-      <headerCompletionDelay>250</headerCompletionDelay>
-      <showOnlyAccessibleItems>false</showOnlyAccessibleItems>
-      <completionBoxItemOrder>0</completionBoxItemOrder>
-      <howEvaluationContextMenu>true</howEvaluationContextMenu>
-      <showCommentWithArgumentHint>true</showCommentWithArgumentHint>
-      <statusBarTypeEvaluation>false</statusBarTypeEvaluation>
-      <namespaceAliases>std=_GLIBCXX_STD;__gnu_cxx=std</namespaceAliases>
-      <processPrimaryTypes>true</processPrimaryTypes>
-      <processFunctionArguments>false</processFunctionArguments>
-      <preProcessAllHeaders>false</preProcessAllHeaders>
-      <parseMissingHeaders>false</parseMissingHeaders>
-      <resolveIncludePaths>true</resolveIncludePaths>
-      <alwaysParseInBackground>true</alwaysParseInBackground>
-      <usePermanentCaching>true</usePermanentCaching>
-      <alwaysIncludeNamespaces>false</alwaysIncludeNamespaces>
-      <includePaths>.;</includePaths>
-      <parseMissingHeadersExperimental>false</parseMissingHeadersExperimental>
-      <resolveIncludePathsUsingMakeExperimental>false</resolveIncludePathsUsingMakeExperimental>
-    </codecompletion>
-    <creategettersetter>
-      <prefixGet></prefixGet>
-      <prefixSet>set</prefixSet>
-      <prefixVariable>m_,_</prefixVariable>
-      <parameterName>theValue</parameterName>
-      <inlineGet>true</inlineGet>
-      <inlineSet>true</inlineSet>
-    </creategettersetter>
-    <splitheadersource>
-      <enabled>false</enabled>
-      <synchronize>true</synchronize>
-      <orientation>Vertical</orientation>
-    </splitheadersource>
-    <references/>
-  </kdevcppsupport>
-  <cppsupportpart>
-    <filetemplates>
-      <interfacesuffix>.hpp</interfacesuffix>
-      <implementationsuffix>.cpp</implementationsuffix>
-    </filetemplates>
-  </cppsupportpart>
-  <kdevdocumentation>
-    <projectdoc>
-      <docsystem></docsystem>
-      <docurl></docurl>
-      <usermanualurl></usermanualurl>
-    </projectdoc>
-  </kdevdocumentation>
-  <kdevfileview>
-    <groups>
-      <hidenonprojectfiles>false</hidenonprojectfiles>
-      <hidenonlocation>false</hidenonlocation>
-    </groups>
-    <tree>
-      <hidepatterns>*.o,*.lo,CVS</hidepatterns>
-      <hidenonprojectfiles>false</hidenonprojectfiles>
-      <showvcsfields>false</showvcsfields>
-    </tree>
-  </kdevfileview>
-  <ctagspart>
-    <customArguments>-R --extra=+q --fields=+n --exclude='.*' --exclude=attic --exclude=doc --exclude=scons-local --exclude=include --exclude=lib/triangulation --exclude=debian --exclude='*.so' --exclude='*.s' --exclude='*.ii' --langmap=c++:+.inl,c++:+.tpp,c++:+.ipp</customArguments>
-    <activeTagsFiles/>
-    <customTagfilePath>/home/chia/yade/src/r2446/tags</customTagfilePath>
-  </ctagspart>
-</kdevelop>

=== modified file 'core/Clump.cpp'
--- core/Clump.cpp	2013-08-30 06:19:46 +0000
+++ core/Clump.cpp	2013-10-04 11:41:10 +0000
@@ -82,7 +82,7 @@
 
 */
 
-void Clump::updateProperties(const shared_ptr<Body>& clumpBody){
+void Clump::updateProperties(const shared_ptr<Body>& clumpBody, unsigned int discretization, bool integrateInertia){
 	LOG_DEBUG("Updating clump #"<<clumpBody->id<<" parameters");
 	const shared_ptr<State> state(clumpBody->state);
 	const shared_ptr<Clump> clump(YADE_PTR_CAST<Clump>(clumpBody->shape));
@@ -110,16 +110,18 @@
 	bool intersecting = false;
 	shared_ptr<Sphere> sph (new Sphere);
 	int Sph_Index = sph->getClassIndexStatic();		// get sphere index for checking if bodies are spheres
-	FOREACH(MemberMap::value_type& mm, clump->members){
-		const shared_ptr<Body> subBody1=Body::byId(mm.first);
+	if (integrateInertia){
 		FOREACH(MemberMap::value_type& mm, clump->members){
-			const shared_ptr<Body> subBody2=Body::byId(mm.first);
-			if ((subBody1->shape->getClassIndex() ==  Sph_Index) && (subBody2->shape->getClassIndex() ==  Sph_Index) && (subBody1!=subBody2)){//clump members should be spheres
-				Vector3r dist = subBody1->state->pos - subBody2->state->pos;
-				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.001*min(sphere1->radius,sphere2->radius)) {intersecting = true; break;}
+			const shared_ptr<Body> subBody1=Body::byId(mm.first);
+			FOREACH(MemberMap::value_type& mm, clump->members){
+				const shared_ptr<Body> subBody2=Body::byId(mm.first);
+				if ((subBody1->shape->getClassIndex() ==  Sph_Index) && (subBody2->shape->getClassIndex() ==  Sph_Index) && (subBody1!=subBody2)){//clump members should be spheres
+					Vector3r dist = subBody1->state->pos - subBody2->state->pos;
+					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.001*min(sphere1->radius,sphere2->radius)) {intersecting = true; break;}
+				}
 			}
 		}
 	}
@@ -150,8 +152,7 @@
 			}
 		}
 		//get volume and inertia tensor using regular cubic cell array inside bounding box of the clump:
-		int divisor = 15; 		//TODO: make it choosable by users
-		Real dx = rMin/divisor; 	//edge length of cell
+		Real dx = rMin/discretization; 	//edge length of cell
 		Real aabbMax = max(max(aabb.max().x()-aabb.min().x(),aabb.max().y()-aabb.min().y()),aabb.max().z()-aabb.min().z());
 		if (aabbMax/dx > 150) dx = aabbMax/150;//limit dx
 		Real dv = pow(dx,3);		//volume of cell
@@ -169,6 +170,7 @@
 								Sg += dv*x;
 								//inertia I = sum_i( mass_i*dist^2 + I_s) )	//steiners theorem
 								Ig += dv*( x.dot(x)*Matrix3r::Identity()-x*x.transpose()/*dist^2*/+Matrix3r(Vector3r::Constant(dv*pow(dx,2)/6.).asDiagonal())/*I_s/m = d^2: along princial axes of dv; perhaps negligible?*/);
+								break;
 							}
 						}
 					}

=== modified file 'core/Clump.hpp'
--- core/Clump.hpp	2013-06-21 06:53:43 +0000
+++ core/Clump.hpp	2013-10-04 11:41:10 +0000
@@ -61,7 +61,7 @@
 		static void add(const shared_ptr<Body>& clump, const shared_ptr<Body>& subBody);
 		static void del(const shared_ptr<Body>& clump, const shared_ptr<Body>& subBody);
 		//! Recalculate physical properties of Clump.
-		static void updateProperties(const shared_ptr<Body>& clump);
+		static void updateProperties(const shared_ptr<Body>& clump, unsigned int discretization, bool integrateInertia);
 		//! Calculate positions and orientations of members based on relative Se3; newton pointer (if non-NULL) calls NewtonIntegrator::saveMaximaVelocity
 		// done as template to avoid cross-dependency between clump and newton (not necessary if all plugins are linked together)
 		template<class IntegratorT>

=== modified file 'core/ForceContainer.hpp'
--- core/ForceContainer.hpp	2013-08-26 21:41:10 +0000
+++ core/ForceContainer.hpp	2013-09-24 06:14:29 +0000
@@ -234,8 +234,22 @@
 		const Vector3r& getPermForce(Body::id_t id) { ensureSize(id); return _permForce[id]; }
 		const Vector3r& getPermTorque(Body::id_t id) { ensureSize(id); return _permTorque[id]; }
 		// single getters do the same as globally synced ones in the non-parallel flavor
-		const Vector3r& getForceSingle (Body::id_t id){ ensureSize(id); return _force [id] + permForceUsed?_permForce[id]:_zero; }
-		const Vector3r& getTorqueSingle(Body::id_t id){ ensureSize(id); return _torque[id]; + permForceUsed?_permTorque[id]:_zero;}
+		const Vector3r& getForceSingle (Body::id_t id){ 
+			ensureSize(id); 
+			if (permForceUsed) {
+				return _force [id] + _permForce[id];
+			} else {
+				return _force [id];
+			}
+		}
+		const Vector3r& getTorqueSingle(Body::id_t id){ 
+			ensureSize(id); 
+			if (permForceUsed) {
+				return _torque[id] + _permTorque[id];
+			} else {
+				return _torque[id];
+			}
+		}
 		const Vector3r& getMoveSingle  (Body::id_t id){ ensureSize(id); return _move  [id]; }
 		const Vector3r& getRotSingle   (Body::id_t id){ ensureSize(id); return _rot   [id]; }
 
@@ -258,7 +272,7 @@
 		
 		void sync(){
 			if (permForceUsed) for(long id=0; id<(long)size; id++)
-				{_force[id]+=permForce[id]; _torque[id]+=permTorque[id];}
+				{_force[id]+=_permForce[id]; _torque[id]+=_permTorque[id];}
 			return;}
 		unsigned long syncCount;
 		// interaction in which the container was last reset; used by NewtonIntegrator to detect whether ForceResetter was not forgotten

=== modified file 'core/Functor.hpp'
--- core/Functor.hpp	2013-04-23 14:07:34 +0000
+++ core/Functor.hpp	2013-09-27 12:11:28 +0000
@@ -25,7 +25,7 @@
 	Scene* scene;
 	virtual ~Functor(); // defined in Dispatcher.cpp
 	YADE_CLASS_BASE_DOC_ATTRS_CTOR_PY(Functor,Serializable,"Function-like object that is called by Dispatcher, if types of arguments match those the Functor declares to accept.",
-		((string,label,,,"Textual label for this object; must be valid python identifier, you can refer to it directly fron python (must be a valid python identifier).")),
+		((string,label,,,"Textual label for this object; must be a valid python identifier, you can refer to it directly from python.")),
 		/*ctor*/
 		#ifdef USE_TIMING_DELTAS
 			timingDeltas=shared_ptr<TimingDeltas>(new TimingDeltas);

=== modified file 'core/Scene.hpp'
--- core/Scene.hpp	2012-07-16 20:13:46 +0000
+++ core/Scene.hpp	2013-10-02 12:47:38 +0000
@@ -111,8 +111,8 @@
 			SpeedElements.Zero();
 		,
 		/* py */
-		.add_property("localCoords",&Scene::usesLocalCoords,"Whether local coordianate system is used on interactions (set by :yref:`Ig2Functor`.")
-		.add_property("compressionNegative",&Scene::usesLocalCoords,"Whether the convention is that compression has negative sign (set by :yref:`Ig2Functor`.")
+		.add_property("localCoords",&Scene::usesLocalCoords,"Whether local coordianate system is used on interactions (set by :yref:`IGeomFunctor`).")
+		.add_property("compressionNegative",&Scene::usesLocalCoords,"Whether the convention is that compression has negative sign (set by :yref:`IGeomFunctor`).")
 	);
 	DECLARE_LOGGER;
 };

=== modified file 'doc/references.bib'
--- doc/references.bib	2013-08-28 10:26:24 +0000
+++ doc/references.bib	2013-09-23 17:17:34 +0000
@@ -608,3 +608,14 @@
 	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",
 }
+
+@article{Antypov2011,
+	author={D. Antypov and J. A. Elliott},
+	title={On an analytical solution for the damped Hertzian spring},
+	journal={EPL (Europhysics Letters)},
+	volume={94},
+	number={5},
+	pages={50004},
+	url={http://stacks.iop.org/0295-5075/94/i=5/a=50004},
+	year={2011}
+}

=== modified file 'doc/sphinx/formulation.rst'
--- doc/sphinx/formulation.rst	2013-08-29 10:30:31 +0000
+++ doc/sphinx/formulation.rst	2013-09-27 12:14:48 +0000
@@ -664,7 +664,7 @@
 			 
 In Yade, particles have associated :yref:`Material` which defines density $\rho$ (:yref:`Material.density`), and also may define (in :yref:`ElastMat` and derived classes) particle's "Young's modulus" $E$ (:yref:`ElastMat.young`). $\rho$ is used when particle's mass $m$ is initially computed from its $\rho$, while $E$ is taken in account when creating new interaction between particles, affecting stiffness $K_N$. Knowing $m$ and $K_N$, we can estimate :eq:`eq-dtcr-particle-stiffness` for each particle; we obviously neglect 
 
-* number of interactions per particle $N_i$; for a "reasonable" radius distribution, however, there is a geometrically imposed upper limit (6 for a packing of spheres with equal radii, for instance);
+* number of interactions per particle $N_i$; for a "reasonable" radius distribution, however, there is a geometrically imposed upper limit (6 for a 2D-packing of spheres with equal radii, for instance);
 * the exact relationship the between particles' rigidities $E_i$, $E_j$, supposing only that $K_N$ is somehow proportional to them.
 
 By defining $E$ and $\rho$, particles have continuum-like quantities. Explicit integration schemes for continuum equations impose a critical timestep based on sonic speed $\sqrt{E/\rho}$; the elastic wave must not propagate farther than the minimum distance of integration points $l_{\rm min}$ during one step. Since $E$, $\rho$ are parameters of the elastic continuum and $l_{\rm min}$ is fixed beforehand, we obtain

=== modified file 'doc/sphinx/installation.rst'
--- doc/sphinx/installation.rst	2013-08-15 12:59:27 +0000
+++ doc/sphinx/installation.rst	2013-09-24 14:55:35 +0000
@@ -120,20 +120,20 @@
 		libboost-iostreams-dev python-dev libboost-python-dev ipython \
 		python-matplotlib libsqlite3-dev python-numpy python-tk gnuplot \
 		libgts-dev python-pygraphviz libvtk5-dev python-scientific libeigen3-dev \
-		binutils-gold python-xlib python-qt4 pyqt4-dev-tools \
+		python-xlib python-qt4 pyqt4-dev-tools \
 		gtk2-engines-pixbuf python-argparse \
-		libqglviewer-qt4-dev python-imaging libjs-jquery python-sphinx python-git python-bibtex \
+		libqglviewer-dev python-imaging libjs-jquery python-sphinx python-git python-bibtex \
 		libxmu-dev libxi-dev libgmp3-dev libcgal-dev help2man libsuitesparse-dev \
-		libopenblas-dev libmetis-dev
-
-	* **Fedora**::
-
-		yum install cmake qt3-devel freeglut-devel boost-devel boost-date-time \
-		boost-filesystem boost-thread boost-regex fakeroot gcc gcc-c++ boost-iostreams \
-		python-devel boost-python ipython python-matplotlib \
-		sqlite-devel python-numeric ScientificPython-tk gnuplot doxygen gts-devel \
-		graphviz-python vtk-devel ScientificPython eigen2-devel libQGLViewer-devel \
-		loki-lib-devel python-xlib PyQt4 PyQt4-devel python-imaging python-sphinx python-bibtex
+		libopenblas-dev libmetis-dev python-gts
+
+If you are using other distribuition, than Debian or its derivatives, you should
+install the software, which is listed above. Their names can differ from the 
+names of Debian-packages.
+
+Some of packages (for example, cmake, eigen3) are mandatory, some of them
+are optional. Watch for notes and warnings/errors, which are shown
+by cmake during configuration step. If the missing package is optional,
+some of Yade features will be disabled (see the messages at the end of configuration).
 
 
 Compilation
@@ -165,6 +165,8 @@
 	* ENABLE_OPENMP: enable OpenMP-parallelizing option (ON by default)
 	* ENABLE_GTS: enable GTS-option (ON by default)
 	* ENABLE_GL2PS: enable GL2PS-option (ON by default)
+	* ENABLE_LINSOLV: enable LINSOLV-option (ON by default)
+	* ENABLE_PFVFLOW: enable PFVFLOW-option, FlowEngine (ON by default)
 	* runtimePREFIX: used for packaging, when install directory is not the same is runtime directory (/usr/local by default)
 	* CHUNKSIZE: used, if you want several sources to be compiled at once. Increases compilation speed and RAM-consumption during it (1 by default).
 

=== modified file 'doc/sphinx/introduction.rst'
--- doc/sphinx/introduction.rst	2013-08-29 10:30:31 +0000
+++ doc/sphinx/introduction.rst	2013-09-27 12:13:27 +0000
@@ -417,7 +417,7 @@
 .. _img-yade-iter-loop:
 .. figure:: fig/yade-iter-loop.*
 
-	Typical simulation loop; each step begins at body-cented bit at 11 o'clock, continues with interaction bit, force application bit, miscillanea and ends with time update.
+	Typical simulation loop; each step begins at body-centered bit at 11 o'clock, continues with interaction bit, force application bit, miscillanea and ends with time update.
 
 Each of these actions is represented by an :yref:`Engine<Engine>`, functional element of simulation. The sequence of engines is called *simulation loop*.
 

=== modified file 'doc/sphinx/templates/index.html'
--- doc/sphinx/templates/index.html	2013-08-30 19:39:27 +0000
+++ doc/sphinx/templates/index.html	2013-09-26 13:26:34 +0000
@@ -28,7 +28,7 @@
         <p class="biglink"><a class="biglink" href="https://launchpad.net/yade/+announcements";>NEWS</a><br/>
            <span class="linkdescr">latest news about Yade project</span></p>
         <p class="biglink"><a class="biglink" href="https://yade-dem.org/wiki/Authors_and_contributors";>Authors and contributors</a><br/>
-           <span class="linkdescr">information about people, who are creating Yade</span></p>
+           <span class="linkdescr">information about the people working on Yade</span></p>
         <p class="biglink"><a class="biglink" href="https://yade-dem.org/wiki/Contact";>Contact</a><br/>
            <span class="linkdescr">contact details, mailing lists</span></p>
         <p class="biglink"><a class="biglink" href="https://yade-dem.org/wiki/WhoIsDoingWhat";>Who Is Doing What (Wiki)</a><br/>
@@ -62,7 +62,7 @@
         <p class="biglink"><a class="biglink" href="{{ pathto("user") }}">User's Manual</a><br/>
            <span class="linkdescr">functionality guide and description</span></p>
         <p class="biglink"><a class="biglink" href="{{ pathto("prog") }}">Programmer's Manual</a><br/>
-           <span class="linkdescr">understanding and modifying the internals</span></p>
+           <span class="linkdescr">understanding and modifying the internals of Yade</span></p>
       </td>
       <td width="50%">
         <p class="biglink"><a class="biglink" href="{{ pathto("formulation") }}">DEM Formulation</a><br/>
@@ -71,8 +71,6 @@
            <span class="linkdescr">simulation building blocks, c++ &amp; python</span></p>
         <p class="biglink"><a class="biglink" href="{{ pathto("modules") }}">Yade modules</a><br/>
            <span class="linkdescr">python modules extending Yade</span></p>
-        <p class="biglink"><a class="biglink" href="{{ pathto("external") }}">External modules</a><br/>
-           <span class="linkdescr">3rd party modules coming with Yade</span></p>
       </td>
     </tr>
     <tr>

=== modified file 'doc/sphinx/user.rst'
--- doc/sphinx/user.rst	2013-09-11 10:52:00 +0000
+++ doc/sphinx/user.rst	2013-10-02 15:32:00 +0000
@@ -25,16 +25,16 @@
 Creating Body objects
 ----------------------
 
-:yref:`Body` objects are only rarely constructed by hand by their components (:yref:`Shape`, :yref:`Bound`, :yref:`State`, :yref:`Material`); instead, convenience functions :yref:`yade.utils.sphere`, :yref:`yade.utils.facet` and :yref:`yade.utils.wall` are used to create them. Using these functions also ensures better future compatibility, if internals of :yref:`Body` change in some way. These functions receive geometry of the particle and several other characteristics. See their documentation for details. If the same :yref:`Material` is used for several (or many) bodies, it can be shared by adding it in ``O.materials``, as explained below.
+:yref:`Body` objects are only rarely constructed by hand by their components (:yref:`Shape`, :yref:`Bound`, :yref:`State`, :yref:`Material`); instead, convenience functions :yref:`sphere<yade.utils.sphere>`, :yref:`facet<yade.utils.facet>` and :yref:`wall<yade.utils.wall>` are used to create them. Using these functions also ensures better future compatibility, if internals of :yref:`Body` change in some way. These functions receive geometry of the particle and several other characteristics. See their documentation for details. If the same :yref:`Material` is used for several (or many) bodies, it can be shared by adding it in ``O.materials``, as explained below.
 
 Defining materials
 ------------------
 
 The ``O.materials`` object (instance of :yref:`Omega.materials`) holds defined shared materials for bodies. It only supports addition, and will typically hold only a few instance (though there is no limit).
 
-``label`` given to each material is optional, but can be passed to :yref:`sphere` and other functions for constructing body. The value returned by ``O.materials.append`` is an ``id`` of the material, which can be also passed to :yref:`sphere` -- it is a little bit faster than using label, though not noticeable for small number of particles and perhaps less convenient.
+``label`` given to each material is optional, but can be passed to :yref:`sphere<yade.utils.sphere>` and other functions for constructing body. The value returned by ``O.materials.append`` is an ``id`` of the material, which can be also passed to :yref:`sphere<yade.utils.sphere>` -- it is a little bit faster than using label, though not noticeable for small number of particles and perhaps less convenient.
 
-If no :yref:`Material` is specified when calling :yref:`sphere`, the *last* defined material is used; that is a convenient default. If no material is defined yet (hence there is no last material), a default material will be created using :yref:`defaultMaterial`; this should not happen for serious simulations, but is handy in simple scripts, where exact material properties are more or less irrelevant.
+If no :yref:`Material` is specified when calling :yref:`sphere<yade.utils.sphere>`, the *last* defined material is used; that is a convenient default. If no material is defined yet (hence there is no last material), a default material will be created: FrictMat(density=2e3,young=30e9,poisson=.3,frictionAngle=.5236). This should not happen for serious simulations, but is handy in simple scripts, where exact material properties are more or less irrelevant.
 
 .. ipython::
 
@@ -94,7 +94,7 @@
 * surface function :yref:`yade.pack.gtsSurface2Facets`
 * import functions :yref:`yade.ymport.gmsh`, :yref:`yade.ymport.stl`, …
 
-As those functions use :yref:`yade.sphere` and :yref:`yade.facet` internally, they accept additional argument passed to those function. In particular, material for each body is selected following the rules above (last one if not specified, by label, by index, etc.).
+As those functions use :yref:`sphere<yade.utils.sphere>` and :yref:`facet<yade.utils.facet>` internally, they accept additional argument passed to those function. In particular, material for each body is selected following the rules above (last one if not specified, by label, by index, etc.).
 
 
 Clumping particles together
@@ -102,8 +102,8 @@
 
 In some cases, you might want to create rigid aggregate of individual particles (i.e. particles will retain their mutual position during simulation). This we call a :yref:`clump<Clump>`. 
 A clump is internally represented by a special :yref:`body<Body>`, referenced by :yref:`clumpId<Body.clumpId>` of its members (see also  :yref:`isClump<Body.isClump>`, :yref:`isClumpMember<Body.isClumpMember>` and :yref:`isStandalone<Body.isStandalone>`). 
-Like every body a clump has a :yref:`position<State.pos>`, which is the balance point between all members. 
-A clump body itself has no :yref:`interactions<Interaction>` with other bodies. Interactions between clumps is internally represented by interactions between clump members. There are also no interactions between clump members with same clumpId. 
+Like every body a clump has a :yref:`position<State.pos>`, which is the (mass) balance point between all members. 
+A clump body itself has no :yref:`interactions<Interaction>` with other bodies. Interactions between clumps is represented by interactions between clump members. There are no interactions between clump members of the same clump. 
 
 YADE supports different ways of creating clumps:
 
@@ -150,7 +150,7 @@
 	
 -> :yref:`clump()<BodyContainer.clump>` returns ``clumpId``
 
-* Another option is to replace :yref:`standalone<Body.isStandalone>` spheres from a given packing (see :yref:`SpherePack<yade._packSpheres.SpherePack>` and :yref:`makeCloud<yade._packSpheres.SpherePack.makeCloud>`) using clump templates.
+* Another option is to replace :yref:`standalone<Body.isStandalone>` spheres from a given packing (see :yref:`SpherePack<yade._packSpheres.SpherePack>` and :yref:`makeCloud<yade._packSpheres.SpherePack.makeCloud>`) by clumps using clump templates.
 
 This is done by a function called :yref:`replaceByClumps()<BodyContainer.replaceByClumps>`. This function takes a list of :yref:`clumpTemplates()<yade.clumpTemplate>` and a list of amounts and replaces spheres by clumps. The volume of a new clump will be the same as the volume of the sphere, that was replaced (clump volume/mass/inertia is accounting for overlaps assuming that there are only pair overlaps).
 
@@ -158,7 +158,29 @@
 
 It is also possible to :yref:`add<BodyContainer.addToClump>` bodies to a clump and :yref:`release<BodyContainer.releaseFromClump>` bodies from a clump. Also you can :yref:`erase<BodyContainer.erase>` the clump (clump members will get standalone spheres).
 
-.. note:: Have a look at ``examples/clumps/`` folder. There you will find some examples, that show usage of different functions for clumps.
+Additionally YADE supports to achieve the :yref:`roundness<BodyContainer.getRoundness>` of a clump or roundness coefficient of a packing. Parts of the packing can be excluded from roundness measurement via exclude list.
+
+.. ipython::
+
+	@suppress
+	Yade [0]: O.reset()
+
+	Yade [1]: bodyList = []
+
+	Yade [2]: for ii in range(1,5):
+	   ...:    bodyList.append(O.bodies.append(sphere([ii,ii,ii],.5)))
+	   ...:
+
+	Yade [4]: O.bodies.clump(bodyList)
+
+	Yade [5]: RC=O.bodies.getRoundness([]) # empty list [] is needed if no body should be excluded
+
+	Yade [3]: print RC
+	
+-> :yref:`getRoundness()<BodyContainer.getRoundness>` returns roundness coefficient RC of a packing or a part of the packing
+
+.. note:: Have a look at :ysrc:`examples/clumps/` folder. There you will find some examples, that show usage of different functions for clumps.
+
 
 Sphere packings
 ===============
@@ -246,7 +268,7 @@
 #. :yref:`yade.pack.gtsSurface2Facets` function can create the triangulated surface (from :yref:`Facet` particles) in the simulation itself, as shown in the funnel example. (Triangulated surface can also be imported directly from a STL file using :yref:`yade.ymport.stl`.)
 #. :yref:`yade._packPredicates.inGtsSurface` predicate can be created, using the surface as boundary representation of the enclosed volume.
 
-The :ysrc:`scripts/test/gts-horse.py` (img. img-horse_) shows both possibilities; first, a GTS surface is imported::
+The :ysrc:`scripts/gts-horse/gts-horse.py` (img. img-horse_) shows both possibilities; first, a GTS surface is imported::
 
 	import gts
 	surf=gts.read(open('horse.coarse.gts'))
@@ -265,7 +287,7 @@
 .. figure:: fig/horse.png
 	:width: 8cm
 
-	Imported GTS surface (horse) used as packing predicate (top) and surface constructed from :yref:`facets<yade.facet>` (bottom). See http://www.youtube.com/watch?v=PZVruIlUX1A for movie of this simulation.
+	Imported GTS surface (horse) used as packing predicate (top) and surface constructed from :yref:`facets<yade.utils.facet>` (bottom). See http://www.youtube.com/watch?v=PZVruIlUX1A for movie of this simulation.
 
 
 Boolean operations on predicates
@@ -295,7 +317,7 @@
 Algorithms presented below operate on geometric spheres, defined by their center and radius. With a few exception documented below, the procedure is as follows:
 
 #. Sphere positions and radii are computed (some functions use volume predicate for this, some do not)
-#. :yref:`yade.sphere` is called for each position and radius computed; it receives extra `keyword arguments <http://docs.python.org/glossary.html#term-keyword-argument>`_ of the packing function (i.e. arguments that the packing function doesn't specify in its definition; they are noted ``**kw``). Each :yref:`yade.sphere` call creates actual :yref:`Body` objects with :yref:`Sphere` :yref:`shape<Shape>`. List of :yref:`Body` objects is returned.
+#. :yref:`sphere<yade.utils.sphere>` is called for each position and radius computed; it receives extra `keyword arguments <http://docs.python.org/glossary.html#term-keyword-argument>`_ of the packing function (i.e. arguments that the packing function doesn't specify in its definition; they are noted ``**kw``). Each :yref:`sphere<yade.utils.sphere>` call creates actual :yref:`Body` objects with :yref:`Sphere` :yref:`shape<Shape>`. List of :yref:`Body` objects is returned.
 #. List returned from the packing function can be added to simulation using ``O.bodies.append``.
 
 Taking the example of pierced box::
@@ -303,7 +325,7 @@
 	pred=pack.inAlignedBox((-2,-2,-2),(2,2,2))-pack.inCylinder((0,-2,0),(0,2,0),1)
 	spheres=pack.randomDensePack(pred,spheresInCell=2000,radius=.1,rRelFuzz=.4,wire=True,color=(0,0,1),material=1)
 
-Keyword arguments ``wire``, ``color`` and ``material`` are not declared in :yref:`yade.pack.randomDensePack`, therefore will be passed to :yref:`yade.sphere`, where they are also documented. ``spheres`` is now list of :yref:`Body` objects, which we add to the simulation::
+Keyword arguments ``wire``, ``color`` and ``material`` are not declared in :yref:`yade.pack.randomDensePack`, therefore will be passed to :yref:`sphere<yade.utils.sphere>`, where they are also documented. ``spheres`` is now list of :yref:`Body` objects, which we add to the simulation::
 
 	O.bodies.append(spheres)
 
@@ -342,12 +364,10 @@
 """"""""""
 Random geometric algorithms do not integrate at all with volume predicates described above; rather, they take their own boundary/volume definition, which is used during sphere positioning. On the other hand, this makes it possible for them to respect boundary in the sense of making spheres touch it at appropriate places, rather than leaving empty space in-between.
 
-:yref:`yade._packSpherePadder.SpherePadder`
-	constructs dense sphere packing based on pre-computed tetrahedron mesh; it is documented in :yref:`yade._packSpherePadder.SpherePadder` documentation; sample script is in :ysrc:`scripts/test/SpherePadder.py`. :yref:`yade._packSpherePadder.SpherePadder` does not return :yref:`Body` list as other algorithms, but a :yref:`yade._packSpheres.SpherePack` object; it can be iterated over, adding spheres to the simulation, as shown in its documentation.
 GenGeo
 	is library (python module) for packing generation developed with `ESyS-Particle <http://www.launchpad.net/esys-particle>`_. It creates packing by random insertion of spheres with given radius range. Inserted spheres touch each other exactly and, more importantly, they also touch the boundary, if in its neighbourhood. Boundary is represented as special object of the GenGeo library (Sphere, cylinder, box, convex polyhedron, …). Therefore, GenGeo cannot be used with volume represented by yade predicates as explained above.
 
-	Packings generated by this module can be imported directly via :yref:`yade.ymport.gengeo`, or from saved file via :yref:`yade.ymport.gengeoFile`. There is an example script :ysrc:`scripts/test/genCylLSM.py`. Full documentation for GenGeo can be found at `ESyS documentation website <http://esys.esscc.uq.edu.au/docs.html>`_.
+	Packings generated by this module can be imported directly via :yref:`yade.ymport.gengeo`, or from saved file via :yref:`yade.ymport.gengeoFile`. There is an example script :ysrc:`examples/test/genCylLSM.py`. Full documentation for GenGeo can be found at `ESyS documentation website <http://esys.esscc.uq.edu.au/docs.html>`_.
 
 	To our knowledge, the GenGeo library is not currently packaged. It can be downloaded from current subversion repository ::
 
@@ -372,9 +392,9 @@
 Triangulated surfaces
 =====================
 
-Yade integrates with the the `GNU Triangulated Surface library <http://gts.sourceforge.net>`_, exposed in python via the 3rd party :yref:`external:gts` module. GTS provides variety of functions for surface manipulation (coarsening, tesselation, simplification, import), to be found in its documentation.
+Yade integrates with the the `GNU Triangulated Surface library <http://gts.sourceforge.net>`_, exposed in python via GTS module. GTS provides variety of functions for surface manipulation (coarsening, tesselation, simplification, import), to be found in its documentation.
 
-GTS surfaces are geometrical objects, which can be inserted into simulation as set of particles whose :yref:`Body.shape` is of type :yref:`Facet` -- single triangulation elements. :yref:`pack.gtsSurface2Facets` can be used to convert GTS surface triangulation into list of :yref:`bodies<Body>` ready to be inserted into simulation via ``O.bodies.append``.
+GTS surfaces are geometrical objects, which can be inserted into simulation as set of particles whose :yref:`Body.shape` is of type :yref:`Facet` -- single triangulation elements. :yref:`yade.pack.gtsSurface2Facets` can be used to convert GTS surface triangulation into list of :yref:`bodies<Body>` ready to be inserted into simulation via ``O.bodies.append``.
 
 Facet particles are created by default as non-:yref:`Body.dynamic` (they have zero inertial mass). That means that  they are fixed in space and will not move if subject to forces. You can however
 
@@ -402,7 +422,7 @@
 Parametric construction
 ------------------------
 
-The :yref:`external:gts` module provides convenient way of creating surface by vertices, edges and triangles.
+The GTS module provides convenient way of creating surface by vertices, edges and triangles.
 
 Frequently, though, the surface can be conveniently described as surface between polylines in space. For instance, cylinder is surface between two polygons (closed polylines). The :yref:`yade.pack.sweptPolylines2gtsSurface` offers the functionality of connecting several polylines with triangulation.
 
@@ -475,7 +495,7 @@
 Individual interactions on demand
 ----------------------------------
 
-It is possible to create an interaction between a pair of particles independently of collision detection using :yref:`yade.createInteraction`. This function looks for and uses matching ``Ig2`` and ``Ip2`` functors. Interaction will be created regardless of distance between given particles (by passing a special parameter to the ``Ig2`` functor to force creation of the interaction even without any geometrical contact). Appropriate constitutive law should be used to avoid deletion of the interaction at the next simulation step.
+It is possible to create an interaction between a pair of particles independently of collision detection using :yref:`createInteraction<yade.utils.createInteraction>`. This function looks for and uses matching ``Ig2`` and ``Ip2`` functors. Interaction will be created regardless of distance between given particles (by passing a special parameter to the ``Ig2`` functor to force creation of the interaction even without any geometrical contact). Appropriate constitutive law should be used to avoid deletion of the interaction at the next simulation step.
 
 .. ipython::
 
@@ -503,7 +523,7 @@
 	# created by functors in InteractionLoop
 	Yade [2]: i.geom, i.phys
 
-This method will be rather slow if many interaction are to be created (the functor lookup will be repeated for each of them). In such case, ask on yade-dev@xxxxxxxxxxxxxxxxxxx to have the :yref:`yade.createInteraction` function accept list of pairs id's as well.
+This method will be rather slow if many interaction are to be created (the functor lookup will be repeated for each of them). In such case, ask on yade-dev@xxxxxxxxxxxxxxxxxxx to have the :yref:`createInteraction<yade.utils.createInteraction>` function accept list of pairs id's as well.
 
 Base engines
 =============
@@ -659,7 +679,7 @@
 
 * :yref:`Body.dynamic` determines whether a body will be accelerated by :yref:`NewtonIntegrator`; it is mandatory to make it false for bodies with zero mass, where applying non-zero force would result in infinite displacement.
 
-  :yref:`Facets<Facet>` are case in the point: :yref:`yade.facet` makes them non-dynamic by default, as they have zero volume and zero mass (this can be changed, by passing ``dynamic=True`` to :yref:`yade.facet` or setting :yref:`Body.dynamic`; setting :yref:`State.mass` to a non-zero value must be done as well). The same is true for :yref:`yade.wall`.
+  :yref:`Facets<Facet>` are case in the point: :yref:`facet<yade.utils.facet>` makes them non-dynamic by default, as they have zero volume and zero mass (this can be changed, by passing ``dynamic=True`` to :yref:`facet<yade.utils.facet>` or setting :yref:`Body.dynamic`; setting :yref:`State.mass` to a non-zero value must be done as well). The same is true for :yref:`wall<yade.utils.wall>`.
 
   Making sphere non-dynamic is achieved simply by::
 
@@ -773,18 +793,18 @@
 Field appliers
 ---------------
 
-Engines deriving from :yref:`FieldApplier` acting on all particles. The one most used is :yref:`GravityEngine` applying uniform acceleration field.
+Engines deriving from :yref:`FieldApplier` acting on all particles. The one most used is :yref:`GravityEngine` applying uniform acceleration field (:yref:`GravityEngine` is deprecated, use :yref:`NewtonIntegrator.gravity` instead!).
 
 Partial engines
 ---------------
 
-Engines deriving from :yref:`PartialEngine` define the :yref:`ids<PartialEngine.subscribedBodies>` attribute determining bodies which will be affected. Several of them warrant explicit mention here:
+Engines deriving from :yref:`PartialEngine` define the :yref:`ids<PartialEngine.ids>` attribute determining bodies which will be affected. Several of them warrant explicit mention here:
 
 * :yref:`TranslationEngine` and :yref:`RotationEngine` for applying constant speed linear and rotational motion on subscribers. 
 * :yref:`ForceEngine` and :yref:`TorqueEngine` applying given values of force/torque on subscribed bodies at every step.
 * :yref:`StepDisplacer` for applying generalized displacement delta at every timestep; designed for precise control of motion when testing constitutive laws on 2 particles.
 
-The real value of partial engines is if you need to prescribe complex types of force or displacement fields. For moving a body at constant velocity or for imposing a single force, the methods explained in `Imposing motion and forces`_ are much simpler. There are several interpolating engines (:yref:`InterpolatingDirectedForceEngine` for applying force with varying magnitude, :yref:`InterpolatingSpiralEngine` for applying spiral displacement with varying angular velocity and possibly others); writing a new interpolating engine is rather simple using examples of those that already exist.
+The real value of partial engines is if you need to prescribe complex types of force or displacement fields. For moving a body at constant velocity or for imposing a single force, the methods explained in `Imposing motion and forces`_ are much simpler. There are several interpolating engines (:yref:`InterpolatingDirectedForceEngine` for applying force with varying magnitude, :yref:`InterpolatingHelixEngine` for applying spiral displacement with varying angular velocity and possibly others); writing a new interpolating engine is rather simple using examples of those that already exist.
 
 
 Convenience features
@@ -837,9 +857,9 @@
 Saving python variables
 ------------------------
 
-Python variable lifetime is limited; in particular, if you save simulation, variables will be lost after reloading. Yade provides limited support for data persistence for this reason (internally, it uses special values of ``O.tags``). The functions in question are :yref:`yade.saveVars` and :yref:`yade.loadVars`. 
+Python variable lifetime is limited; in particular, if you save simulation, variables will be lost after reloading. Yade provides limited support for data persistence for this reason (internally, it uses special values of ``O.tags``). The functions in question are :yref:`saveVars<yade.utils.saveVars>` and :yref:`loadVars<yade.utils.loadVars>`. 
 
-:yref:`yade.saveVars` takes dictionary (variable names and their values) and a *mark* (identification string for the variable set); it saves the dictionary inside the simulation. These variables can be re-created (after the simulation was loaded from a XML file, for instance) in the ``yade.params.``\ *mark* namespace by calling :yref:`yade.loadVars` with the same identification *mark*:
+:yref:`saveVars<yade.utils.saveVars>` takes dictionary (variable names and their values) and a *mark* (identification string for the variable set); it saves the dictionary inside the simulation. These variables can be re-created (after the simulation was loaded from a XML file, for instance) in the ``yade.params.``\ *mark* namespace by calling :yref:`loadVars<yade.utils.loadVars>` with the same identification *mark*:
 
 .. ipython::
 
@@ -882,7 +902,7 @@
 	from yade.params.geom import *
 	# use the variables now
 
-.. note:: Only types that can be `pickled <http://docs.python.org/library/pickle.html>`_ can be passed to :yref:`yade.saveVars`.
+.. note:: Only types that can be `pickled <http://docs.python.org/library/pickle.html>`_ can be passed to :yref:`saveVars<yade.utils.saveVars>`.
 
 
 
@@ -899,7 +919,7 @@
 
 A special engine :yref:`PyRunner` can be used to periodically call python code, specified via the ``command`` parameter. Periodicity can be controlled by specifying computation time (``realPeriod``), virutal time (``virtPeriod``) or iteration number (``iterPeriod``).
 
-For instance, to print kinetic energy (using :yref:`yade.kineticEnergy`) every 5 seconds, this engine will be put to ``O.engines``::
+For instance, to print kinetic energy (using :yref:`kineticEnergy<yade.utils.kineticEnergy>`) every 5 seconds, this engine will be put to ``O.engines``::
 	PyRunner(command="print 'kinetic energy',kineticEnergy()",realPeriod=5)
 
 For running more complex commands, it is convenient to define an external function and only call it from within the engine. Since the ``command`` is run in the script's namespace, functions defined within scripts can be called. Let us print information on interaction between bodies 0 and 1 periodically::
@@ -975,9 +995,9 @@
 		UniaxialStrainer(...,label='strainer')
 	]
 	def myAddData():
-		plot.addData(sigma=strainer.stress,eps=strainer.strain)
+		plot.addData(sigma=strainer.avgStress,eps=strainer.strain)
 
-In that case, naturally, the labeled object must define attributes which are used (:yref:`UniaxialStrainer.strain` and :yref:`UniaxialStrainer.stress` in this case).
+In that case, naturally, the labeled object must define attributes which are used (:yref:`UniaxialStrainer.strain` and :yref:`UniaxialStrainer.avgStress` in this case).
 
 Plotting variables
 -------------------
@@ -1118,7 +1138,7 @@
 
 Frequently, decisions have to be made based on evolution of the simulation itself, which is not yet known. In such case, a function checking some specific condition is called periodically; if the condition is satisfied, ``O.pause`` or other functions can be called to stop the stimulation. See documentation for :yref:`Omega.run`, :yref:`Omega.pause`, :yref:`Omega.step`, :yref:`Omega.stopAtIter` for details.
 
-For simulations that seek static equilibrium, the :yref:`yade._unbalancedForce` can provide a useful metrics (see its documentation for details); for a desired value of ``1e-2`` or less, for instance, we can use::
+For simulations that seek static equilibrium, the :yref:`unbalancedForce<yade.utils.unbalancedForce>` can provide a useful metrics (see its documentation for details); for a desired value of ``1e-2`` or less, for instance, we can use::
 
 	
 	def checkUnbalanced():
@@ -1235,7 +1255,7 @@
 -------------
 ``TCP Info provider`` listens at port 21000 (or higher) and returns some basic information about current simulation upon connection; the connection terminates immediately afterwards. The information is python dictionary represented as string (serialized) using standard `pickle <http://docs.python.org/library/pickle.html>`_ module.
 
-This functionality is used by the batch system (described below) to be informed about individual simulation progress and estimated times. If you want to access this information yourself, you can study :ysrc:`core/main/yade-multi.in` for details.
+This functionality is used by the batch system (described below) to be informed about individual simulation progress and estimated times. If you want to access this information yourself, you can study :ysrc:`core/main/yade-batch.in` for details.
 
 Batch queuing and execution (yade-batch)
 ========================================
@@ -1243,12 +1263,12 @@
 Yade features light-weight system for running one simulation with different parameters; it handles assignment of parameter values to python variables in simulation script, scheduling jobs based on number of available and required cores and more. The whole batch consists of 2 files:
 
 simulation script
-	regular Yade script, which calls :yref:`yade.readParamsFromTable` to obtain parameters from parameter table. In order to make the script runnable outside the batch, :yref:`yade.readParamsFromTable` takes default values of parameters, which might be overridden from the parameter table.
+	regular Yade script, which calls :yref:`readParamsFromTable<yade.utils.readParamsFromTable>` to obtain parameters from parameter table. In order to make the script runnable outside the batch, :yref:`readParamsFromTable<yade.utils.readParamsFromTable>` takes default values of parameters, which might be overridden from the parameter table.
 	
-	:yref:`yade.readParamsFromTable` knows which parameter file and which line to read by inspecting the ``PARAM_TABLE`` environment variable, set by the batch system.
+	:yref:`readParamsFromTable<yade.utils.readParamsFromTable>` knows which parameter file and which line to read by inspecting the ``PARAM_TABLE`` environment variable, set by the batch system.
 
 parameter table
-	simple text file, each line representing one parameter set. This file is read by :yref:`yade.readParamsFromTable` (using :yref:`yade.TableParamReader` class), called from simulation script, as explained above. For better reading of the text file you can make use of tabulators, these will be ignored by :yref:`yade.readParamsFromTable`. Parameters are not restricted to numerical values. You can also make use of strings by "quoting" them ('  ' may also be used instead of "  "). This can be useful for nominal parameters.
+	simple text file, each line representing one parameter set. This file is read by :yref:`readParamsFromTable<yade.utils.readParamsFromTable>` (using :yref:`TableParamReader<yade.utils.TableParamReader>` class), called from simulation script, as explained above. For better reading of the text file you can make use of tabulators, these will be ignored by :yref:`readParamsFromTable<yade.utils.readParamsFromTable>`. Parameters are not restricted to numerical values. You can also make use of strings by "quoting" them ('  ' may also be used instead of "  "). This can be useful for nominal parameters.
 
 The batch can be run as ::
 
@@ -1288,7 +1308,7 @@
 	from yade.params.table import *
 	print gravity, density, initialVelocity
 
-after the call to :yref:`yade.readParamsFromTable`, corresponding python variables are created in the ``yade.params.table`` module and can be readily used in the script, e.g.
+after the call to :yref:`readParamsFromTable<yade.utils.readParamsFromTable>`, corresponding python variables are created in the ``yade.params.table`` module and can be readily used in the script, e.g.
 
 .. code-block:: python
 
@@ -1423,14 +1443,14 @@
 
 #. Capture screen output (the 3d rendering window) during the simulation − there are tools available for that (such as `Istanbul <http://live.gnome.org/Istanbul>`_ or `RecordMyDesktop <http://recordmydesktop.sourceforge.net/about.php>`_, which are also packaged for most Linux distributions).  The output is "what you see is what you get", with all the advantages and disadvantages.
 
-#. Periodic frame snapshot using :yref:`SnapshotEngine` (see :ysrc:`examples/bulldozer.py` for a full example)::
+#. Periodic frame snapshot using :yref:`SnapshotEngine` (see :ysrc:`examples/bulldozer/bulldozer.py` for a full example)::
    
       O.engines=[
       	#...
       	SnapshotEngine(iterPeriod=100,fileBase='/tmp/bulldozer-',viewNo=0,label='snapshooter')
       ]
 
-   which will save numbered files like ``/tmp/bulldozer-0000.png``. These files can be processed externally (with `mencoder <http://www.mplayerhq.hu>`_ and similar tools) or directly with the :yref:`yade.makeVideo`::
+   which will save numbered files like ``/tmp/bulldozer-0000.png``. These files can be processed externally (with `mencoder <http://www.mplayerhq.hu>`_ and similar tools) or directly with the :yref:`makeVideo<yade.utils.makeVideo>`::
 
       makeVideo(frameSpec,out,renameNotOverwrite=True,fps=24,kbps=6000,bps=None)
    
@@ -1453,10 +1473,7 @@
 
 * :yref:`iterPeriod<PeriodicEngine.iterPeriod>` determines how often to save simulation data (besides :yref:`iterPeriod<PeriodicEngine.iterPeriod>`, you can also use :yref:`virtPeriod<PeriodicEngine.virtPeriod>` or :yref:`realPeriod<PeriodicEngine.realPeriod>`). If the period is too high (and data are saved only few times), the video will have few frames. 
 * :yref:`fileName<VTKRecorder.fileName>` is the prefix for files being saved. In this case, output files will be named ``/tmp/p1-spheres.0.vtu`` and ``/tmp/p1-facets.0.vtu``, where the number is the number of iteration; many files are created, putting them in a separate directory is advisable.
-* :yref:`recorders<VTKRecorder.recorders>` determines what data to save (see the :yref:`documentation<VTKRecorder.recorders>`)
-
-:yref:`VTKExporter` plays a similar role, with the difference that it is more flexible. It will save any user defined variable associated to the bodies. 
-
+* :yref:`recorders<VTKRecorder.recorders>` determines what data to save
 
 Loading data into Paraview
 ^^^^^^^^^^^^^^^^^^^^^^^^^^
@@ -1538,7 +1555,7 @@
 
 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:
+Stress fields can be generated by combining the volume returned by TesselationWrapper to per-particle stress given by :yref:`bodyStressTensors<yade.utils.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
 
@@ -1548,7 +1565,7 @@
 	s=bodyStressTensors()
 	stress = s[b.id]**4.*pi/3.*b.shape.radius**3/TW.volume(b.id)
 
-As any other value, the stress can be exported to a vtk file for display in Paraview using :yref:`VTKExporter`.
+As any other value, the stress can be exported to a vtk file for display in Paraview using :yref:`VTKRecorder`.
 
 ******************************
 Python specialties and tricks

=== modified file 'examples/clumps/apply-buoyancy-clumps.py'
--- examples/clumps/apply-buoyancy-clumps.py	2013-06-24 13:23:34 +0000
+++ examples/clumps/apply-buoyancy-clumps.py	2013-10-04 08:11:01 +0000
@@ -4,19 +4,18 @@
 '''	The script shows how to include the effect of buoyancy in a particle assembly 
 	under condition of an increasing water-level. Water-level at start of the sim-
 	ulation is at the lower boundary of the model. During the calculation particles
-	gets partly surrounded by water and buoyancy (=density*volumeOfDisplacedWater)
+	get partly surrounded by water and buoyancy (=fluidDensity*volumeOfDisplacedWater)
 	is increasing until particle is completely surrounded. When particle is sur-
 	rounded volumeOfDisplacedWater is equal to the volume of the particle.
 	
-	For calculation of buoyancy of a clump the theoretical radius 
-	R = (3*mass/(4*pi*density))^1/3 
+	For calculation of buoyancy of a clump the equivalent radius 
+	R = (3*clumpMass/(4*pi*particleDensity))^1/3 
 	of a sphere with clump mass and clump volume 
-	V = (4*pi*R^3)/3 = mass/density
+	V = (4*pi*R^3)/3 = clumpMass/particleDensity
 	is used. This approximation can be used for well rounded clumps.
 	
-	Buoyancy is included via reduced mass (=massAtStart - dm), where dm is the 
-	buoyancy. Reduced mass must be corrected via density scaling for calculation
-	of correct particle accelerations.'''
+	Buoyancy is included with an additional force 
+	F_buo = -volumeOfDisplacedWater*fluidDensity*gravityAcceleration.'''
 
 #define material properties:
 shear_modulus			= 3.2e10
@@ -24,6 +23,7 @@
 young_modulus			= 2*shear_modulus*(1+poisson_ratio)
 angle					= 0.5	#friction angle in radians
 rho_p					= 2650	#density of particles
+rho_f					= 5000	#density of the fluid			rho_f > rho_p = floating particles
 
 v_iw					= 1  #velocity of increasing water-level
 
@@ -31,6 +31,12 @@
 boundaryMin = Vector3(-1.5,-1.5,0)
 boundaryMax = Vector3(1.5,1.5,2)
 
+#define colors:
+sphereColor = (.8,.8,0.)#dirty yellow
+clumpColor	= (1.,.55,0.)#dark orange
+boxColor	= (.1,.5,.1)#green
+waterColor	= (.2,.2,.7)#blue
+
 #material:
 id_Mat=O.materials.append(FrictMat(young=young_modulus,poisson=poisson_ratio,density=rho_p,frictionAngle=angle))
 Mat=O.materials[id_Mat]
@@ -38,14 +44,18 @@
 #create assembly of spheres:
 sp=pack.SpherePack()
 sp.makeCloud(minCorner=boundaryMin,maxCorner=boundaryMax,rMean=.2,rRelFuzz=.5,num=100,periodic=False)
-O.bodies.append([sphere(c,r,material=Mat) for c,r in sp])
+O.bodies.append([sphere(c,r,material=Mat,color=sphereColor) for c,r in sp])
 
 #create template for clumps and replace 10% of spheres by clumps:
 templateList = [clumpTemplate(relRadii=[1,.5],relPositions=[[0,0,0],[.7,0,0]])]
 O.bodies.replaceByClumps(templateList,[.1])
+#color clumps:
+for b in O.bodies:
+	if b.isClumpMember:
+		b.shape.color=clumpColor
 
 #create boundary:
-O.bodies.append(facetBox((0,0,1), (boundaryMax-boundaryMin)/2, fixed=True, material=Mat))#boundaryMax-boundaryMin
+O.bodies.append(facetBox((0,0,1), (boundaryMax-boundaryMin)/2, fixed=True, material=Mat, color=boxColor))#boundaryMax-boundaryMin
 
 #define engines:
 O.engines=[
@@ -62,7 +72,7 @@
 ts.dead=True
 
 #definition to apply buoyancy:
-def apply_buo(water_height,saturatedList,startMass):
+def apply_buo(water_height,saturatedList):
 	for b in O.bodies:
 		if b not in saturatedList:
 			h_low = 1e9
@@ -78,18 +88,25 @@
 					pos = O.bodies[keys[ii]].state.pos
 					h_low = min(h_low,pos[2]-O.bodies[keys[ii]].shape.radius)
 					h_high = max(h_high,pos[2]+O.bodies[keys[ii]].shape.radius)
-				rad = ( 3*startMass[b.id]/(4*pi*O.bodies[keys[0]].mat.density) )**(1./3.)		#get radius from startMass
+				rad = ( 3*b.state.mass/(4*pi*O.bodies[keys[0]].mat.density) )**(1./3.)		#get equivalent radius from clump mass
 			else:
 				continue
 			if water_height > h_low:
 				dh = water_height - h_low
 				dh = min(dh,2*rad)	#to get sure, that dh is not bigger than 2*radius
-				dm = (pi/3)*dh*dh*(3*rad - dh)*1000		#buoyancy acts via reduced mass dm=rho*V_cap
-				b.state.mass = startMass[b.id] - dm		#needs a list of masses of all particles at start (see 5-final.py)
-				#reduced mass must be corrected via density scaling for accelerations a = F/m_reduced, a_correct = a*densityScaling, see line 179 in pkg/dem/NewtonIntegrator.cpp:
-				b.state.densityScaling = (startMass[b.id] - dm)/startMass[b.id]
+				F_buo = -1*(pi/3)*dh*dh*(3*rad - dh)*rho_f*integrator.gravity										# = -V*rho*g
+				#apply buoyancy force (will overwrite old forces applied with addF command)
+				if b.isStandalone and isinstance(b.shape,Sphere):
+					O.forces.addF(b.id,F_buo,permanent=True)
+				if b.isClump:
+					keys = O.bodies[b.id].shape.members.keys()
+					for ii in range(0,len(keys)):
+						O.forces.addF(keys[ii],(O.bodies[keys[ii]].state.mass/b.state.mass)*F_buo,permanent=True)	# F_buo_clumpmember = massPortion*F_buo_clump
 				if water_height > h_high:
 					saturatedList.append(b)
+		else:
+			if water_height < h_high:
+				saturatedList.remove(b)	#remove "hoppers" from saturatedList
 	return saturatedList
 
 #STEP1: reduce overlaps from replaceByClumps() method:
@@ -99,47 +116,35 @@
 O.run(1000000,True)
 calmRunner.dead=True
 
-#STEP2: let particles settle down:
+#STEP2: let particles settle down
 O.dt=1e-5
 print '\nSTEP2 in progress. Please wait a minute ...\n'
 O.run(50000,True)
 
-#get maximum body id:
-idmax=0
-for b in O.bodies:
-	idmax=max(idmax,b.id)
-integrator.densityScaling=True	#activate density scaling
-
-#get a list of masses at start:
-startMass = [0 for ii in range(0,idmax+1)]
-for b in O.bodies:
-	if (b.isStandalone and isinstance(b.shape,Sphere)) or b.isClump:
-		startMass[b.id] = b.state.mass
-
 #start PyRunner engine to apply buoyancy:
 saturatedList = []
 t0 = O.time
-O.engines=O.engines+[PyRunner(iterPeriod=100,command='saturatedList=apply_buo(((O.time-t0) * v_iw),saturatedList,startMass)',label='buoLabel')]
+O.engines=O.engines+[PyRunner(iterPeriod=100,command='saturatedList=apply_buo(((O.time-t0) * v_iw),saturatedList)',label='buoLabel')]
 
 #create 2 facets, that show water height:
 idsWaterFacets =  []
 idsWaterFacets.append(O.bodies.append(facet( \
 			[ boundaryMin, [boundaryMax[0],boundaryMin[1],boundaryMin[2]], [boundaryMax[0],boundaryMax[1],boundaryMin[2]] ], \
-			fixed=True,material=FrictMat(young=0),color=(0,0,1),wire=False)))#no interactions will appear
+			fixed=True,material=FrictMat(young=0),color=waterColor,wire=False)))#no interactions will appear
 idsWaterFacets.append(O.bodies.append(facet( \
 			[ [boundaryMax[0],boundaryMax[1],boundaryMin[2]], [boundaryMin[0],boundaryMax[1],boundaryMin[2]], boundaryMin ], \
-			fixed=True,material=FrictMat(young=0),color=(0,0,1),wire=False)))#no interactions will appear
+			fixed=True,material=FrictMat(young=0),color=waterColor,wire=False)))#no interactions will appear
 
 #set velocity of incr. water level to the facets:
 for ids in idsWaterFacets:
 	O.bodies[ids].state.vel = [0,0,v_iw]
 
-#STEP3: simulate buoyancy#
+#STEP3: simulate buoyancy with increasing water table condition
 O.dt=3e-5
 from yade import qt
 qt.Controller()
 v=qt.View()
 v.eyePosition=(-7,0,2); v.upVector=(0,0,1); v.viewDir=(1,0,-.1); v.axes=True; v.sceneRadius=1.9
 print '\nSTEP3 started ...\n'
-O.run(60000)
+O.run(70000)
 

=== modified file 'examples/jointedCohesiveFrictionalPM/README'
--- examples/jointedCohesiveFrictionalPM/README	2013-08-01 11:54:13 +0000
+++ examples/jointedCohesiveFrictionalPM/README	2013-10-04 09:47:21 +0000
@@ -11,3 +11,6 @@
 2-identificationSpheresOnJoint.py is a script used to identify the spheres belonging to a predefined packing (parallellepiped_10.spheres) interacting along pre-existing discontinuity surfaces defined by a meshed surface (persistentPlane30Deg.stl). Executing this script produces 2 text files containing respectively spheres from packing (parallellepiped_10_persistentPlane30Deg.spheres) and spheres attributes regarding jcfPM variables (parallellepiped_10_persistentPlane30Deg_jointedPM.spheres). 
 
 3-gravityLoading.py is a simple example showing how to use Law2_ScGeom_JCFpmPhys_JointedCohesiveFrictionalPM. It simulates the loading of a pre-fractured packing (parallellepiped_10_persistentPlane30Deg.spheres) by gravity to emphasize how the pre-existing discontinuity affects the behavior. User can play along with joint surface properties (smooth contact logic or not, joint friction angle,...) to see the effect on the simulated behavior.
+
+
+A more compact way of use is proposed in gravityBis.py. This script is stand-alone, and calls itself the scrit identifBis.py. This later script can be called from any script in JCFpm modelling to detect spheres that should interact according to smooth contact logic.
\ No newline at end of file

=== added file 'examples/jointedCohesiveFrictionalPM/gravityBis.py'
--- examples/jointedCohesiveFrictionalPM/gravityBis.py	1970-01-01 00:00:00 +0000
+++ examples/jointedCohesiveFrictionalPM/gravityBis.py	2013-10-04 09:47:21 +0000
@@ -0,0 +1,125 @@
+# encoding: utf-8
+
+# example of use JCFpm classes : Law2_ScGeom_JCFpmPhys_JointedCohesiveFrictionalPM...
+# a cubic rock massif, containing a rock joint with ~ 31 deg. dip angle. At one time, the mechanical properties of the joint are degraded, triggering a smooth sliding
+
+
+# definition of a predicate for use of randomDensePack() function
+
+from yade import pack
+dimModele = 10.0
+pred = pack.inAlignedBox((0,0,0),(dimModele,dimModele,dimModele))
+
+# the packing of spheres :
+
+def mat(): return JCFpmMat(type=1,young=1e8,frictionAngle=radians(30),density=3000)
+nSpheres = 3000.0
+poros=0.13
+rMeanSpheres = dimModele * pow(3.0/4.0*(1-poros)/(pi*nSpheres),1.0/3.0)
+print ''
+print 'Creating a cubic sample of spheres (may take some time)'
+print ''
+sp = pack.randomDensePack(pred,radius=rMeanSpheres,rRelFuzz=0.3,memoizeDb='/tmp/gts-triax-packings.sqlite',returnSpherePack=True)
+sp.toSimulation(color=(0.9,0.8,0.6),wire=False,material=mat)
+
+# Definition of the facets for joint's geometry
+
+import gts
+# joint with ~ 31 deg. dip angle
+v1 = gts.Vertex(0 , 0 , 0.8*dimModele)
+v2 = gts.Vertex(0 , dimModele , 0.8*dimModele )
+v3 = gts.Vertex(dimModele , dimModele , 0.2*dimModele)
+v4 = gts.Vertex(dimModele , 0 , 0.2*dimModele)
+
+e1 = gts.Edge(v1,v2)
+e2 = gts.Edge(v2,v4)
+e3 = gts.Edge(v4,v1)
+f1 = gts.Face(e1,e2,e3)
+
+e4 = gts.Edge(v4,v3)
+e5 = gts.Edge(v3,v2)
+f2 = gts.Face(e2,e4,e5)
+
+s1 = gts.Surface()
+s1.add(f1)
+s1.add(f2)
+
+facet = gtsSurface2Facets(s1,wire = False,material=mat)
+O.bodies.append(facet)
+
+yade.qt.View()
+yade.qt.Controller()
+
+O.saveTmp()
+# identification of spheres onJoint, and so on:
+execfile('identifBis.py')
+dim=utils.aabbExtrema()
+xsup=dim[1][0]
+yinf=dim[0][1]
+ysup=dim[1][1]
+zinf=dim[0][2]
+zsup=dim[1][2]
+
+e=2*rMeanSpheres
+
+for o in O.bodies:
+   if isinstance(o.shape,Sphere):
+      o.shape.color=(0.9,0.8,0.6)
+      ## to fix boundary particles on ground
+      if o.state.pos[2]<(zinf+2*e) :
+	 o.state.blockedDOFs+='xyz'
+	 o.shape.color=(1,1,1)
+
+      ## to identify indicator on top
+      if o.state.pos[2]>(zsup-e) and o.state.pos[0]>(xsup-e) and o.state.pos[1]>((yinf+ysup-e)/2.0) and o.state.pos[1]<((yinf+ysup+e)/2) : 
+	refPoint=o.id
+	p0=o.state.pos[2] # its initial position
+
+O.bodies[refPoint].shape.highlight=True
+
+#### Engines definition
+interactionRadius=1. # to set initial contacts to larger neighbours
+O.engines=[
+	ForceResetter(),
+	InsertionSortCollider([Bo1_Sphere_Aabb(aabbEnlargeFactor=interactionRadius),]),
+	InteractionLoop(
+		[Ig2_Sphere_Sphere_ScGeom(interactionDetectionFactor=interactionRadius)],
+		[Ip2_JCFpmMat_JCFpmMat_JCFpmPhys(cohesiveTresholdIteration=1,alpha=0.3,tensileStrength=1e6,cohesion=1e6,jointNormalStiffness=1e7,jointShearStiffness=1e7,jointCohesion=1e6,jointFrictionAngle=radians(20),jointDilationAngle=0.0)],
+		[Law2_ScGeom_JCFpmPhys_JointedCohesiveFrictionalPM(smoothJoint=True)]
+	),
+	GlobalStiffnessTimeStepper(timestepSafetyCoefficient=0.8),
+	PyRunner(iterPeriod=1000,initRun=False,command='jointStrengthDegradation()'),
+	PyRunner(iterPeriod=10,initRun=True,command='dataCollector()'),
+	NewtonIntegrator(damping=0.7,gravity=(0.,0.,-10.)),
+
+]
+
+#### dataCollector
+from yade import plot
+plot.plots={'iterations':('v',)}
+def dataCollector():
+	R=O.bodies[refPoint]
+	plot.addData(v=R.state.vel[2],p=R.state.pos[2]-p0,iterations=O.iter,t=O.realtime)
+
+#### joint strength degradation
+stableIter=2000
+stableVel=0.001
+degrade=True
+def jointStrengthDegradation():
+    global degrade
+    if degrade and O.iter>=stableIter and abs(O.bodies[refPoint].state.vel[1])<stableVel :
+	print '!joint cohesion total degradation!', ' | iteration=', O.iter
+	degrade=False
+	for i in O.interactions:
+	    if i.phys.isOnJoint : 
+		if i.phys.isCohesive:
+		  i.phys.isCohesive=False
+		  i.phys.FnMax=0.
+		  i.phys.FsMax=0.
+
+O.step()
+print ''
+print 'Seeking first after an initial equilibrium state'
+print ''
+O.run(10000)
+plot.plot()

=== added file 'examples/jointedCohesiveFrictionalPM/identifBis.py'
--- examples/jointedCohesiveFrictionalPM/identifBis.py	1970-01-01 00:00:00 +0000
+++ examples/jointedCohesiveFrictionalPM/identifBis.py	2013-10-04 09:47:21 +0000
@@ -0,0 +1,161 @@
+# -*- coding: utf-8 -*-
+
+# ---- Script to detect spheres which are "onJoint", according to JCFpm. -----
+# To be called directly within an other script, for example, with execfile('identifBis.py')
+# The sample (spheres + facets) has to exist already, with their JCFpmMat
+
+
+############################ engines definition
+interactionRadius=1.;
+O.engines=[
+
+	ForceResetter(),
+	InsertionSortCollider([Bo1_Sphere_Aabb(aabbEnlargeFactor=interactionRadius,label='is2aabb'),Bo1_Facet_Aabb()]),
+	InteractionLoop(
+		[Ig2_Sphere_Sphere_ScGeom(interactionDetectionFactor=interactionRadius,label='ss2d3dg'),Ig2_Facet_Sphere_ScGeom()],
+		[Ip2_JCFpmMat_JCFpmMat_JCFpmPhys(cohesiveTresholdIteration=1,alpha=1,tensileStrength=1e6,cohesion=1e6,jointNormalStiffness=1,jointShearStiffness=1,jointTensileStrength=1e6,jointCohesion=1e6,jointFrictionAngle=1,label='interactionPhys')],
+		[Law2_ScGeom_JCFpmPhys_JointedCohesiveFrictionalPM(smoothJoint=True,label='interactionLaw')]
+	),
+	NewtonIntegrator(damping=1)
+
+]
+
+############################ timestep + opening yade windows
+O.dt=0.001*utils.PWaveTimeStep()
+
+# from yade import qt
+# v=qt.Controller()
+# v=qt.View()
+
+############################ Identification spheres on joint
+#### color set for particles on joint
+jointcolor1=(0,1,0)
+jointcolor2=(1,0,0)
+jointcolor3=(0,0,1)
+jointcolor4=(1,1,1)
+jointcolor5=(0,0,0)
+
+#### first step-> find spheres on facet
+O.step();
+
+for i in O.interactions:
+    ##if not i.isReal : continue
+    ### Rk: facet are only stored in id1 
+    if isinstance(O.bodies[i.id1].shape,Facet) and isinstance(O.bodies[i.id2].shape,Sphere): 
+	vertices=O.bodies[i.id1].shape.vertices
+	normalRef=vertices[0].cross(vertices[1]) # defines the normal to the facet normalRef
+	nRef=normalRef/(normalRef.norm()) ## normalizes normalRef
+	normalFacetSphere=i.geom.normal # geom.normal is oriented from id1 to id2 -> normalFacetSphere from facet (i.id1) to sphere (i.id2)
+
+	if O.bodies[i.id2].mat.onJoint==False : ## particles has not yet been identified as belonging to a joint plane
+	    O.bodies[i.id2].mat.onJoint=True
+	    O.bodies[i.id2].mat.joint=1
+	    O.bodies[i.id2].shape.color=jointcolor1
+	    if nRef.dot(normalFacetSphere)>=0 :
+		O.bodies[i.id2].mat.jointNormal1=nRef
+	    elif nRef.dot(normalFacetSphere)<0 :
+		O.bodies[i.id2].mat.jointNormal1=-nRef
+	elif O.bodies[i.id2].mat.onJoint==True :  ## particles has already been identified as belonging to, at least, 1 facet
+	    if O.bodies[i.id2].mat.joint==1 and ((O.bodies[i.id2].mat.jointNormal1.cross(nRef)).norm()>0.05) : ## particles has already been identified as belonging to only 1 facet
+		O.bodies[i.id2].mat.joint=2
+		O.bodies[i.id2].shape.color=jointcolor2
+		if nRef.dot(normalFacetSphere)>=0 :
+		    O.bodies[i.id2].mat.jointNormal2=nRef
+		elif nRef.dot(normalFacetSphere)<0 :
+		    O.bodies[i.id2].mat.jointNormal2=-nRef
+	    elif O.bodies[i.id2].mat.joint==2 and ((O.bodies[i.id2].mat.jointNormal1.cross(nRef)).norm()>0.05) and ((O.bodies[i.id2].mat.jointNormal2.cross(nRef)).norm()>0.05): ## particles has already been identified as belonging to more than 1 facet
+		O.bodies[i.id2].mat.joint=3
+		O.bodies[i.id2].shape.color=jointcolor3
+		if nRef.dot(normalFacetSphere)>=0 :
+		    O.bodies[i.id2].mat.jointNormal3=nRef
+		elif nRef.dot(normalFacetSphere)<0 :
+		    O.bodies[i.id2].mat.jointNormal3=-nRef
+	    elif O.bodies[i.id2].mat.joint==3 and ((O.bodies[i.id2].mat.jointNormal1.cross(nRef)).norm()>0.05) and ((O.bodies[i.id2].mat.jointNormal2.cross(nRef)).norm()>0.05) and ((O.bodies[i.id2].mat.jointNormal3.cross(nRef)).norm()>0.05):
+		O.bodies[i.id2].mat.joint=4
+		O.bodies[i.id2].shape.color=jointcolor5
+
+#### second step -> find spheres interacting with spheres on facet (could be executed in the same timestep as step 1?)
+for j in O.interactions:
+    #if not i.isReal : continue
+    ## Rk: facet are only stored in id1 
+    if isinstance(O.bodies[j.id1].shape,Facet) and isinstance(O.bodies[j.id2].shape,Sphere): 
+	vertices=O.bodies[j.id1].shape.vertices
+	normalRef=vertices[0].cross(vertices[1]) # defines the normal to the facet normalRef
+	nRef=normalRef/(normalRef.norm()) ## normalizes normalRef
+	if ((O.bodies[j.id2].mat.jointNormal1.cross(nRef)).norm()<0.05) :
+	    jointNormalRef=O.bodies[j.id2].mat.jointNormal1
+	elif ((O.bodies[j.id2].mat.jointNormal2.cross(nRef)).norm()<0.05) :
+	    jointNormalRef=O.bodies[j.id2].mat.jointNormal2
+	elif ((O.bodies[j.id2].mat.jointNormal3.cross(nRef)).norm()<0.05) :
+	    jointNormalRef=O.bodies[j.id2].mat.jointNormal3
+	else : continue
+	facetCenter=O.bodies[j.id1].state.pos
+	#### seek for each sphere interacting with the identified sphere j.id2
+	for n in O.interactions.withBody(j.id2) :
+            if isinstance(O.bodies[n.id1].shape,Sphere) and isinstance(O.bodies[n.id2].shape,Sphere):
+                if j.id2==n.id1: # the sphere that was detected on facet (that is, j.id2) is id1 of interaction n
+                    sphOnF=n.id1
+                    othSph=n.id2
+                elif j.id2==n.id2: # here, this sphere that was detected on facet (that is, j.id2) is id2 of interaction n
+                    sphOnF=n.id2
+                    othSph=n.id1
+		facetSphereDir=(O.bodies[othSph].state.pos-facetCenter)
+		if O.bodies[othSph].mat.onJoint==True :
+		    if O.bodies[othSph].mat.joint==3 and ((O.bodies[othSph].mat.jointNormal1.cross(jointNormalRef)).norm()>0.05) and ((O.bodies[othSph].mat.jointNormal2.cross(jointNormalRef)).norm()>0.05) and ((O.bodies[othSph].mat.jointNormal3.cross(jointNormalRef)).norm()>0.05):
+			O.bodies[othSph].mat.joint=4
+			O.bodies[othSph].shape.color=jointcolor5
+		    elif O.bodies[othSph].mat.joint==2 and ((O.bodies[othSph].mat.jointNormal1.cross(jointNormalRef)).norm()>0.05) and ((O.bodies[othSph].mat.jointNormal2.cross(jointNormalRef)).norm()>0.05):
+			O.bodies[othSph].mat.joint=3
+			if facetSphereDir.dot(jointNormalRef)>=0:
+			    O.bodies[othSph].mat.jointNormal3=jointNormalRef
+			elif facetSphereDir.dot(jointNormalRef)<0:
+			    O.bodies[othSph].mat.jointNormal3=-jointNormalRef 
+		    elif O.bodies[othSph].mat.joint==1 and ((O.bodies[othSph].mat.jointNormal1.cross(jointNormalRef)).norm()>0.05) :
+			O.bodies[othSph].mat.joint=2
+			if facetSphereDir.dot(jointNormalRef)>=0:
+			    O.bodies[othSph].mat.jointNormal2=jointNormalRef
+			elif facetSphereDir.dot(jointNormalRef)<0:
+			    O.bodies[othSph].mat.jointNormal2=-jointNormalRef
+		elif  O.bodies[othSph].mat.onJoint==False :
+		    O.bodies[othSph].mat.onJoint=True
+		    O.bodies[othSph].mat.joint=1
+		    O.bodies[othSph].shape.color=jointcolor4
+		    if facetSphereDir.dot(jointNormalRef)>=0:
+			O.bodies[othSph].mat.jointNormal1=jointNormalRef
+		    elif facetSphereDir.dot(jointNormalRef)<0:
+			O.bodies[othSph].mat.jointNormal1=-jointNormalRef
+
+#### for visualization:
+#bj=0
+#vert=(0.,1.,0.)
+#hor=(0.,1.,1.)
+#for o in O.bodies:
+    #if o.mat.onJoint==True : # or o.shape.name=='Facet':
+	##if  o.shape.name=='Facet':
+	    ##o.shape.wire=True
+	##o.state.pos+=(0,50,0)
+	##bj+=1
+	#if o.mat.jointNormal1.dot(hor)>0 :
+	    ##o.state.pos+=(0,50,0)
+	    #o.shape.color=jointcolor1
+	#elif o.mat.jointNormal1.dot(hor)<0 :
+	    ##o.state.pos+=(0,55,0)
+	    #o.shape.color=jointcolor2
+	#if o.mat.type>2 :
+	    #bj+=1
+	    #o.shape.color=jointcolor5
+	    ##print o.mat.jointNormal.dot(vert)
+
+
+##### to delete facets (should be OK to start the simulation after that!
+for b in O.bodies:
+    if isinstance(b.shape,Facet):
+	O.bodies.erase(b.id)
+
+O.resetTime()
+O.interactions.clear()
+print ''
+print 'IdentificationSpheresOnJoint executed ! Spheres onJoint (and so on...) detected, facets deleted'
+print ''
+
+

=== modified file 'examples/jointedCohesiveFrictionalPM/identificationSpheresOnJoint.py'
--- examples/jointedCohesiveFrictionalPM/identificationSpheresOnJoint.py	2013-08-01 11:54:13 +0000
+++ examples/jointedCohesiveFrictionalPM/identificationSpheresOnJoint.py	2013-10-04 09:43:53 +0000
@@ -123,7 +123,7 @@
 	    jointNormalRef=O.bodies[j.id2].mat.jointNormal3
 	else : continue
 	facetCenter=O.bodies[j.id1].state.pos
-	#### seek for each sphere interacting with the identified sphere i.id2
+	#### seek for each sphere interacting with the identified sphere j.id2
 	for n in O.interactions.withBody(j.id2) :
 	    if n.id1==j.id2 and isinstance(O.bodies[n.id2].shape,Sphere): 
 		facetSphereDir=(O.bodies[n.id2].state.pos-facetCenter)

=== modified file 'examples/packs/packs.py'
--- examples/packs/packs.py	2013-03-28 16:15:54 +0000
+++ examples/packs/packs.py	2013-10-04 11:58:44 +0000
@@ -43,7 +43,7 @@
 	pack.regularHexa (pack.inCylinder((+1,1,-2.5),(0,3,-5),1),radius=rad,gap=gap,color=(0,1,1),**kw), # right leg
 	pack.regularHexa (pack.inHyperboloid((+2,0,1),(+6,0,0),1,.5),radius=rad,gap=gap,color=(0,0,1),**kw), # right hand
 	pack.regularOrtho(pack.inCylinder((-2,0,2),(-5,0,4),1),radius=rad,gap=gap,color=(0,0,1),**kw) # left hand
-	]: O.bodies.appendClumped(part)
+	]: O.bodies.appendClumped(part,integrateInertia=False)
 
 
 # Example of geom.facetBox usage 

=== modified file 'lib/import/STLReader.hpp'
--- lib/import/STLReader.hpp	2013-05-29 09:48:51 +0000
+++ lib/import/STLReader.hpp	2013-09-23 17:39:59 +0000
@@ -111,20 +111,19 @@
     
     vector<Vrtx> vcs;
     set<pair<int,int> > egs;
-    size_t ret;
 
     /* Read a single facet from an ASCII .STL file */
     while(!feof(fp))
     {
 	float n[3];
 	Vrtx v[3];
-	ret=fscanf(fp, "%*s %*s %f %f %f\n", &n[0], &n[1], &n[2]);
-	ret=fscanf(fp, "%*s %*s");
-	ret=fscanf(fp, "%*s %f %f %f\n", &v[0][0],  &v[0][1],  &v[0][2]);
-	ret=fscanf(fp, "%*s %f %f %f\n", &v[1][0],  &v[1][1],  &v[1][2]);
-	ret=fscanf(fp, "%*s %f %f %f\n", &v[2][0],  &v[2][1],  &v[2][2]);
-	ret=fscanf(fp, "%*s"); // end loop
-	ret=fscanf(fp, "%*s"); // end facet
+	fscanf(fp, "%*s %*s %f %f %f\n", &n[0], &n[1], &n[2]);
+	fscanf(fp, "%*s %*s");
+	fscanf(fp, "%*s %f %f %f\n", &v[0][0],  &v[0][1],  &v[0][2]);
+	fscanf(fp, "%*s %f %f %f\n", &v[1][0],  &v[1][1],  &v[1][2]);
+	fscanf(fp, "%*s %f %f %f\n", &v[2][0],  &v[2][1],  &v[2][2]);
+	fscanf(fp, "%*s"); // end loop
+	fscanf(fp, "%*s"); // end facet
 	if(feof(fp)) break;
 
 	int vid[3];

=== modified file 'pkg/dem/FlowEngine.cpp'
--- pkg/dem/FlowEngine.cpp	2013-08-30 13:27:06 +0000
+++ pkg/dem/FlowEngine.cpp	2013-09-23 17:39:59 +0000
@@ -395,7 +395,6 @@
 	typedef typename Solver::element_type Flow;
 	typedef typename Flow::Finite_vertices_iterator Finite_vertices_iterator;
 	typedef typename Solver::element_type Flow;
-	typedef typename Flow::Finite_cells_iterator Finite_cells_iterator;
 	
 	Finite_vertices_iterator vertices_end = flow->T[flow->currentTes].Triangulation().finite_vertices_end();
 	CGT::Vecteur Zero(0,0,0);

=== modified file 'pkg/dem/GlobalStiffnessTimeStepper.cpp'
--- pkg/dem/GlobalStiffnessTimeStepper.cpp	2013-05-24 16:48:19 +0000
+++ pkg/dem/GlobalStiffnessTimeStepper.cpp	2013-09-26 07:51:11 +0000
@@ -14,6 +14,7 @@
 #include<yade/core/Scene.hpp>
 #include<yade/core/Clump.hpp>
 #include<yade/pkg/dem/Shop.hpp>
+#include<yade/pkg/dem/ViscoelasticPM.hpp>
 
 CREATE_LOGGER(GlobalStiffnessTimeStepper);
 YADE_PLUGIN((GlobalStiffnessTimeStepper));
@@ -25,13 +26,16 @@
 	State* sdec=body->state.get();
 	Vector3r&  stiffness= stiffnesses[body->getId()];
 	Vector3r& Rstiffness=Rstiffnesses[body->getId()];
-	
 	if(body->isClump()) {// if clump, we sum stifnesses of all members
 		const shared_ptr<Clump>& clump=YADE_PTR_CAST<Clump>(body->shape);
 		FOREACH(Clump::MemberMap::value_type& B, clump->members){
 			const shared_ptr<Body>& b = Body::byId(B.first,scene);
 			stiffness+=stiffnesses[b->getId()];
 			Rstiffness+=Rstiffnesses[b->getId()];
+			if (viscEl == true){
+				viscosities[body->getId()]+=viscosities[b->getId()];
+				Rviscosities[body->getId()]+=Rviscosities[b->getId()];
+			}
 		}
 	}
 	
@@ -39,13 +43,15 @@
 		if (densityScaling) sdec->densityScaling = min(1.0001*sdec->densityScaling, timestepSafetyCoefficient*pow(defaultDt/targetDt,2.0));
 		return; // not possible to compute!
 	}
-	
+
+	//Determine the elastic minimum eigenperiod (and if required determine also the viscous one separately and take the minimum of the two)
+
+	//Elastic
 	Real dtx, dty, dtz;
 	Real dt = max( max (stiffness.x(), stiffness.y()), stiffness.z() );
 	if (dt!=0) {
 		dt = sdec->mass/dt;  computedSomething = true;}//dt = squared eigenperiod of translational motion 
 	else dt = Mathr::MAX_REAL;
-	
 	if (Rstiffness.x()!=0) {
 		dtx = sdec->inertia.x()/Rstiffness.x();  computedSomething = true;}//dtx = squared eigenperiod of rotational motion around x
 	else dtx = Mathr::MAX_REAL;	
@@ -56,15 +62,43 @@
 		dtz = sdec->inertia.z()/Rstiffness.z();  computedSomething = true;}
 	else dtz = Mathr::MAX_REAL;
 	
-	Real Rdt =  std::min( std::min (dtx, dty), dtz );//Rdt = smallest squared eigenperiod for rotational motions
+	Real Rdt =  std::min( std::min (dtx, dty), dtz );//Rdt = smallest squared eigenperiod for elastic rotational motions
 	dt = 1.41044*timestepSafetyCoefficient*std::sqrt(std::min(dt,Rdt));//1.41044 = sqrt(2)
+	
+	//Viscous 
+	if (viscEl == true){		
+		Vector3r&  viscosity = viscosities[body->getId()];
+		Vector3r& Rviscosity = Rviscosities[body->getId()];
+		Real dtx_visc, dty_visc, dtz_visc;
+		Real dt_visc = max(max(viscosity.x(), viscosity.y()), viscosity.z() );
+		if (dt_visc!=0) {
+			dt_visc = sdec->mass/dt_visc;  computedSomething = true;}//dt = eigenperiod of the viscous translational motion 
+		else {dt_visc = Mathr::MAX_REAL;}
+
+		if (Rviscosity.x()!=0) {
+			dtx_visc = sdec->inertia.x()/Rviscosity.x();  computedSomething = true;}//dtx = eigenperiod of viscous rotational motion around x
+		else dtx_visc = Mathr::MAX_REAL;	
+		if (Rviscosity.y()!=0) {
+			dty_visc = sdec->inertia.y()/Rviscosity.y();  computedSomething = true;}
+		else dty_visc = Mathr::MAX_REAL;
+		if (Rviscosity.z()!=0) {
+			dtz_visc = sdec->inertia.z()/Rviscosity.z();  computedSomething = true;}
+		else dtz_visc = Mathr::MAX_REAL;
+	
+		Real Rdt_visc =  std::min( std::min (dtx_visc, dty_visc), dtz_visc );//Rdt = smallest squared eigenperiod for viscous rotational motions
+		dt_visc = 2*timestepSafetyCoefficient*std::min(dt_visc,Rdt_visc);
+
+		//Take the minimum between the elastic and viscous minimum eigenperiod. 
+		dt = std::min(dt,dt_visc);
+	}
+
 	//if there is a target dt, then we apply density scaling on the body, the inertia used in Newton will be mass*scaling, the weight is unmodified
 	if (densityScaling) {
 		sdec->densityScaling = min(sdec->densityScaling,timestepSafetyCoefficient*pow(dt /targetDt,2.0));
 		newDt=targetDt;
 	}
 	//else we update dt normaly
-	else {newDt = std::min(dt,newDt);}
+	else {newDt = std::min(dt,newDt);}   
 }
 
 bool GlobalStiffnessTimeStepper::isActivated()
@@ -97,7 +131,7 @@
 		computedOnce = true;}
 	else if (!computedOnce) scene->dt=defaultDt;
 	LOG_INFO("computed timestep " << newDt <<
-			(scene->dt==newDt ? string(", appplied") :
+			(scene->dt==newDt ? string(", applied") :
 			string(", BUT timestep is ")+lexical_cast<string>(scene->dt))<<".");
 }
 
@@ -107,15 +141,24 @@
 	if(size<rb->bodies->size()){
 		size=rb->bodies->size();
 		stiffnesses.resize(size); Rstiffnesses.resize(size);
+		if (viscEl == true){
+			viscosities.resize(size); Rviscosities.resize(size);
+			}
 	}
 	/* reset stored values */
 	memset(& stiffnesses[0],0,sizeof(Vector3r)*size);
 	memset(&Rstiffnesses[0],0,sizeof(Vector3r)*size);
+	if (viscEl == true){
+		memset(& viscosities[0],0,sizeof(Vector3r)*size);
+		memset(&Rviscosities[0],0,sizeof(Vector3r)*size);
+	}
+
 	FOREACH(const shared_ptr<Interaction>& contact, *rb->interactions){
 		if(!contact->isReal()) continue;
 
 		GenericSpheresContact* geom=YADE_CAST<GenericSpheresContact*>(contact->geom.get()); assert(geom);
 		NormShearPhys* phys=YADE_CAST<NormShearPhys*>(contact->phys.get()); assert(phys);
+
 		// all we need for getting stiffness
 		Vector3r& normal=geom->normal; Real& kn=phys->kn; Real& ks=phys->ks; Real& radius1=geom->refR1; Real& radius2=geom->refR2;
 		Real fn = (static_cast<NormShearPhys *> (contact->phys.get()))->normalForce.squaredNorm();
@@ -134,10 +177,35 @@
 				std::pow(normal.x(),2)+std::pow(normal.z(),2),
 				std::pow(normal.x(),2)+std::pow(normal.y(),2));
 		diag_Rstiffness *= ks;
+
+
 		//NOTE : contact laws with moments would be handled correctly by summing directly bending+twisting stiffness to diag_Rstiffness. The fact that there is no problem currently with e.g. cohesiveFrict law is probably because final computed dt is constrained by translational motion, not rotations.
 		stiffnesses [contact->getId1()]+=diag_stiffness;
 		Rstiffnesses[contact->getId1()]+=diag_Rstiffness*pow(radius1,2);
 		stiffnesses [contact->getId2()]+=diag_stiffness;
-		Rstiffnesses[contact->getId2()]+=diag_Rstiffness*pow(radius2,2);
+		Rstiffnesses[contact->getId2()]+=diag_Rstiffness*pow(radius2,2);	
+
+		//Same for the Viscous part, if required
+		if (viscEl == true){
+			ViscElPhys* viscPhys = YADE_CAST<ViscElPhys*>(contact->phys.get()); assert(viscPhys);
+			Real& cn=viscPhys->cn; Real& cs=viscPhys->cs;
+			//Diagonal terms of the translational viscous matrix
+			Vector3r diag_viscosity = Vector3r(std::pow(normal.x(),2),std::pow(normal.y(),2),std::pow(normal.z(),2));
+			diag_viscosity *= cn-cs;
+			diag_viscosity = diag_viscosity + Vector3r(1,1,1)*cs;
+			//diagonal terms of the rotational viscous matrix
+			Vector3r diag_Rviscosity =
+				Vector3r(std::pow(normal.y(),2)+std::pow(normal.z(),2),
+					std::pow(normal.x(),2)+std::pow(normal.z(),2),
+					std::pow(normal.x(),2)+std::pow(normal.y(),2));
+			diag_Rviscosity *= cs;			
+			
+			// Add the contact stiffness matrix to the two particles one
+			viscosities [contact->getId1()]+=diag_viscosity;
+			Rviscosities[contact->getId1()]+=diag_Rviscosity*pow(radius1,2);
+			viscosities [contact->getId2()]+=diag_viscosity;
+			Rviscosities[contact->getId2()]+=diag_Rviscosity*pow(radius2,2);
+		}
+
 	}
 }

=== modified file 'pkg/dem/GlobalStiffnessTimeStepper.hpp'
--- pkg/dem/GlobalStiffnessTimeStepper.hpp	2013-04-09 14:14:48 +0000
+++ pkg/dem/GlobalStiffnessTimeStepper.hpp	2013-09-27 15:51:12 +0000
@@ -24,6 +24,8 @@
 	private :
 		vector<Vector3r> stiffnesses;
 		vector<Vector3r> Rstiffnesses;
+		vector<Vector3r> viscosities;
+		vector<Vector3r> Rviscosities;
 		void computeStiffnesses(Scene*);
 
 		Real		newDt;
@@ -37,13 +39,14 @@
 		virtual void computeTimeStep(Scene*);
 		virtual bool isActivated();
 		YADE_CLASS_BASE_DOC_ATTRS_CTOR(
-			GlobalStiffnessTimeStepper,TimeStepper,"An engine assigning the time-step as a fraction of the minimum eigen-period in the problem. The derivation is detailed in the chapter on `DEM formulation <https://www.yade-dem.org/doc/formulation.html#dem-simulations>`_",
+			GlobalStiffnessTimeStepper,TimeStepper,"An engine assigning the time-step as a fraction of the minimum eigen-period in the problem. The derivation is detailed in the chapter on `DEM formulation <https://www.yade-dem.org/doc/formulation.html#dem-simulations>`_. The viscEl option enables to evaluate the timestep in a similar way for the visco-elastic contact law :yref:`Law2_ScGeom_ViscElPhys_Basic`, more detail in :yref:`GlobalStiffnessTimestepper::viscEl`. ",
 			((Real,defaultDt,-1,,"used as the initial value of the timestep (especially useful in the first steps when no contact exist). If negative, it will be defined by :yref:`utils.PWaveTimeStep` * :yref:`GlobalStiffnessTimeStepper::timestepSafetyCoefficient`"))
 			((Real,maxDt,Mathr::MAX_REAL,,"if positive, used as max value of the timestep whatever the computed value"))
 			((Real,previousDt,1,,"last computed dt |yupdate|"))
 			((Real,timestepSafetyCoefficient,0.8,,"safety factor between the minimum eigen-period and the final assigned dt (less than 1))"))
 			((bool,densityScaling,false,,"|yupdate| don't modify this value if you don't plan to modify the scaling factor manually for some bodies. In most cases, it is enough to set :yref:`NewtonIntegrator::densityScaling` and let this one be adjusted automatically."))
-			((Real,targetDt,1,,"if :yref:`NewtonIntegrator::densityScaling` is active, this value will be used as the simulation  timestep and the scaling will use this value of dt as the target value. The value of targetDt is arbitrary and should have no effect in the result in general. However if some bodies have imposed velocities, for instance, they will move more or less per each step depending on this value.")),
+			((Real,targetDt,1,,"if :yref:`NewtonIntegrator::densityScaling` is active, this value will be used as the simulation  timestep and the scaling will use this value of dt as the target value. The value of targetDt is arbitrary and should have no effect in the result in general. However if some bodies have imposed velocities, for instance, they will move more or less per each step depending on this value."))
+			((bool,viscEl,false,,"To use with :yref:`ViscElPhys`. if True, evaluate separetly the minimum eigen-period in the problem considering only the elastic contribution on one hand (spring only), and only the viscous contribution on the other hand (dashpot only). Take then the minimum of the two and use the safety coefficient :yref:`GlobalStiffnessTimestepper::timestepSafetyCoefficient` to take into account the possible coupling between the two contribution.")),
 			computedOnce=false;)
 		DECLARE_LOGGER;
 };

=== modified file 'pkg/dem/HertzMindlin.cpp'
--- pkg/dem/HertzMindlin.cpp	2013-09-07 19:40:12 +0000
+++ pkg/dem/HertzMindlin.cpp	2013-09-23 17:17:34 +0000
@@ -86,7 +86,7 @@
 	// en or es specified, just compute alpha, otherwise alpha remains 0
 	if(en || es){
 		Real logE = log((*en)(mat1->id,mat2->id));
-		contactPhysics->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), also [Antypov2011] eq. 17
 	}
 	
 	// betan specified, use that value directly; otherwise give zero
@@ -319,7 +319,7 @@
 	}
 	else if (useDamping){ // (see Tsuji, 1992)
 		Real mbar = (!b1->isDynamic() && b2->isDynamic()) ? de2->mass : ((!b2->isDynamic() && b1->isDynamic()) ? de1->mass : (de1->mass*de2->mass / (de1->mass + de2->mass))); // get equivalent mass if both bodies are dynamic, if not set it equal to the one of the dynamic body
-		cn = phys->alpha*sqrt(mbar)*pow(uN,0.25); // normal viscous coefficient
+		cn = phys->alpha*sqrt(mbar)*pow(uN,0.25); // normal viscous coefficient, see also [Antypov2011] eq. 10
 		cs = cn; // same value for shear viscous coefficient
 	}
 
@@ -346,12 +346,32 @@
 	/**************************************/
 	
 	// normal force must be updated here before we apply the Mohr-Coulomb criterion
-	if (useDamping){ // get normal viscous component 
+	if (useDamping){ // get normal viscous component
 		phys->normalViscous = cn*incidentVn;
-		// add normal viscous component if damping is included
-		phys->normalForce -= phys->normalViscous;
+		Vector3r normTemp = phys->normalForce - phys->normalViscous; // temporary normal force
+		// viscous force should not exceed the value of current normal force, i.e. no attraction force should be permitted if particles are non-adhesive
+		// if particles are adhesive, then fixed the viscous force at maximum equal to the adhesion force
+		// *** enforce normal force to zero if no adhesion is permitted ***
+		if (phys->adhesionForce==0.0 || !includeAdhesion){
+						if (normTemp.dot(scg->normal)<0.0){
+										phys->normalForce = Vector3r::Zero();
+										phys->normalViscous = phys->normalViscous + normTemp; // normal viscous force is such that the total applied force is null - it is necessary to compute energy correctly!
+						}
+						else{phys->normalForce -= phys->normalViscous;}
+		}
+		else if (includeAdhesion && phys->adhesionForce!=0.0){
+						// *** limit viscous component to the max adhesive force ***
+						if (normTemp.dot(scg->normal)<0.0 && (phys->normalViscous.norm() > phys->adhesionForce) ){
+										Real normVisc = phys->normalViscous.norm(); Vector3r normViscVector = phys->normalViscous/normVisc;
+										phys->normalViscous = phys->adhesionForce*normViscVector;
+										phys->normalForce -= phys->normalViscous;
+						}
+						// *** apply viscous component - in the presence of adhesion ***
+						else {phys->normalForce -= phys->normalViscous;}
+		}
 		if (calcEnergy) {normDampDissip += phys->normalViscous.dot(incidentVn*dt);} // calc dissipation of energy due to normal damping
 	}
+	
 
 	/*************************************/
 	/* SHEAR DISPLACEMENT (elastic only) */

=== modified file 'pkg/dem/Ip2_ElastMat.cpp'
--- pkg/dem/Ip2_ElastMat.cpp	2013-09-08 11:12:42 +0000
+++ pkg/dem/Ip2_ElastMat.cpp	2013-09-23 17:39:59 +0000
@@ -46,7 +46,7 @@
 	Real Vb 	= mat2->poisson;
 	interaction->phys = shared_ptr<NormShearPhys>(new NormShearPhys());
 	const shared_ptr<NormShearPhys>& phys = YADE_PTR_CAST<NormShearPhys>(interaction->phys);
-	Real Kn, Ks;
+	Real Kn=0.0, Ks=0.0;
 	GenericSpheresContact* geom=dynamic_cast<GenericSpheresContact*>(interaction->geom.get());
 	if (geom) {
 		Real Ra,Rb;//Vector3r normal;

=== modified file 'pkg/dem/JointedCohesiveFrictionalPM.cpp'
--- pkg/dem/JointedCohesiveFrictionalPM.cpp	2013-08-01 11:54:13 +0000
+++ pkg/dem/JointedCohesiveFrictionalPM.cpp	2013-09-19 08:50:04 +0000
@@ -174,7 +174,7 @@
 	
 	shared_ptr<JCFpmPhys> contactPhysics(new JCFpmPhys()); 
 	
-	/* From interaction physics */
+	/* From material properties */
 	Real E1 	= yade1->young;
 	Real E2 	= yade2->young;
 	Real f1 	= yade1->frictionAngle;
@@ -185,7 +185,7 @@
 	Real R2= geom->radius2;
 	contactPhysics->crossSection = Mathr::PI*pow(min(R1,R2),2);
 
-	/* Pass values to JCFpmPhys */
+	/* Pass values to JCFpmPhys. In case of a "jointed" interaction, the following values will be replaced by other ones later (in few if(){} blocks)*/
 	
 	// frictional properties
 	contactPhysics->kn = 2.*E1*R1*E2*R2/(E1*R1+E2*R2);

=== modified file 'pkg/dem/JointedCohesiveFrictionalPM.hpp'
--- pkg/dem/JointedCohesiveFrictionalPM.hpp	2013-08-01 11:54:13 +0000
+++ pkg/dem/JointedCohesiveFrictionalPM.hpp	2013-09-26 09:10:15 +0000
@@ -12,6 +12,9 @@
 	YADE_CLASS_BASE_DOC_ATTRS_CTOR(JCFpmState,State,"JCFpm state information about each body.\n\nNone of that is used for computation (at least not now), only for post-processing.",
 		((int,tensBreak,0,,"number of tensile breakages. [-]"))
                 ((int,shearBreak,0,,"number of shear breakages. [-]"))
+		// ((int,noIniLinks,0,,"number of initial cohesive interactions. [-]"))
+		// ((Real,tensBreakRel,0,,"relative number of tensile breakages (compared with noIniLinks). [-]"))
+		// ((Real,shearBreakRel,0,,"relative number of shear breakages (compared with noIniLinks). [-]"))
                 ,
 		createIndex();
 	);
@@ -77,11 +80,11 @@
 		
 		YADE_CLASS_BASE_DOC_ATTRS(Ip2_JCFpmMat_JCFpmMat_JCFpmPhys,IPhysFunctor,"converts 2 JCFpmMat instances to JCFpmPhys with corresponding parameters.",
 			((int,cohesiveTresholdIteration,1,,"should new contacts be cohesive? They will before this iter, they won't afterward."))
-			((Real,alpha,0.,,"defines the shear to normal stiffness ratio ks/kn."))
+			((Real,alpha,0.,,"defines the shear to normal stiffness ratio ks/kn in the matrix."))
 			((Real,tensileStrength,0.,,"defines the maximum admissible normal force in traction FnMax=tensileStrength*crossSection in the matrix. [Pa]"))
 			((Real,cohesion,0.,,"defines the maximum admissible tangential force in shear FsMax=cohesion*crossSection in the matrix. [Pa]"))
-			((Real,jointNormalStiffness,0.,,"defines the normal stiffness on the joint surface. "))
-			((Real,jointShearStiffness,0.,,"defines the shear stiffness on the joint surface."))
+			((Real,jointNormalStiffness,0.,,"defines the normal stiffness on the joint surface. [Pa]"))
+			((Real,jointShearStiffness,0.,,"defines the shear stiffness on the joint surface. [Pa]"))
 			((Real,jointTensileStrength,0.,,"defines the maximum admissible normal force in traction FnMax=tensileStrength*crossSection on the joint surface. [Pa]"))
 			((Real,jointCohesion,0.,,"defines the maximum admissible tangential force in shear FsMax=cohesion*crossSection on the joint surface. [Pa]"))
 			((Real,jointFrictionAngle,-1,,"defines Coulomb friction on the joint surface. [rad]"))
@@ -97,7 +100,7 @@
 		virtual void go(shared_ptr<IGeom>& _geom, shared_ptr<IPhys>& _phys, Interaction* I);
 		FUNCTOR2D(ScGeom,JCFpmPhys);
 
-		YADE_CLASS_BASE_DOC_ATTRS(Law2_ScGeom_JCFpmPhys_JointedCohesiveFrictionalPM,LawFunctor,"interaction law for jointed frictional material. Basically, this law adds the possibility to define joint surfaces into a cohesive frictional material as defined by :yref:'Law2_ScGeom_CFpmPhys_CohesiveFrictionalPM'. Joint surfaces can be defined in a preprocessing phase through .stl meshes (see ref for details of the procedure).",
+		YADE_CLASS_BASE_DOC_ATTRS(Law2_ScGeom_JCFpmPhys_JointedCohesiveFrictionalPM,LawFunctor,"interaction law for jointed frictional material. Basically, this law adds the possibility to define joint surfaces into a cohesive frictional material as defined by :yref:`Law2_ScGeom_CFpmPhys_CohesiveFrictionalPM`. Joint surfaces can be defined in a preprocessing phase through .stl meshes (see ref for details of the procedure).",
 			((bool,smoothJoint,false,,"if true, particles belonging to joint surface have a smooth contact logic."))
 			((bool,recordCracks,false,,"if true a text file cracks.txt will be created (iteration, position, type (tensile or shear), cross section and contact normal)."))
 			((bool,cracksFileExist,false,,"If true, text file already exists and its content won't be reset."))

=== modified file 'pkg/dem/NewtonIntegrator.hpp'
--- pkg/dem/NewtonIntegrator.hpp	2013-05-14 21:24:11 +0000
+++ pkg/dem/NewtonIntegrator.hpp	2013-09-26 09:03:43 +0000
@@ -61,7 +61,7 @@
 		virtual void action();
 	YADE_CLASS_BASE_DOC_ATTRS_CTOR_PY(NewtonIntegrator,GlobalEngine,"Engine integrating newtonian motion equations.",
 		((Real,damping,0.2,,"damping coefficient for Cundall's non viscous damping (see [Chareyre2005]_) [-]"))
-		((Vector3r,gravity,Vector3r::Zero(),,"Gravitational acceleration (effectifely replaces GravityEngine)."))
+		((Vector3r,gravity,Vector3r::Zero(),,"Gravitational acceleration (effectively replaces GravityEngine)."))
 		((Real,maxVelocitySq,NaN,,"store square of max. velocity, for informative purposes; computed again at every step. |yupdate|"))
 		((bool,exactAsphericalRot,true,,"Enable more exact body rotation integrator for :yref:`aspherical bodies<Body.aspherical>` *only*, using formulation from [Allen1989]_, pg. 89."))
 		((Matrix3r,prevVelGrad,Matrix3r::Zero(),,"Store previous velocity gradient (:yref:`Cell::velGrad`) to track acceleration. |yupdate|"))

=== modified file 'pkg/dem/Shop.cpp'
--- pkg/dem/Shop.cpp	2013-09-08 11:19:06 +0000
+++ pkg/dem/Shop.cpp	2013-10-04 11:41:10 +0000
@@ -873,7 +873,7 @@
 	}
 }
 
-void Shop::growParticles(Real multiplier, bool updateMass, bool dynamicOnly)
+void Shop::growParticles(Real multiplier, bool updateMass, bool dynamicOnly, unsigned int discretization, bool integrateInertia)
 {
 	Scene* scene = Omega::instance().getScene().get();
 	FOREACH(const shared_ptr<Body>& b,*scene->bodies){
@@ -888,7 +888,7 @@
 	FOREACH(const shared_ptr<Body>& b,*scene->bodies){
 		if(b->isClump()){
 			Clump* clumpSt = YADE_CAST<Clump*>(b->shape.get());
-			clumpSt->updateProperties(b);
+			clumpSt->updateProperties(b, discretization, integrateInertia);
 		}
 	}
 	FOREACH(const shared_ptr<Interaction>& ii, *scene->interactions){

=== modified file 'pkg/dem/Shop.hpp'
--- pkg/dem/Shop.hpp	2013-09-08 11:19:06 +0000
+++ pkg/dem/Shop.hpp	2013-10-04 11:41:10 +0000
@@ -145,7 +145,7 @@
 		static void setContactFriction(Real angleRad);
 
 		//! Homothetic change of sizes of spheres and clumps
-		static void growParticles(Real multiplier, bool updateMass, bool dynamicOnly);
+		static void growParticles(Real multiplier, bool updateMass, bool dynamicOnly, unsigned int discretization, bool integrateInertia);
 
 
 };

=== modified file 'pkg/dem/SpherePack.cpp'
--- pkg/dem/SpherePack.cpp	2013-08-23 15:21:20 +0000
+++ pkg/dem/SpherePack.cpp	2013-09-23 17:39:59 +0000
@@ -410,7 +410,7 @@
 					for(size_t j=0; j<packSize; j++){ if(pow(pack[j].r+r,2) >= (pack[j].c-c).squaredNorm()) { overlap=true; break; } }
 				} else {
 					for(size_t j=0; j<packSize; j++){
-						Vector3r dr;
+						Vector3r dr=Vector3r::Zero();
 						for(int axis=0; axis<2; axis++) dr[axis]=min(cellWrapRel(c[axis],pack[j].c[axis],pack[j].c[axis]+size[axis]),cellWrapRel(pack[j].c[axis],c[axis],c[axis]+size[axis]));
 						if(pow(pack[j].r+r,2)>= dr.squaredNorm()){ overlap=true; break; }
 					}

=== modified file 'pkg/dem/Tetra.cpp'
--- pkg/dem/Tetra.cpp	2013-10-04 12:03:13 +0000
+++ pkg/dem/Tetra.cpp	2013-10-04 12:04:43 +0000
@@ -148,7 +148,6 @@
 {
 	for (int i=0; i<6; i++) {
 		const Segment& sa = sA[i];
-		bool b[4];
 		const Triangle& ta0 = tA[stMap[i][0]];
 		const Triangle& ta1 = tA[stMap[i][1]];
 		for (int j=0; j<6; j++) {
@@ -222,8 +221,6 @@
 				bool b21 = do_intersect(ta,s21);
 				bool b22 = do_intersect(ta,s22);
 				if ( !((b20 && b21) || (b21 && b22) || (b22 && b20) ) ) { continue; }
-				int si = ppsMap[j][k];
-				const Segment& sb = sB[si];
 				int l,m;
 				for (l=0; l<3; l++) {
 					if (l!=j && l!=k) { break; }
@@ -231,8 +228,6 @@
 				for (m=l+1; m<4; m++) {
 					if (m!=j && m!=k) { break; }
 				}
-				const Point& p3 = pB[l];
-				const Point& p4 = pB[m];
 				const Segment& s13 = sB[ppsMap[j][l]];
 				const Segment& s14 = sB[ppsMap[j][m]];
 				const Segment& s23 = sB[ppsMap[k][l]];

=== modified file 'pkg/dem/TriaxialTest.hpp'
--- pkg/dem/TriaxialTest.hpp	2012-09-08 01:19:45 +0000
+++ pkg/dem/TriaxialTest.hpp	2013-09-19 08:50:04 +0000
@@ -28,7 +28,7 @@
 	
 	Essential engines :
 	
-	1/ The TrixialCompressionEngine is used for controlling the state of the sample and simulating loading paths. TrixialCompressionEngine inherits from TriaxialStressController, which can compute stress- strain-like quantities in the packing and maintain a constant level of stress at each boundary. TriaxialCompressionEngine has few more members in order to impose constant strain rate and control the transition between isotropic compression and triaxial test.
+	1/ The TriaxialCompressionEngine is used for controlling the state of the sample and simulating loading paths. TriaxialCompressionEngine inherits from TriaxialStressController, which can compute stress- strain-like quantities in the packing and maintain a constant level of stress at each boundary. TriaxialCompressionEngine has few more members in order to impose constant strain rate and control the transition between isotropic compression and triaxial test.
 		
 	2/ The class TriaxialStateRecorder is used to write to a file the history of stresses and strains.
 	

=== modified file 'py/_extraDocs.py'
--- py/_extraDocs.py	2013-08-29 10:30:31 +0000
+++ py/_extraDocs.py	2013-09-19 08:50:04 +0000
@@ -46,7 +46,7 @@
 	.. note:: *Axis conventions.* Boundaries perpendicular to the *x* axis are called "left" and "right", *y* corresponds to "top" and "bottom", and axis *z* to "front" and "back". In the default loading path, strain rate is assigned along *y*, and constant stresses are assigned on *x* and *z*.
 
 **Essential engines**
-	#. The :yref:`TrixaialCompressionEngine` is used for controlling the state of the sample and simulating loading paths. :yref:`TriaxialCompressionEngine` inherits from :yref:`TriaxialStressController`, which computes stress- and strain-like quantities in the packing and maintain a constant level of stress at each boundary. :yref:`TriaxialCompressionEngine` has few more members in order to impose constant strain rate and control the transition between isotropic compression and triaxial test. Transitions are defined by changing some flags of the :yref:`TriaxialStressController`, switching from/to imposed strain rate to/from imposed stress.
+	#. The :yref:`TriaxialCompressionEngine` is used for controlling the state of the sample and simulating loading paths. :yref:`TriaxialCompressionEngine` inherits from :yref:`TriaxialStressController`, which computes stress- and strain-like quantities in the packing and maintain a constant level of stress at each boundary. :yref:`TriaxialCompressionEngine` has few more members in order to impose constant strain rate and control the transition between isotropic compression and triaxial test. Transitions are defined by changing some flags of the :yref:`TriaxialStressController`, switching from/to imposed strain rate to/from imposed stress.
 	#. The class :yref:`TriaxialStateRecorder` is used to write to a file the history of stresses and strains.
 	#. :yref:`TriaxialTest` is using :yref:`GlobalStiffnessTimeStepper` to compute an appropriate $\Dt$ for the numerical scheme. 
 

=== modified file 'py/_utils.cpp'
--- py/_utils.cpp	2013-09-08 11:19:06 +0000
+++ py/_utils.cpp	2013-10-04 11:41:10 +0000
@@ -529,7 +529,7 @@
 	py::def("wireNone",wireNone,"Set :yref:`Shape::wire` on all bodies to False, rendering them as solids.");
 	py::def("wireNoSpheres",wireNoSpheres,"Set :yref:`Shape::wire` to True on non-spherical bodies (:yref:`Facets<Facet>`, :yref:`Walls<Wall>`).");
 	py::def("flipCell",&Shop::flipCell,(py::arg("flip")=Matrix3r(Matrix3r::Zero())),"Flip periodic cell so that angles between $R^3$ axes and transformed axes are as small as possible. This function relies on the fact that periodic cell defines by repetition or its corners regular grid of points in $R^3$; however, all cells generating identical grid are equivalent and can be flipped one over another. This necessiatates adjustment of :yref:`Interaction.cellDist` for interactions that cross boundary and didn't before (or vice versa), and re-initialization of collider. The *flip* argument can be used to specify desired flip: integers, each column for one axis; if zero matrix, best fit (minimizing the angles) is computed automatically.\n\nIn c++, this function is accessible as ``Shop::flipCell``.\n\n.. warning:: This function is currently broken and should not be used.");
-	py::def("getViscoelasticFromSpheresInteraction",getViscoelasticFromSpheresInteraction,(py::arg("tc"),py::arg("en"),py::arg("es")),"Compute viscoelastic interaction parameters from analytical solution of a pair spheres collision problem:\n\n.. math:: k_n=\\frac{m}{t_c^2}\\left(\\pi^2+(\\ln e_n)^2\\right) \\\\ c_n=-\\frac{2m}{t_c} \\\\  k_t=\\frac{2}{7}\\frac{m}{t_c^2}\\left(\\pi^2+(\\ln e_t)^2\\right) \\\\ c_t=-\\frac{2}{7}\\frac{m}{t_c}\\ln e_t \n\n\nwhere $k_n$, $c_n$ are normal elastic and viscous coefficients and $k_t$, $c_t$ shear elastic and viscous coefficients. For details see [Pournin2001]_.\n\n:param float m: sphere mass $m$\n:param float tc: collision time $t_c$\n:param float en: normal restitution coefficient $e_n$\n:param float es: tangential restitution coefficient $e_s$\n:return: dictionary with keys ``kn`` (the value of $k_n$), ``cn`` ($c_n$), ``kt`` ($k_t$), ``ct`` ($c_t$).");
+	py::def("getViscoelasticFromSpheresInteraction",getViscoelasticFromSpheresInteraction,(py::arg("tc"),py::arg("en"),py::arg("es")),"Compute viscoelastic interaction parameters from analytical solution of a pair spheres collision problem:\n\n.. math:: k_n=\\frac{m}{t_c^2}\\left(\\pi^2+(\\ln e_n)^2\\right) \\\\ c_n=-\\frac{2m}{t_c}\\ln e_n \\\\  k_t=\\frac{2}{7}\\frac{m}{t_c^2}\\left(\\pi^2+(\\ln e_t)^2\\right) \\\\ c_t=-\\frac{2}{7}\\frac{m}{t_c}\\ln e_t \n\n\nwhere $k_n$, $c_n$ are normal elastic and viscous coefficients and $k_t$, $c_t$ shear elastic and viscous coefficients. For details see [Pournin2001]_.\n\n:param float m: sphere mass $m$\n:param float tc: collision time $t_c$\n:param float en: normal restitution coefficient $e_n$\n:param float es: tangential restitution coefficient $e_s$\n:return: dictionary with keys ``kn`` (the value of $k_n$), ``cn`` ($c_n$), ``kt`` ($k_t$), ``ct`` ($c_t$).");
 	py::def("stressTensorOfPeriodicCell",Shop::getStress,(py::args("volume")=0),"Deprecated, use utils.getStress instead |ydeprecated|");
 	//py::def("stressTensorOfPeriodicCell",Shop__stressTensorOfPeriodicCell,(py::args("smallStrains")=false),"Compute overall (macroscopic) stress of periodic cell using equation published in [Kuhl2001]_:\n\n.. math:: \\vec{\\sigma}=\\frac{1}{V}\\sum_cl^c[\\vec{N}^cf_N^c+\\vec{T}^{cT}\\cdot\\vec{f}^c_T],\n\nwhere $V$ is volume of the cell, $l^c$ length of interaction $c$, $f^c_N$ normal force and $\\vec{f}^c_T$ shear force. Sumed are values over all interactions $c$. $\\vec{N}^c$ and $\\vec{T}^{cT}$ are projection tensors (see the original publication for more details):\n\n.. math:: \\vec{N}=\\vec{n}\\otimes\\vec{n}\\rightarrow N_{ij}=n_in_j\n\n.. math:: \\vec{T}^T=\\vec{I}_{sym}\\cdot\\vec{n}-\\vec{n}\\otimes\\vec{n}\\otimes\\vec{n}\\rightarrow T^T_{ijk}=\\frac{1}{2}(\\delta_{ik}\\delta_{jl}+\\delta_{il}\\delta_{jk})n_l-n_in_jn_k\n\n.. math:: \\vec{T}^T\\cdot\\vec{f}_T\\equiv T^T_{ijk}f_k=(\\delta_{ik}n_j/2+\\delta_{jk}n_i/2-n_in_jn_k)f_k=n_jf_i/2+n_if_j/2-n_in_jn_kf_k,\n\nwhere $n$ is unit vector oriented along the interaction (:yref:`normal<GenericSpheresContact::normal>`) and $\\delta$ is Kronecker's delta. As $\\vec{n}$ and $\\vec{f}_T$ are perpendicular (therfore $n_if_i=0$) we can write\n\n.. math:: \\sigma_{ij}=\\frac{1}{V}\\sum l[n_in_jf_N+n_jf^T_i/2+n_if^T_j/2]\n\n:param bool smallStrains: if false (large strains), real values of volume and interaction lengths are computed. If true, only :yref:`refLength<Dem3DofGeom::refLength>` of interactions and initial volume are computed (can save some time).\n\n:return: macroscopic stress tensor as Matrix3");
 	py::def("normalShearStressTensors",Shop__normalShearStressTensors,(py::args("compressionPositive")=false,py::args("splitNormalTensor")=false,py::args("thresholdForce")=NaN),"Compute overall stress tensor of the periodic cell decomposed in 2 parts, one contributed by normal forces, the other by shear forces. The formulation can be found in [Thornton2000]_, eq. (3):\n\n.. math:: \\tens{\\sigma}_{ij}=\\frac{2}{V}\\sum R N \\vec{n}_i \\vec{n}_j+\\frac{2}{V}\\sum R T \\vec{n}_i\\vec{t}_j\n\nwhere $V$ is the cell volume, $R$ is \"contact radius\" (in our implementation, current distance between particle centroids), $\\vec{n}$ is the normal vector, $\\vec{t}$ is a vector perpendicular to $\\vec{n}$, $N$ and $T$ are norms of normal and shear forces.\n\n:param bool splitNormalTensor: if true the function returns normal stress tensor split into two parts according to the two subnetworks of strong an weak forces.\n\n:param Real thresholdForce: threshold value according to which the normal stress tensor can be split (e.g. a zero value would make distinction between tensile and compressive forces).");
@@ -543,7 +543,7 @@
 	py::def("calm",Shop__calm,(py::arg("mask")=-1),"Set translational and rotational velocities of all bodies to zero.");
 	py::def("setNewVerticesOfFacet",setNewVerticesOfFacet,(py::arg("b"),py::arg("v1"),py::arg("v2"),py::arg("v3")),"Sets new vertices (in global coordinates) to given facet.");
 	py::def("setContactFriction",Shop::setContactFriction,py::arg("angleRad"),"Modify the friction angle (in radians) inside the material classes and existing contacts. The friction for non-dynamic bodies is not modified.");
-	py::def("growParticles",Shop::growParticles,(py::args("multiplier"), py::args("updateMass")=true, py::args("dynamicOnly")=true), "Change the size of spheres and sphere clumps by the multiplier. If updateMass=True, then the mass is updated. dynamicOnly=True is mandatory in many cases since in current implementation the function would crash on the non-spherical and non-dynamic bodies (e.g. facets, boxes, etc.)");
+	py::def("growParticles",Shop::growParticles,(py::args("multiplier"), py::args("updateMass")=true, py::args("dynamicOnly")=true, py::args("discretization")=15, py::args("integrateInertia")=true), "Change the size of spheres and sphere clumps by the multiplier. If updateMass=True, then the mass is updated. dynamicOnly=True is mandatory in many cases since in current implementation the function would crash on the non-spherical and non-dynamic bodies (e.g. facets, boxes, etc.). For clumps the masses and inertias are adapted automatically (for details of inertia tensor integration scheme see :yref:`clump()<BodyContainer.clump>`).");
 	py::def("intrsOfEachBody",intrsOfEachBody,"returns list of lists of interactions of each body");
 	py::def("numIntrsOfEachBody",numIntrsOfEachBody,"returns list of number of interactions of each body");
 	py::def("TetrahedronSignedVolume",static_cast<Real (*)(const vector<Vector3r>&)>(&TetrahedronSignedVolume),"TODO");

=== modified file 'py/export.py'
--- py/export.py	2013-10-04 12:03:13 +0000
+++ py/export.py	2013-10-04 12:04:43 +0000
@@ -26,25 +26,53 @@
 	
 	count=0
 	
-	out.write('#format ' + format + '\n')
-	if (comment):
-		out.write('# ' + comment + '\n')
+	output = ''
+	outputVel=''
+	if (format<>'liggghts_in'):
+		output = '#format ' + format + '\n'
+		if (comment):
+			output += '# ' + comment + '\n'
+	
+	minCoord= Vector3.Zero
+	maxCoord= Vector3.Zero
+	maskNumber = []
+	
 	for b in O.bodies:
 		try:
 			if (isinstance(b.shape,Sphere) and ((mask<0) or ((mask&b.mask)>0))):
 				if (format=='x_y_z_r'):
-					out.write('%g\t%g\t%g\t%g\n'%(b.state.pos[0],b.state.pos[1],b.state.pos[2],b.shape.radius))
+					output+=('%g\t%g\t%g\t%g\n'%(b.state.pos[0],b.state.pos[1],b.state.pos[2],b.shape.radius))
 				elif (format=='x_y_z_r_matId'):
-					out.write('%g\t%g\t%g\t%g\t%d\n'%(b.state.pos[0],b.state.pos[1],b.state.pos[2],b.shape.radius,b.material.id))
+					output+=('%g\t%g\t%g\t%g\t%d\n'%(b.state.pos[0],b.state.pos[1],b.state.pos[2],b.shape.radius,b.material.id))
 				elif (format=='id_x_y_z_r_matId'):
-					out.write('%d\t%g\t%g\t%g\t%g\t%d\n'%(b.id,b.state.pos[0],b.state.pos[1],b.state.pos[2],b.shape.radius,b.material.id))
+					output+=('%d\t%g\t%g\t%g\t%g\t%d\n'%(b.id,b.state.pos[0],b.state.pos[1],b.state.pos[2],b.shape.radius,b.material.id))
 				elif (format=='jointedPM'):
-					out.write('%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\n'%(b.id,b.mat.onJoint,b.mat.joint,b.mat.jointNormal1[0],b.mat.jointNormal1[1],b.mat.jointNormal1[2],b.mat.jointNormal2[0],b.mat.jointNormal2[1],b.mat.jointNormal2[2],b.mat.jointNormal3[0],b.mat.jointNormal3[1],b.mat.jointNormal3[2]))
+					output+=('%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\t%g\n'%(b.id,b.mat.onJoint,b.mat.joint,b.mat.jointNormal1[0],b.mat.jointNormal1[1],b.mat.jointNormal1[2],b.mat.jointNormal2[0],b.mat.jointNormal2[1],b.mat.jointNormal2[2],b.mat.jointNormal3[0],b.mat.jointNormal3[1],b.mat.jointNormal3[2]))
+				elif (format=='liggghts_in'):
+					output+=('%g %g %g %g %g %g %g\n'%(count+1,b.mask,b.shape.radius,b.material.density,b.state.pos[0],b.state.pos[1],b.state.pos[2]))
+					outputVel+=('%g %g %g %g %g %g %g\n'%(count+1,b.state.vel[0],b.state.vel[1],b.state.vel[2],b.state.angVel[0],b.state.angVel[1],b.state.angVel[2]))
 				else:
 					raise RuntimeError("Please, specify a correct format output!");
 				count+=1
+				if  (count==1):
+					minCoord = b.state.pos - Vector3(b.shape.radius,b.shape.radius,b.shape.radius)
+					maxCoord = b.state.pos + Vector3(b.shape.radius,b.shape.radius,b.shape.radius)
+				else:
+					minCoord = Vector3(min(minCoord[0], b.state.pos[0]-b.shape.radius),min(minCoord[1], b.state.pos[1]-b.shape.radius),min(minCoord[2], b.state.pos[2]-b.shape.radius))
+					maxCoord = Vector3(max(maxCoord[0], b.state.pos[0]+b.shape.radius),max(maxCoord[1], b.state.pos[1]+b.shape.radius),max(minCoord[2], b.state.pos[2]+b.shape.radius))
+				if b.mask not in maskNumber:
+					maskNumber.append(b.mask)
 		except AttributeError:
 			pass
+			
+	if (format=='liggghts_in'):
+		outputHeader = 'LIGGGHTS Description\n\n'
+		outputHeader += '%d atoms\n%d atom types\n\n'%(count,len(maskNumber))
+		outputHeader += '%g %g xlo xhi\n%g %g ylo yhi\n%g %g zlo zhi\n\n'%(minCoord[0],maxCoord[0],minCoord[1],maxCoord[1],minCoord[2],maxCoord[2])
+		
+		
+		output=outputHeader + 'Atoms\n\n' + output + '\nVelocities\n\n' + outputVel
+	out.write(output)
 	out.close()
 	return count
 

=== modified file 'py/pack/pack.py'
--- py/pack/pack.py	2013-03-08 21:26:47 +0000
+++ py/pack/pack.py	2013-09-19 08:50:04 +0000
@@ -286,7 +286,8 @@
 	return ret
 
 def filterSpherePack(predicate,spherePack,returnSpherePack=None,**kw):
-	"""Using given SpherePack instance, return spheres the satisfy predicate.
+	"""Using given SpherePack instance, return spheres that satisfy predicate.
+	It returns either a :yref:`yade._packSpheres.SpherePack` (if returnSpherePack) or a list.
 	The packing will be recentered to match the predicate and warning is given if the predicate
 	is larger than the packing."""
 	if returnSpherePack==None:
@@ -386,7 +387,7 @@
 	:param predicate: solid-defining predicate for which we generate packing
 	:param spheresInCell: if given, the packing will be periodic, with given number of spheres in the periodic cell.
 	:param radius: mean radius of spheres
-	:param rRelFuzz: relative fuzz of the radius -- e.g. radius=10, rRelFuzz=.2, then spheres will have radii 10 ± (10*.2)).
+	:param rRelFuzz: relative fuzz of the radius -- e.g. radius=10, rRelFuzz=.2, then spheres will have radii 10 ± (10*.2)), with an uniform distribution.
 		0 by default, meaning all spheres will have exactly the same radius.
 	:param cropLayers: (aperiodic only) how many layers of spheres will be added to the computed dimension of the box so that there no
 		(or not so much, at least) boundary effects at the boundaries of the predicate.
@@ -398,9 +399,9 @@
 		least number spheres will be loaded and returned.
 	:param useOBB: effective only if a inGtsSurface predicate is given. If true (not default), oriented bounding box will be
 		computed first; it can reduce substantially number of spheres for the triaxial compression (like 10× depending on
-		how much asymmetric the body is), see scripts/test/gts-triax-pack-obb.py.
-	:param memoDbg: show packigns that are considered and reasons why they are rejected/accepted
-	:param returnSpherePack: see :yref:`filterSpherePack`
+		how much asymmetric the body is), see examples/gts-horse/gts-random-pack-obb.py
+	:param memoDbg: show packings that are considered and reasons why they are rejected/accepted
+	:param returnSpherePack: see the corresponding argument in :yref:`yade.pack.filterSpherePack`
 
 	:return: SpherePack object with spheres, filtered by the predicate.
 	"""

=== modified file 'py/utils.py'
--- py/utils.py	2013-10-04 12:03:13 +0000
+++ py/utils.py	2013-10-04 12:04:43 +0000
@@ -270,7 +270,7 @@
 	b.mask=0	#avoid contact detection with the nodes. Manual interaction will be set for them in "gridConnection" below.
 	return b
 
-def gridConnection(id1,id2,radius,wire=False,color=None,highlight=False,material=-1,mask="none",cellDist=None):
+def gridConnection(id1,id2,radius,wire=False,color=None,highlight=False,material=-1,mask=1,cellDist=None):
 	b=Body()
 	b.shape=GridConnection(radius=radius,color=color if color else randomColor(),wire=wire,highlight=highlight)
 	sph1=O.bodies[id1] ; sph2=O.bodies[id2]

=== modified file 'py/wrapper/yadeWrapper.cpp'
--- py/wrapper/yadeWrapper.cpp	2013-08-22 18:35:55 +0000
+++ py/wrapper/yadeWrapper.cpp	2013-10-04 11:47:37 +0000
@@ -133,7 +133,7 @@
 		#endif
 		vector<Body::id_t> ret; FOREACH(shared_ptr<Body>& b, bb){ret.push_back(append(b));} return ret;
 	}
-	Body::id_t clump(vector<Body::id_t> ids){
+	Body::id_t clump(vector<Body::id_t> ids, unsigned int discretization, bool integrateInertia){
 		// create and add clump itself
 		Scene* scene(Omega::instance().getScene().get());
 		shared_ptr<Body> clumpBody=shared_ptr<Body>(new Body());
@@ -149,16 +149,16 @@
 		};
 		
 		FOREACH(Body::id_t id, ids) Clump::add(clumpBody,Body::byId(id,scene));
-		Clump::updateProperties(clumpBody);
+		Clump::updateProperties(clumpBody, discretization, integrateInertia);
 		return clumpBody->getId();
 	}
-	python::tuple appendClump(vector<shared_ptr<Body> > bb){
+	python::tuple appendClump(vector<shared_ptr<Body> > bb, unsigned int discretization, bool integrateInertia){
 		// append constituent particles
 		vector<Body::id_t> ids(appendList(bb));
 		// clump them together (the clump fcn) and return
-		return python::make_tuple(clump(ids),ids);
+		return python::make_tuple(clump(ids, discretization, integrateInertia),ids);
 	}
-	void addToClump(vector<Body::id_t> bids, Body::id_t cid){
+	void addToClump(vector<Body::id_t> bids, Body::id_t cid, unsigned int discretization, bool integrateInertia){
 		Scene* scene(Omega::instance().getScene().get());	// get scene
 		shared_ptr<Body> clp = Body::byId(cid,scene);		// get clump pointer
 		checkClump(clp);
@@ -179,10 +179,10 @@
 			}
 			else Clump::add(clp,bp);// bp must be a standalone!
 		}
-		Clump::updateProperties(clp);
+		Clump::updateProperties(clp, discretization, integrateInertia);
 		FOREACH(Body::id_t bid, eraseList) proxee->erase(bid);//erase old clumps
 	}
-	void releaseFromClump(Body::id_t bid, Body::id_t cid){
+	void releaseFromClump(Body::id_t bid, Body::id_t cid, unsigned int discretization, bool integrateInertia){
 		Scene* scene(Omega::instance().getScene().get());	// get scene
 		shared_ptr<Body> bp = Body::byId(bid,scene);		// get body pointer
 		shared_ptr<Body> clp = Body::byId(cid,scene);		// get clump pointer
@@ -194,11 +194,11 @@
 				std::map<Body::id_t,Se3r>& members = clump->members;
 				if (members.size() == 2) {PyErr_Warn(PyExc_UserWarning,("Warning: Body "+lexical_cast<string>(bid)+" not released from clump "+lexical_cast<string>(cid)+", because number of clump members would get < 2!").c_str()); return;}
 				Clump::del(clp,bp);//release bid from cid
-				Clump::updateProperties(clp);
+				Clump::updateProperties(clp, discretization, integrateInertia);
 			} else { PyErr_Warn(PyExc_UserWarning,("Warning: Body "+lexical_cast<string>(bid)+" must be a clump member of clump "+lexical_cast<string>(cid)+". Body was not released.").c_str()); return;}
 		} else { PyErr_Warn(PyExc_UserWarning,("Warning: Body "+lexical_cast<string>(bid)+" is not a clump member. Body was not released.").c_str()); return;}
 	}
-	python::list replaceByClumps(python::list ctList, vector<Real> amounts){
+	python::list replaceByClumps(python::list ctList, vector<Real> amounts, unsigned int discretization, bool integrateInertia){
 		python::list ret;
 		Real checkSum = 0.0;
 		FOREACH(Real amount, amounts) {
@@ -337,7 +337,7 @@
 					LOG_DEBUG("New body (sphere) "<<newSphere->id<<" added.");
 					idsTmp[jj] = newSphere->id;
 				}
-				Body::id_t newClumpId = clump(idsTmp);
+				Body::id_t newClumpId = clump(idsTmp, discretization, integrateInertia);
 				ret.append(python::make_tuple(newClumpId,idsTmp));
 				erase(b->id);
 			}
@@ -860,12 +860,12 @@
 		.def("__iter__",&pyBodyContainer::pyIter)
 		.def("append",&pyBodyContainer::append,"Append one Body instance, return its id.")
 		.def("append",&pyBodyContainer::appendList,"Append list of Body instance, return list of ids")
-		.def("appendClumped",&pyBodyContainer::appendClump,"Append given list of bodies as a clump (rigid aggregate); returns a tuple of ``(clumpId,[memberId1,memberId2,...])``. Clump masses and inertia are adapted automatically. If clump members are overlapping this is done by integration/summation over mass points using a regular grid of cells. For non-overlapping members inertia of the clump is the sum of inertias from members.")
-		.def("clump",&pyBodyContainer::clump,"Clump given bodies together (creating a rigid aggregate); returns ``clumpId``. Clump masses and inertia are adapted automatically (see :yref:`appendClumped()<BodyContainer.appendClumped>`).")
-		.def("addToClump",&pyBodyContainer::addToClump,"Add body b (or a list of bodies) to an existing clump c. c must be clump and b may not be a clump member of c.\n\nSee **/examples/clumps/addToClump-example.py** for an example script.\n\n.. note:: If b is a clump itself, then all members will be added to c and b will be deleted. If b is a clump member of clump d, then all members from d will be added to c and d will be deleted. If you need to add just clump member b, :yref:`release<BodyContainer.releaseFromClump>` this member from d first.")
-		.def("releaseFromClump",&pyBodyContainer::releaseFromClump,"Release body b from clump c. b must be a clump member of c.\n\nSee **/examples/clumps/releaseFromClump-example.py** for an example script.\n\n.. note:: If c contains only 2 members b will not be released and a warning will appear. In this case clump c should be :yref:`erased<BodyContainer.erase>`.")
-		.def("replaceByClumps",&pyBodyContainer::replaceByClumps,"Replace spheres by clumps using a list of clump templates and a list of amounts; returns a list of tuples: ``[(clumpId1,[memberId1,memberId2,...]),(clumpId2,[memberId1,memberId2,...]),...]``. A new clump will have the same volume as the sphere, that was replaced (clump volume/mass/inertia is accounting for overlaps assuming that there are only pair overlaps, to adapt masses of clumps with multiple overlaps use :yref:`adaptClumpMasses()<BodyContainer.adaptClumpMasses>`). \n\n\t *O.bodies.replaceByClumps( [utils.clumpTemplate([1,1],[.5,.5])] , [.9] ) #will replace 90 % of all standalone spheres by 'dyads'*\n\nSee **/examples/clumps/replaceByClumps-example.py** for an example script.")
-		.def("getRoundness",&pyBodyContainer::getRoundness,"Returns roundness coefficient RC = R2/R1. R1 is the theoretical radius of a sphere, with same volume as clump. R2 is the minimum radius of a sphere, that imbeds clump. If just spheres are present RC = 1. If clumps are present 0 < RC < 1. Bodies can be excluded from the calculation by giving a list of ids: *O.bodies.getRoundness([ids])*.\n\nSee **/examples/clumps/replaceByClumps-example.py** for an example script.")
+		.def("appendClumped",&pyBodyContainer::appendClump,(python::arg("discretization")=15,python::arg("integrateInertia")=true),"Append given list of bodies as a clump (rigid aggregate); returns a tuple of ``(clumpId,[memberId1,memberId2,...])``. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`).")
+		.def("clump",&pyBodyContainer::clump,(python::arg("discretization")=15,python::arg("integrateInertia")=true),"Clump given bodies together (creating a rigid aggregate); returns ``clumpId``. Clump masses and inertia are adapted automatically (default with integrateInertia=True). If clump members are overlapping this is done by integration/summation over mass points using a regular grid of cells (number of grid cells in one direction is defined as $R_{min}/discretization$, where $R_{min}$ is minimum clump member radius). For non-overlapping members inertia of the clump is the sum of inertias from members. If integrateInertia=False sum of inertias from members is used (faster, but inaccurate).")
+		.def("addToClump",&pyBodyContainer::addToClump,(python::arg("discretization")=15,python::arg("integrateInertia")=true),"Add body b (or a list of bodies) to an existing clump c. c must be clump and b may not be a clump member of c. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`).\n\nSee :ysrc:`examples/clumps/addToClump-example.py` for an example script.\n\n.. note:: If b is a clump itself, then all members will be added to c and b will be deleted. If b is a clump member of clump d, then all members from d will be added to c and d will be deleted. If you need to add just clump member b, :yref:`release<BodyContainer.releaseFromClump>` this member from d first.")
+		.def("releaseFromClump",&pyBodyContainer::releaseFromClump,(python::arg("discretization")=15,python::arg("integrateInertia")=true),"Release body b from clump c. b must be a clump member of c. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`).\n\nSee :ysrc:`examples/clumps/releaseFromClump-example.py` for an example script.\n\n.. note:: If c contains only 2 members b will not be released and a warning will appear. In this case clump c should be :yref:`erased<BodyContainer.erase>`.")
+		.def("replaceByClumps",&pyBodyContainer::replaceByClumps,(python::arg("discretization")=15,python::arg("integrateInertia")=true),"Replace spheres by clumps using a list of clump templates and a list of amounts; returns a list of tuples: ``[(clumpId1,[memberId1,memberId2,...]),(clumpId2,[memberId1,memberId2,...]),...]``. A new clump will have the same volume as the sphere, that was replaced. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`). \n\n\t *O.bodies.replaceByClumps( [utils.clumpTemplate([1,1],[.5,.5])] , [.9] ) #will replace 90 % of all standalone spheres by 'dyads'*\n\nSee :ysrc:`examples/clumps/replaceByClumps-example.py` for an example script.")
+		.def("getRoundness",&pyBodyContainer::getRoundness,"Returns roundness coefficient RC = R2/R1. R1 is the theoretical radius of a sphere, with same volume as clump. R2 is the minimum radius of a sphere, that imbeds clump. If just spheres are present RC = 1. If clumps are present 0 < RC < 1. Bodies can be excluded from the calculation by giving a list of ids: *O.bodies.getRoundness([ids])*.\n\nSee :ysrc:`examples/clumps/replaceByClumps-example.py` for an example script.")
 		.def("clear", &pyBodyContainer::clear,"Remove all bodies (interactions not checked)")
 		.def("erase", &pyBodyContainer::erase,"Erase body with the given id; all interaction will be deleted by InteractionLoop in the next step.")
 		.def("replace",&pyBodyContainer::replace);

=== removed file 'yade.kdev4'
--- yade.kdev4	2013-04-09 07:59:49 +0000
+++ yade.kdev4	1970-01-01 00:00:00 +0000
@@ -1,3 +0,0 @@
-[Project]
-Manager=KDevCustomMakeManager
-Name=yade