← Back to team overview

yade-dev team mailing list archive

[Branch ~yade-pkg/yade/git-trunk] Rev 3778: Potential particles modifications

 

------------------------------------------------------------
revno: 3778
committer: Jan Stransky <jan.stransky@xxxxxxxxxxx>
timestamp: Fri 2016-01-22 23:27:43 +0100
message:
  Potential particles modifications
  
  deleted unused code, fixed compilation warnings
  Marking PotentialParticles as experimental in docs
  fixed PotentialParticles rendering
  fixed a buf in MarchonCube (positions)
  double, floats -> Real (where possible)
  commented cout, fprintf
  added one example
modified:
  examples/PotentialParticles/cubePPscaled.py
  lib/computational-geometry/MarchingCube.cpp
  lib/computational-geometry/MarchingCube.hpp
  pkg/common/Gl1_PotentialParticle.cpp
  pkg/common/Gl1_PotentialParticle.hpp
  pkg/dem/Ig2_PP_PP_ScGeom.cpp
  pkg/dem/Ig2_PP_PP_ScGeom.hpp
  pkg/dem/KnKsLaw.cpp
  pkg/dem/KnKsLaw.hpp
  pkg/dem/PotentialParticle.hpp
  pkg/dem/PotentialParticle2AABB.hpp


--
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 'examples/PotentialParticles/cubePPscaled.py'
--- examples/PotentialParticles/cubePPscaled.py	2016-01-19 00:59:38 +0000
+++ examples/PotentialParticles/cubePPscaled.py	2016-01-22 22:27:43 +0000
@@ -40,7 +40,7 @@
 	wire=False
 	color=[0,0,255.0]
 	highlight=False
-	b.shape=PotentialParticle(k=0.2, r=0.05*meanSize, R=1.02*sphereRad, a=[1.0,-1.0,0.0,0.0,0.0,0.0], b=[0.0,0.0,1.0,-1.0,0.0,0.0], c=[0.0,0.0,0.0,0.0,1.0,-1.0], d=[distanceToCentre-rPP,distanceToCentre-rPP,distanceToCentre-rPP,distanceToCentre-rPP,distanceToCentre-rPP,distanceToCentre-rPP],isBoundary=False,color=color,wire=wire,highlight=highlight,minAabb=Vector3(sphereRad,sphereRad,sphereRad),maxAabb=Vector3(sphereRad,sphereRad,sphereRad),maxAabbRotated=Vector3(sphereRad,sphereRad,sphereRad),minAabbRotated=Vector3(sphereRad,sphereRad,sphereRad),AabbMinMax=False)
+	b.shape=PotentialParticle(k=0.2, r=0.05*meanSize, R=1.02*sphereRad, a=[1.0,-1.0,0.0,0.0,0.0,0.0], b=[0.0,0.0,1.0,-1.0,0.0,0.0], c=[0.0,0.0,0.0,0.0,1.0,-1.0], d=[distanceToCentre-rPP,distanceToCentre-rPP,distanceToCentre-rPP,distanceToCentre-rPP,distanceToCentre-rPP,distanceToCentre-rPP],isBoundary=False,color=color,wire=wire,highlight=highlight,minAabb=Vector3(sphereRad,sphereRad,sphereRad),maxAabb=Vector3(sphereRad,sphereRad,sphereRad),maxAabbRotated=Vector3(sphereRad,sphereRad,sphereRad),minAabbRotated=Vector3(sphereRad,sphereRad,sphereRad),AabbMinMax=False, id=count)
 	length=meanSize
   	V= 1.0
   	geomInert=(2./5.)*powderDensity*V*sphereRad**2

=== modified file 'lib/computational-geometry/MarchingCube.cpp'
--- lib/computational-geometry/MarchingCube.cpp	2016-01-19 00:59:38 +0000
+++ lib/computational-geometry/MarchingCube.cpp	2016-01-22 22:27:43 +0000
@@ -8,7 +8,7 @@
 
 #include "MarchingCube.hpp"
 
- 
+
 MarchingCube::MarchingCube( )
 {
 	nbTriangles = 0;
@@ -20,33 +20,32 @@
 }
 
 
-void  MarchingCube::init(int sx, int sy, int sz, const Vector3r& min, const Vector3r& max) 
+void MarchingCube::init(int sx, int sy, int sz, const Vector3r& min, const Vector3r& max)
 {
 	sizeX = sx;
 	sizeY = sy;
 	sizeZ = sz;
 	
-	alpha	= (max-min).cwiseProduct(Vector3r(1.0/(float)sx, 1.0/(float)sy, 1.0/(float)sz));
-	beta	= ((min-max).cwiseProduct(Vector3r(1.0/(Real)sx, 1.0/(Real)sy, 1.0/(Real)sz)))*.5+min;
+	Vector3r alpha = (max-min).cwiseProduct(Vector3r(1.0/(Real)(sx-1), 1.0/(Real)(sy-1), 1.0/(Real)(sz-1)));
 
 	triangles.resize(16*sx*sy*sz);
 	normals.resize(16*sx*sy*sz);
 
 	positions.resize(sizeX);
 	for(int i=0;i<sizeX;i++)
-		positions[i].resize(sizeY); 
+		positions[i].resize(sizeY);
 	for(int i=0;i<sizeX;i++)
 		for(int j=0;j<sizeY;j++)
-			positions[i][j].resize(sizeZ); 
+			positions[i][j].resize(sizeZ);
 
 	for(int i=0;i<sizeX;i++)
 		for(int j=0;j<sizeY;j++)
-			for(int k=0;k<sizeZ;k++) 
-				positions[i][j][k] = alpha.cwiseProduct(Vector3r(i,j,k))+beta;
+			for(int k=0;k<sizeZ;k++)
+				positions[i][j][k] = min + alpha.cwiseProduct(Vector3r(i,j,k));
 }
 
 
-void MarchingCube::resizeScalarField(vector<vector<vector<float> > >& scalarField, int sx, int sy, int sz)
+void MarchingCube::resizeScalarField(vector<vector<vector<Real> > >& scalarField, int sx, int sy, int sz)
 {
 	sizeX = sx;
 	sizeY = sy;
@@ -54,27 +53,27 @@
 	
 	scalarField.resize(sx);
 	for(int i=0;i<sx;i++)
-			scalarField[i].resize(sy); 
+		scalarField[i].resize(sy);
 	for(int i=0;i<sx;i++)
 		for(int j=0;j<sy;j++)
-				scalarField[i][j].resize(sz,0); 
+			scalarField[i][j].resize(sz,0);
 }
 
 
-void MarchingCube::computeTriangulation(const vector<vector<vector<float> > >& scalarField, float iso)  
+void MarchingCube::computeTriangulation(const vector<vector<vector<Real> > >& scalarField, Real iso)
 {
 	isoValue = iso;
 	nbTriangles = 0;
 	for(int i=1;i<sizeX-2;i++)
 		for(int j=1;j<sizeY-2;j++)
-			for(int k=1;k<sizeZ-2;k++) 
+			for(int k=1;k<sizeZ-2;k++)
 				polygonize(scalarField,i,j,k);
 }
 
 
-void MarchingCube::polygonize(const vector<vector<vector<float> > >& scalarField, int x,int y,int z)
+void MarchingCube::polygonize(const vector<vector<vector<Real> > >& scalarField, int x,int y,int z)
 {
-	static vector<float> cellValues(8);
+	static vector<Real> cellValues(8);
 	static vector<Vector3r> cellPositions(8);
 	static vector<Vector3r> vertexList(12);
 	
@@ -88,7 +87,7 @@
 	cellValues[7] = scalarField[x][y+1][z+1];
 	
 	cellPositions[0] = positions[x][y][z];
-	cellPositions[1] = positions[x+1][y][z];	
+	cellPositions[1] = positions[x+1][y][z];
 	cellPositions[2] = positions[x+1][y][z+1];
 	cellPositions[3] = positions[x][y][z+1];
 	cellPositions[4] = positions[x][y+1][z];
@@ -98,24 +97,24 @@
 
 	/* compute index in edgeArray that tells how the surface intersect the cell */
 	int index = 0;
-	if (cellValues[0]>isoValue) 
+	if (cellValues[0]>isoValue)
 		index |= 1;
 	if (cellValues[1]>isoValue)
-		index |= 2; 
-	if (cellValues[2]>isoValue) 
-		index |= 4; 
+		index |= 2;
+	if (cellValues[2]>isoValue)
+		index |= 4;
 	if (cellValues[3]>isoValue)
-		index |= 8; 
-	if (cellValues[4]>isoValue) 
+		index |= 8;
+	if (cellValues[4]>isoValue)
 		index |= 16;
-	if (cellValues[5]>isoValue) 
+	if (cellValues[5]>isoValue)
 		index |= 32;
 	if (cellValues[6]>isoValue)
 		index |= 64;
 	if (cellValues[7]>isoValue)
-		index |= 128; 
+		index |= 128;
 		
-	/* compute position of vertices where the surface interesct the cell*/ 
+	/* compute position of vertices where the surface interesct the cell*/
 	int config = edgeArray[index];
 	if (config == 0) /* the cell is not intersected by surface */
 		return;
@@ -123,47 +122,47 @@
 		interpolate(cellPositions[0], cellPositions[1], cellValues[0], cellValues[1], vertexList[0]);
 	if (config & 2)
 		interpolate(cellPositions[1], cellPositions[2], cellValues[1], cellValues[2], vertexList[1]);
-	if (config & 4) 
+	if (config & 4)
 		interpolate(cellPositions[2], cellPositions[3], cellValues[2], cellValues[3], vertexList[2]);
 	if (config & 8)
-		interpolate(cellPositions[3], cellPositions[0], cellValues[3], cellValues[0], vertexList[3]); 
+		interpolate(cellPositions[3], cellPositions[0], cellValues[3], cellValues[0], vertexList[3]);
 	if (config & 16)
 		interpolate(cellPositions[4], cellPositions[5], cellValues[4], cellValues[5], vertexList[4]);
-	if (config & 32) 
+	if (config & 32)
 		interpolate(cellPositions[5], cellPositions[6], cellValues[5], cellValues[6], vertexList[5]);
 	if (config & 64)
 		interpolate(cellPositions[6], cellPositions[7], cellValues[6], cellValues[7], vertexList[6]);
 	if (config & 128)
-		interpolate(cellPositions[7], cellPositions[4], cellValues[7], cellValues[4], vertexList[7]); 
+		interpolate(cellPositions[7], cellPositions[4], cellValues[7], cellValues[4], vertexList[7]);
 	if (config & 256)
 		interpolate(cellPositions[0], cellPositions[4], cellValues[0], cellValues[4], vertexList[8]);
-	if (config & 512) 
+	if (config & 512)
 		interpolate(cellPositions[1], cellPositions[5], cellValues[1], cellValues[5], vertexList[9]);
-	if (config & 1024) 
+	if (config & 1024)
 		interpolate(cellPositions[2], cellPositions[6], cellValues[2], cellValues[6], vertexList[10]);
 	if (config & 2048)
 		interpolate(cellPositions[3], cellPositions[7], cellValues[3], cellValues[7], vertexList[11]);
-				  
+
 	/* compute triangles and normals*/
 	int offset,i;
 	const int * tri = triTable[index];
 	
-	for (i=0; tri[i]!=-1; ++i) 
-	{ 
+	for (i=0; tri[i]!=-1; ++i)
+	{
 		offset = nbTriangles*3;
 		
 		index = tri[i];
-		triangles[offset]      = vertexList[index];
-		computeNormal(scalarField,x,y,z,offset,index);
-		
-		offset++;
-		index = tri[++i];
-		triangles[offset]    = vertexList[index]; 
-		computeNormal(scalarField,x,y,z,offset,index);
-		
-		offset++;
-		index = tri[++i];
-		triangles[offset]    = vertexList[index];
+		triangles[offset] = vertexList[index];
+		computeNormal(scalarField,x,y,z,offset,index);
+		
+		offset++;
+		index = tri[++i];
+		triangles[offset] = vertexList[index];
+		computeNormal(scalarField,x,y,z,offset,index);
+		
+		offset++;
+		index = tri[++i];
+		triangles[offset] = vertexList[index];
 		computeNormal(scalarField,x,y,z,offset,index);
 		
 		nbTriangles++;
@@ -171,95 +170,95 @@
 }
 
 
-void MarchingCube::computeNormal(const vector<vector<vector<float> > >& scalarField, int x, int y, int z,int offset, int triangleNum)
-{ 
-	switch (triangleNum) 
-	{ 
+void MarchingCube::computeNormal(const vector<vector<vector<Real> > >& scalarField, int x, int y, int z,int offset, int triangleNum)
+{
+	switch (triangleNum)
+	{
 		case 0  : normals[offset] = computeNormalX(scalarField,x, y, z); break;
-		case 1  : normals[offset] = computeNormalZ(scalarField,x+1, y, z); break; 
-		case 2  : normals[offset] = computeNormalX(scalarField,x, y, z+1); break; 
+		case 1  : normals[offset] = computeNormalZ(scalarField,x+1, y, z); break;
+		case 2  : normals[offset] = computeNormalX(scalarField,x, y, z+1); break;
 		case 3  : normals[offset] = computeNormalZ(scalarField,x, y, z); break;
-		case 4  : normals[offset] = computeNormalX(scalarField,x, y+1, z); break; 
-		case 5  : normals[offset] = computeNormalZ(scalarField,x+1, y+1, z); break; 
-		case 6  : normals[offset] = computeNormalX(scalarField,x, y+1, z+1); break; 
-		case 7  : normals[offset] = computeNormalZ(scalarField,x, y+1, z); break; 
-		case 8  : normals[offset] = computeNormalY(scalarField,x, y, z); break; 
-		case 9  : normals[offset] = computeNormalY(scalarField,x+1, y, z); break; 
+		case 4  : normals[offset] = computeNormalX(scalarField,x, y+1, z); break;
+		case 5  : normals[offset] = computeNormalZ(scalarField,x+1, y+1, z); break;
+		case 6  : normals[offset] = computeNormalX(scalarField,x, y+1, z+1); break;
+		case 7  : normals[offset] = computeNormalZ(scalarField,x, y+1, z); break;
+		case 8  : normals[offset] = computeNormalY(scalarField,x, y, z); break;
+		case 9  : normals[offset] = computeNormalY(scalarField,x+1, y, z); break;
 		case 10 : normals[offset] = computeNormalY(scalarField,x+1, y, z+1); break;
 		case 11 : normals[offset] = computeNormalY(scalarField,x, y, z+1); break;
 	}
 }
 
 
-void MarchingCube::interpolate(const Vector3r& vect1, const Vector3r& vect2, float val1, float val2, Vector3r& vect) 
+void MarchingCube::interpolate(const Vector3r& vect1, const Vector3r& vect2, Real val1, Real val2, Vector3r& vect)
 {
-	vect[0] =  interpolateValue(val1, val2, vect1[0], vect2[0]);
-	vect[1] =  interpolateValue(val1, val2, vect1[1], vect2[1]);
-	vect[2] =  interpolateValue(val1, val2, vect1[2], vect2[2]);	
+	vect[0] = interpolateValue(val1, val2, vect1[0], vect2[0]);
+	vect[1] = interpolateValue(val1, val2, vect1[1], vect2[1]);
+	vect[2] = interpolateValue(val1, val2, vect1[2], vect2[2]);
 }
 
 
-float MarchingCube::interpolateValue( float val1, float val2, float val_cible1, float val_cible2) 
+Real MarchingCube::interpolateValue( Real val1, Real val2, Real val_cible1, Real val_cible2)
 {
-	float a = (val_cible2-val_cible1)/(val2-val1);
-	float b = val_cible1-a*val1;
+	Real a = (val_cible2-val_cible1)/(val2-val1);
+	Real b = val_cible1-a*val1;
 	return a*isoValue+b;
-} 
-
-				   
-const Vector3r& MarchingCube::computeNormalX(const vector<vector<vector<float> > >& scalarField, int x, int y, int z)
-{
-	static Vector3r normal;
-	
-	float xyz = scalarField[x][y][z];
-	float xp1yz = scalarField[x+1][y][z];
-	
-	normal[0] =	interpolateValue( xp1yz, xyz, scalarField[x+2][y][z]-xyz, xp1yz-scalarField[x-1][y][z] );
-	normal[1] =	interpolateValue( xyz, xp1yz, scalarField[x][y+1][z], scalarField[x+1][y+1][z] ) - 
-			interpolateValue( xyz, xp1yz, scalarField[x][y-1][z], scalarField[x+1][y-1][z] ); 
-	normal[2] =	interpolateValue( xyz, xp1yz, scalarField[x][y][z+1], scalarField[x+1][y][z+1] ) - 
-			interpolateValue( xyz, xp1yz, scalarField[x][y][z-1], scalarField[x+1][y][z-1] );
-			
-	normal.normalize();
-	return normal;
-}
-
-
-const Vector3r& MarchingCube::computeNormalY(const vector<vector<vector<float> > >& scalarField, int x, int y, int z ) 
-{
-	static Vector3r normal;
-	
-	float xyz = scalarField[x][y][z];
-	float xyp1z = scalarField[x][y+1][z];
-
-	normal[0] =	interpolateValue( xyz, xyp1z, scalarField[x+1][y][z], scalarField[x+1][y+1][z] ) - 
-			interpolateValue( xyz, xyp1z, scalarField[x-1][y][z], scalarField[x-1][y+1][z] ); 	
-	normal[1] =	interpolateValue( xyp1z, xyz, scalarField[x][y+2][z]-xyz, xyp1z-scalarField[x][y-1][z] ); 
-	normal[2] =	interpolateValue( xyz, xyp1z, scalarField[x][y][z+1], scalarField[x][y+1][z+1] ) - 
-			interpolateValue( xyz, xyp1z, scalarField[x][y][z-1], scalarField[x][y+1][z-1] );
-	
-	normal.normalize();
-	return normal;
-} 
-
-              
-const Vector3r& MarchingCube::computeNormalZ(const vector<vector<vector<float> > >& scalarField, int x, int y, int z) 
-{
-	static Vector3r normal;
-
-	float xyz = scalarField[x][y][z];
-	float xyzp1 = scalarField[x][y][z+1];
-	
-	normal[0] = 	interpolateValue( xyz, xyzp1, scalarField[x+1][y][z], scalarField[x+1][y][z+1] ) - 
-			interpolateValue( xyz, xyzp1, scalarField[x-1][y][z], scalarField[x-1][y][z+1] ); 
-
-	normal[1] = 	interpolateValue( xyz, xyzp1, scalarField[x][y+1][z], scalarField[x][y+1][z+1] ) - 
-			interpolateValue( xyz, xyzp1, scalarField[x][y-1][z], scalarField[x][y-1][z+1] ); 
-	normal[2] =	interpolateValue( xyzp1, xyz, scalarField[x][y][z+2]-xyz, xyzp1-scalarField[x][y][z-1] );
-	
-	normal.normalize();
-	return normal;
-} 
+}
+
+
+const Vector3r& MarchingCube::computeNormalX(const vector<vector<vector<Real> > >& scalarField, int x, int y, int z)
+{
+	static Vector3r normal;
+	
+	Real xyz = scalarField[x][y][z];
+	Real xp1yz = scalarField[x+1][y][z];
+	
+	normal[0] = interpolateValue( xp1yz, xyz, scalarField[x+2][y][z]-xyz, xp1yz-scalarField[x-1][y][z] );
+	normal[1] = interpolateValue( xyz, xp1yz, scalarField[x][y+1][z], scalarField[x+1][y+1][z] ) -
+		interpolateValue( xyz, xp1yz, scalarField[x][y-1][z], scalarField[x+1][y-1][z] );
+	normal[2] = interpolateValue( xyz, xp1yz, scalarField[x][y][z+1], scalarField[x+1][y][z+1] ) -
+		interpolateValue( xyz, xp1yz, scalarField[x][y][z-1], scalarField[x+1][y][z-1] );
+		
+	normal.normalize();
+	return normal;
+}
+
+
+const Vector3r& MarchingCube::computeNormalY(const vector<vector<vector<Real> > >& scalarField, int x, int y, int z )
+{
+	static Vector3r normal;
+	
+	Real xyz = scalarField[x][y][z];
+	Real xyp1z = scalarField[x][y+1][z];
+
+	normal[0] = interpolateValue( xyz, xyp1z, scalarField[x+1][y][z], scalarField[x+1][y+1][z] ) -
+		interpolateValue( xyz, xyp1z, scalarField[x-1][y][z], scalarField[x-1][y+1][z] );
+	normal[1] = interpolateValue( xyp1z, xyz, scalarField[x][y+2][z]-xyz, xyp1z-scalarField[x][y-1][z] );
+	normal[2] = interpolateValue( xyz, xyp1z, scalarField[x][y][z+1], scalarField[x][y+1][z+1] ) -
+		interpolateValue( xyz, xyp1z, scalarField[x][y][z-1], scalarField[x][y+1][z-1] );
+	
+	normal.normalize();
+	return normal;
+}
+
+
+const Vector3r& MarchingCube::computeNormalZ(const vector<vector<vector<Real> > >& scalarField, int x, int y, int z)
+{
+	static Vector3r normal;
+
+	Real xyz = scalarField[x][y][z];
+	Real xyzp1 = scalarField[x][y][z+1];
+	
+	normal[0] = interpolateValue( xyz, xyzp1, scalarField[x+1][y][z], scalarField[x+1][y][z+1] ) -
+		interpolateValue( xyz, xyzp1, scalarField[x-1][y][z], scalarField[x-1][y][z+1] );
+
+	normal[1] = interpolateValue( xyz, xyzp1, scalarField[x][y+1][z], scalarField[x][y+1][z+1] ) -
+		interpolateValue( xyz, xyzp1, scalarField[x][y-1][z], scalarField[x][y-1][z+1] );
+	normal[2] = interpolateValue( xyzp1, xyz, scalarField[x][y][z+2]-xyz, xyzp1-scalarField[x][y][z-1] );
+	
+	normal.normalize();
+	return normal;
+}
 
 
 const int MarchingCube::edgeArray[256] = {
@@ -294,7 +293,7 @@
 	0xe90, 0xf99, 0xc93, 0xd9a, 0xa96, 0xb9f, 0x895, 0x99c,
 	0x69c, 0x795, 0x49f, 0x596, 0x29a, 0x393, 0x99 , 0x190,
 	0xf00, 0xe09, 0xd03, 0xc0a, 0xb06, 0xa0f, 0x905, 0x80c,
-	0x70c, 0x605, 0x50f, 0x406, 0x30a, 0x203, 0x109, 0x0   
+	0x70c, 0x605, 0x50f, 0x406, 0x30a, 0x203, 0x109, 0x0
 };
 
 

=== modified file 'lib/computational-geometry/MarchingCube.hpp'
--- lib/computational-geometry/MarchingCube.hpp	2016-01-19 00:59:38 +0000
+++ lib/computational-geometry/MarchingCube.hpp	2016-01-22 22:27:43 +0000
@@ -13,7 +13,7 @@
 #include <vector>
 #include <lib/base/Math.hpp>
 
-class MarchingCube 
+class MarchingCube
 {
 
 /// ATTRIBUTES
@@ -26,37 +26,35 @@
 
 	private : int nbTriangles;
 	public  : int getNbTriangles() { return nbTriangles; }
-  
-	private : Vector3r beta;
-	private : Vector3r alpha;
+
 	private : int sizeX,sizeY,sizeZ;
-	private : float isoValue;
-  
+	private : Real isoValue;
+
 	private : vector<vector<vector<Vector3r> > > positions;
 	private : static const int edgeArray[256];
 	private : static const int triTable[256][16];
-	Vector3r aNormal;	
+	Vector3r aNormal;
 	
 /// PRIVATE METHOD
-  
-	/** triangulate cell  (x,y,z) **/
-	private : void polygonize (const vector<vector<vector<float> > >& scalarField, int x, int y, int z);
+
+	/** triangulate cell (x,y,z) **/
+	private : void polygonize (const vector<vector<vector<Real> > >& scalarField, int x, int y, int z);
 
 	/** compute normals of the triangles previously found with polygonizecalcule les normales des triangles trouver dans la case (x,y,z)
 		@param n : indice of the first triangle to process
 	**/
-  	private : void computeNormal(const vector<vector<vector<float> > >& scalarField, int x, int y, int z,int offset, int triangleNum);
+	private : void computeNormal(const vector<vector<vector<Real> > >& scalarField, int x, int y, int z,int offset, int triangleNum);
 	
 	/** interpolate coordinates of point vect (that is on isosurface) from coordinates of points vect1 et vect2 **/
-	private : void interpolate (const Vector3r&  vect1, const Vector3r& vect2, float val1, float val2,Vector3r& vect);
+	private : void interpolate (const Vector3r& vect1, const Vector3r& vect2, Real val1, Real val2,Vector3r& vect);
 
 	/** Same as interpolate but in 1D **/
-	private : float interpolateValue(float val1, float val2, float val_cible1, float val_cible2);
+	private : Real interpolateValue(Real val1, Real val2, Real val_cible1, Real val_cible2);
 
 	/** Compute normal to vertice or triangle inside cell (x,y,z) **/
-	private : const Vector3r& computeNormalX(const vector<vector<vector<float> > >& scalarField, int x, int y, int z);
-	private : const Vector3r& computeNormalY(const vector<vector<vector<float> > >& scalarField, int x, int y, int z );
-	private : const Vector3r& computeNormalZ(const vector<vector<vector<float> > >& scalarField, int x, int y, int z); 
+	private : const Vector3r& computeNormalX(const vector<vector<vector<Real> > >& scalarField, int x, int y, int z);
+	private : const Vector3r& computeNormalY(const vector<vector<vector<Real> > >& scalarField, int x, int y, int z);
+	private : const Vector3r& computeNormalZ(const vector<vector<vector<Real> > >& scalarField, int x, int y, int z);
 
 /// CONSTRUCTOR/DESTRUCTOR
 
@@ -65,9 +63,9 @@
 
 /// PULIC METHODS
 
-	public  : void computeTriangulation(const vector<vector<vector<float> > >& scalarField, float iso);
+	public  : void computeTriangulation(const vector<vector<vector<Real> > >& scalarField, Real iso);
 
 	public  : void init(int sx, int sy, int sz, const Vector3r& min, const Vector3r& max);
 
-	public  : void resizeScalarField(vector<vector<vector<float> > >& scalarField, int sx, int sy, int sz);
+	public  : void resizeScalarField(vector<vector<vector<Real> > >& scalarField, int sx, int sy, int sz);
 };

=== modified file 'pkg/common/Gl1_PotentialParticle.cpp'
--- pkg/common/Gl1_PotentialParticle.cpp	2016-01-19 00:59:38 +0000
+++ pkg/common/Gl1_PotentialParticle.cpp	2016-01-22 22:27:43 +0000
@@ -55,43 +55,32 @@
 #include <vtkIntArray.h>
 
 #ifdef YADE_OPENGL
-void Gl1_PotentialParticle::calcMinMax(const shared_ptr<Shape>& cm) {
-	PotentialParticle* pp = static_cast<PotentialParticle*>(cm.get());
-	int planeNo = pp->d.size();
-	Real maxD = pp->d[0];
+void Gl1_PotentialParticle::calcMinMax(const PotentialParticle& pp) {
+	int planeNo = pp.d.size();
+	Real maxD = pp.d[0];
 
 	for (int i=0; i<planeNo; ++i) {
-		if (pp->d[i] > maxD) {
-			maxD = pp->d[i];
+		if (pp.d[i] > maxD) {
+			maxD = pp.d[i];
 		}
 	}
 
-	//Real R = pp->R;
-	min =-1.1*pp->minAabb; // 1.5*Vector3r(-maxTip,-maxTip,-maxTip);
-	max = 1.1*pp->maxAabb; //-1.0*min;
+	min = -aabbEnlargeFactor*pp.minAabb;
+	max =  aabbEnlargeFactor*pp.maxAabb;
 
-	float dx = (max[0]-min[0])/((float)(sizeX));
-	float dy = (max[1]-min[1])/((float)(sizeY));
-	float dz = (max[2]-min[2])/((float)(sizeZ));
+	Real dx = (max[0]-min[0])/((Real)(sizeX-1));
+	Real dy = (max[1]-min[1])/((Real)(sizeY-1));
+	Real dz = (max[2]-min[2])/((Real)(sizeZ-1));
 
 	isoStep=Vector3r(dx,dy,dz);
 }
 
 
-void Gl1_PotentialParticle::generateScalarField(const shared_ptr<Shape>& cm) {
-	for(int i=0; i<sizeX; i++) {
-		for(int j=0; j<sizeY; j++) {
-			for(int k=0; k<sizeZ; k++)
-			{
-				scalarField[i][j][k] = 0.0;
-			}
-		}
-	}
-
+void Gl1_PotentialParticle::generateScalarField(const PotentialParticle& pp) {
 	for(int i=0; i<sizeX; i++) {
 		for(int j=0; j<sizeY; j++) {
 			for(int k=0; k<sizeZ; k++) {
-				scalarField[i][j][k] = evaluateF(cm,  min[0]+ double(i)*isoStep[0],  min[1]+ double(j)*isoStep[1],  min[2]+double(k)*isoStep[2]);//
+				scalarField[i][j][k] = evaluateF(pp,  min[0]+ Real(i)*isoStep[0],  min[1]+ Real(j)*isoStep[1],  min[2]+Real(k)*isoStep[2]);//
 			}
 		}
 	}
@@ -101,13 +90,10 @@
 
 vector<Gl1_PotentialParticle::scalarF> Gl1_PotentialParticle::SF;
 int Gl1_PotentialParticle::sizeX, Gl1_PotentialParticle::sizeY, Gl1_PotentialParticle::sizeZ;
+Real Gl1_PotentialParticle::aabbEnlargeFactor;
 bool Gl1_PotentialParticle::store;
 bool Gl1_PotentialParticle::initialized;
 
-void Gl1_PotentialParticle::clearMemory() {
-	SF.clear();
-}
-
 
 void Gl1_PotentialParticle::go( const shared_ptr<Shape>& cm, const shared_ptr<State>& state ,bool wire2, const GLViewInfo&) {
 
@@ -125,12 +111,13 @@
 	if(initialized == false ) {
 		FOREACH(const shared_ptr<Body>& b, *scene->bodies) {
 			if (!b) continue;
-			const shared_ptr<Shape>&  cmbody=b->shape;
-			calcMinMax(cmbody);
+			PotentialParticle* cmbody = dynamic_cast<PotentialParticle*>(b->shape.get());
+			if (!cmbody) continue;
+			calcMinMax(*cmbody);
 			mc.init(sizeX,sizeY,sizeZ,min,max);
 			mc.resizeScalarField(scalarField,sizeX,sizeY,sizeZ);
 			SF.push_back(scalarF());
-			generateScalarField(cmbody);
+			generateScalarField(*cmbody);
 			mc.computeTriangulation(scalarField,0.0);
 			SF[b->id].triangles = mc.getTriangles();
 			SF[b->id].normals = mc.getNormals();
@@ -144,23 +131,14 @@
 		initialized = true;
 	}
 
-
-	//if(std::isnan(shapeId)==true){return;}
-
-	calcMinMax(cm);
-	mc.init(sizeX,sizeY,sizeZ,min,max);
-	mc.resizeScalarField(scalarField,sizeX,sizeY,sizeZ);
-
-
-
 	// FIXME : check that : one of those 2 lines are useless
 	glMaterialv(GL_FRONT, GL_AMBIENT_AND_DIFFUSE, Vector3r(cm->color[0],cm->color[1],cm->color[2]));
 	glColor3v(cm->color);
 
 
-	vector<Vector3r>& triangles 	= SF[shapeId].triangles; //mc.getTriangles();
-	int nbTriangles			= SF[shapeId].nbTriangles; // //mc.getNbTriangles();
-	vector<Vector3r>& normals 	= SF[shapeId].normals; //mc.getNormals();
+	const vector<Vector3r>& triangles = SF[shapeId].triangles; //mc.getTriangles();
+	int nbTriangles = SF[shapeId].nbTriangles; // //mc.getNbTriangles();
+	const vector<Vector3r>& normals = SF[shapeId].normals; //mc.getNormals();
 
 	glDisable(GL_CULL_FACE);
 	glEnable(GL_LIGHTING); // 2D
@@ -182,27 +160,25 @@
 
 
 
-double Gl1_PotentialParticle::evaluateF(const shared_ptr<Shape>& cm, double x, double y, double z) {
-
-	PotentialParticle* pp = static_cast<PotentialParticle*>(cm.get());
-	Real k = pp->k;
-	Real r = pp->r;
-	Real R = pp->R;
-
-
-	int planeNo = pp->a.size();
-
-	vector<double>a;
-	vector<double>b;
-	vector<double>c;
-	vector<double>d;
-	vector<double>p;
+Real Gl1_PotentialParticle::evaluateF(const PotentialParticle& pp, Real x, Real y, Real z) {
+	Real k = pp.k;
+	Real r = pp.r;
+	Real R = pp.R;
+
+
+	int planeNo = pp.a.size();
+
+	vector<Real>a;
+	vector<Real>b;
+	vector<Real>c;
+	vector<Real>d;
+	vector<Real>p;
 	Real pSum3 = 0.0;
 	for (int i=0; i<planeNo; i++) {
-		a.push_back(pp->a[i]);
-		b.push_back(pp->b[i]);
-		c.push_back(pp->c[i]);
-		d.push_back(pp->d[i]);
+		a.push_back(pp.a[i]);
+		b.push_back(pp.b[i]);
+		c.push_back(pp.c[i]);
+		d.push_back(pp.d[i]);
 		Real plane = a[i]*x + b[i]*y + c[i]*z - d[i];
 		if (plane<pow(10,-15)) {
 			plane = 0.0;
@@ -236,10 +212,10 @@
 }
 
 // Evaluate function
-double ImpFunc::FunctionValue(double x[3]) {
+Real ImpFunc::FunctionValue(Real x[3]) {
 	int planeNo = a.size();
-	vector<double>p;
-	double pSum2 = 0.0;
+	vector<Real>p;
+	Real pSum2 = 0.0;
 	if (!clump) {
 		Eigen::Vector3d xori(x[0],x[1],x[2]);
 		Eigen::Vector3d xlocal = rotationMatrix*xori;
@@ -250,14 +226,14 @@
 		//x[0]=xlocal[0]; x[1]=xlocal[1]; x[2]=xlocal[2];
 
 		for (int i=0; i<planeNo; i++) {
-			double plane = a[i]*xlocal[0] + b[i]*xlocal[1] + c[i]*xlocal[2] - d[i];
+			Real plane = a[i]*xlocal[0] + b[i]*xlocal[1] + c[i]*xlocal[2] - d[i];
 			if (plane<pow(10,-15)) {
 				plane = 0.0;
 			}
 			p.push_back(plane);
 			pSum2 += pow(p[i],2);
 		}
-		double sphere  = (  pow(xlocal[0],2) + pow(xlocal[1],2) + pow(xlocal[2],2) ) ;
+		Real sphere  = (  pow(xlocal[0],2) + pow(xlocal[1],2) + pow(xlocal[2],2) ) ;
 		Real f = (1.0-k)*(pSum2/pow(r,2) - 1.0)+k*(sphere/pow(R,2)-1.0);
 		return f;
 	} else {
@@ -272,14 +248,14 @@
 		//x[0]=xlocal[0]; x[1]=xlocal[1]; x[2]=xlocal[2];
 
 		for (int i=0; i<planeNo; i++) {
-			double plane = a[i]*xlocal[0] + b[i]*xlocal[1] + c[i]*xlocal[2] - d[i];
+			Real plane = a[i]*xlocal[0] + b[i]*xlocal[1] + c[i]*xlocal[2] - d[i];
 			if (plane<pow(10,-15)) {
 				plane = 0.0;
 			}
 			p.push_back(plane);
 			pSum2 += pow(p[i],2);
 		}
-		double sphere  = (  pow(xlocal[0],2) + pow(xlocal[1],2) + pow(xlocal[2],2) ) ;
+		Real sphere  = (  pow(xlocal[0],2) + pow(xlocal[1],2) + pow(xlocal[2],2) ) ;
 		Real f = (1.0-k)*(pSum2/pow(r,2) - 1.0)+k*(sphere/pow(R,2)-1.0);
 		return f;
 		// return 0;
@@ -392,14 +368,12 @@
 		vtkSmartPointer<vtkSampleFunction> sample = vtkSampleFunction::New();
 		sample->SetImplicitFunction(function);
 
-		//double xmin = -pb->halfSize.x(); double xmax = pb->halfSize.x(); double ymin = -pb->halfSize.y(); double ymax=pb->halfSize.y(); double zmin=-pb->halfSize.z(); double zmax=pb->halfSize.z();
-		//double xmin = -value; double xmax = value; double ymin = -value; double ymax=value; double zmin=-value; double zmax=value;
-		double xmin = -std::max(pb->minAabb.x(),pb->maxAabb.x());
-		double xmax = -xmin;
-		double ymin = -std::max(pb->minAabb.y(),pb->maxAabb.y());
-		double ymax=-ymin;
-		double zmin=-std::max(pb->minAabb.z(),pb->maxAabb.z());
-		double zmax=-zmin;
+		Real xmin = -std::max(pb->minAabb.x(),pb->maxAabb.x());
+		Real xmax = -xmin;
+		Real ymin = -std::max(pb->minAabb.y(),pb->maxAabb.y());
+		Real ymax=-ymin;
+		Real zmin=-std::max(pb->minAabb.z(),pb->maxAabb.z());
+		Real zmax=-zmin;
 		if(twoDimension==true) {
 			ymax = 0.0;
 			ymin = 0.0;
@@ -409,13 +383,13 @@
 		int sampleXno = sampleX;
 		int sampleYno = sampleY;
 		int sampleZno = sampleZ;
-		if(fabs(xmax-xmin)/static_cast<double>(sampleX) > maxDimension) {
+		if(fabs(xmax-xmin)/static_cast<Real>(sampleX) > maxDimension) {
 			sampleXno = static_cast<int>(fabs(xmax-xmin)/maxDimension);
 		}
-		if(fabs(ymax-ymin)/static_cast<double>(sampleY) > maxDimension) {
+		if(fabs(ymax-ymin)/static_cast<Real>(sampleY) > maxDimension) {
 			sampleYno = static_cast<int>(fabs(ymax-ymin)/maxDimension);
 		}
-		if(fabs(zmax-zmin)/static_cast<double>(sampleZ) > maxDimension) {
+		if(fabs(zmax-zmin)/static_cast<Real>(sampleZ) > maxDimension) {
 			sampleZno = static_cast<int>(fabs(zmax-zmin)/maxDimension);
 		}
 		if(twoDimension==true) {

=== modified file 'pkg/common/Gl1_PotentialParticle.hpp'
--- pkg/common/Gl1_PotentialParticle.hpp	2016-01-19 00:59:38 +0000
+++ pkg/common/Gl1_PotentialParticle.hpp	2016-01-22 22:27:43 +0000
@@ -50,27 +50,27 @@
 		// Description
 		// Create a new function
 		static ImpFunc * New(void);
-		vector<double>a;
-		vector<double>b;
-		vector<double>c;
-		vector<double>d;
-		double k;
-		double r;
-		double R;
+		vector<Real>a;
+		vector<Real>b;
+		vector<Real>c;
+		vector<Real>d;
+		Real k;
+		Real r;
+		Real R;
 		Eigen::Matrix3d rotationMatrix;
 		bool clump;
-		double clumpMemberCentreX;
-		double clumpMemberCentreY;
-		double clumpMemberCentreZ;
+		Real clumpMemberCentreX;
+		Real clumpMemberCentreY;
+		Real clumpMemberCentreZ;
 		// Description
 		// Evaluate function
-		double FunctionValue(double x[3]);
-		double EvaluateFunction(double x[3]) {
+		Real FunctionValue(Real x[3]);
+		Real EvaluateFunction(Real x[3]) {
 			//return this->vtkImplicitFunction::EvaluateFunction(x);
 			return FunctionValue(x);
 		};
 
-		double EvaluateFunction(double x, double y, double z) {
+		Real EvaluateFunction(Real x, Real y, Real z) {
 			return this->vtkImplicitFunction::EvaluateFunction(x, y, z);
 		};
 
@@ -79,7 +79,7 @@
 
 		// Description
 		// Evaluate gradient for function
-		void EvaluateGradient(double x[3], double n[3]) { };
+		void EvaluateGradient(Real x[3], Real n[3]) { };
 
 		// If you need to set parameters, add methods here
 
@@ -97,13 +97,11 @@
 	private :
 		MarchingCube mc;
 		Vector3r min,max;
-		vector<vector<vector<float > > > 	scalarField,weights;
-		void generateScalarField(const shared_ptr<Shape>& cm);
-		void calcMinMax(const shared_ptr<Shape>& cm);
-		float oldIsoValue,oldIsoSec,oldIsoThick;
+		vector<vector<vector<Real > > > scalarField,weights;
+		void generateScalarField(const PotentialParticle& pp);
+		void calcMinMax(const PotentialParticle& pp);
+		Real oldIsoValue,oldIsoSec,oldIsoThick;
 		Vector3r isoStep;
-
-	public :
 		struct Leaf {
 			Vector3r centre;
 			Leaf(Vector3r pos) {
@@ -114,21 +112,24 @@
 			}
 		};
 		struct scalarF {
-			vector<vector<vector<float > > > scalarField2;
+			vector<vector<vector<Real > > > scalarField2;
 			vector<Vector3r> triangles;
 			vector<Vector3r> normals;
 			int nbTriangles;
 		};
+		Real evaluateF(const PotentialParticle& pp, Real x, Real y, Real z);
+		static vector<scalarF> SF ;
+
+	public :
 		virtual void go(const shared_ptr<Shape>&, const shared_ptr<State>&,bool,const GLViewInfo&);
-		double evaluateF(const shared_ptr<Shape>& cm, double x, double y, double z);
-		static vector<scalarF> SF ;
-		void clearMemory();
+
 		YADE_CLASS_BASE_DOC_STATICATTRS(Gl1_PotentialParticle,GlShapeFunctor,"Renders :yref:`PotentialParticle` object",
 			((int,sizeX,10,,"Number of divisions in the x direction for triangulation"))
 			((int,sizeY,10,,"Number of divisions in the y direction for triangulation"))
 			((int,sizeZ,10,,"Number of divisions in the z direction for triangulation"))
 			((bool,store,false,,"store computed triangulation or not"))
 			((bool,initialized,false,,"if triangulation is initialized"))
+			((Real,aabbEnlargeFactor,1.3,,"some factor for displaying algorithm, try different value if you have problems with displaying"))
 		);
 		RENDERS(PotentialParticle);
 };
@@ -146,7 +147,7 @@
 			((int,sampleX,30,,"Number of divisions in the x direction for triangulation"))
 			((int,sampleY,30,,"Number of divisions in the y direction for triangulation"))
 			((int,sampleZ,30,,"Number of divisions in the z direction for triangulation"))
-			((double,maxDimension,30,,"max dimension"))
+			((Real,maxDimension,30,,"max dimension"))
 			((bool,twoDimension,false,,"2D or not"))
 			((bool,REC_INTERACTION,false,,"contact point and forces"))
 			((bool,REC_COLORS,false,,"colors"))

=== modified file 'pkg/dem/Ig2_PP_PP_ScGeom.cpp'
--- pkg/dem/Ig2_PP_PP_ScGeom.cpp	2016-01-19 00:59:38 +0000
+++ pkg/dem/Ig2_PP_PP_ScGeom.cpp	2016-01-22 22:27:43 +0000
@@ -53,12 +53,11 @@
 	bool hasGeom = false;
 	Vector3r contactPt(0,0,0);
 	shared_ptr<ScGeom> scm;
-	shared_ptr<KnKsPhys> phys;
-
-
-	double stepBisection = 0.001*std::min(s1->R,s2->R);
+
+
+	Real stepBisection = 0.001*std::min(s1->R,s2->R);
 	if(stepBisection<pow(10,-6)) {
-		std::cout<<"R1: "<<s1->R<<", R2: "<<s2->R<<", stepBisection: "<<stepBisection<<", id1: "<<c->getId1()<<", id2: "<<c->getId2()<<endl;
+		//std::cout<<"R1: "<<s1->R<<", R2: "<<s2->R<<", stepBisection: "<<stepBisection<<", id1: "<<c->getId1()<<", id2: "<<c->getId2()<<endl;
 	}
 
 	bool contact = false;
@@ -80,7 +79,7 @@
 			stepBisection = 0.5*scm->penetrationDepth;
 		}
 		if(stepBisection<pow(10,-6)) {
-			std::cout<<"stepBisection: "<<stepBisection<<", penetrationDepth: "<<scm->penetrationDepth<<endl;
+			//std::cout<<"stepBisection: "<<stepBisection<<", penetrationDepth: "<<scm->penetrationDepth<<endl;
 		}
 		contactPt = scm->contactPoint;
 	} else {
@@ -90,13 +89,6 @@
 
 	}
 
-	bool hasPhys=false;
-	if(c->phys) {
-		phys=YADE_PTR_CAST<KnKsPhys>(c->phys);
-		hasPhys=true;
-	}
-
-
 	converge = true;
 	fA= evaluatePP(cm1,state1, contactPt);
 	fB = evaluatePP(cm2,state2, contactPt);
@@ -126,7 +118,7 @@
 	fB = evaluatePP(cm2,state2, contactPt);
 
 	if (fA*fB<0.0) {
-		std::cout<<"fA: "<<fA<<", fB: "<<fB<<endl;
+		//std::cout<<"fA: "<<fA<<", fB: "<<fB<<endl;
 	}
 
 //std::cout<<"converge: "<<converge<<", fA: "<<fA<<", fB: "<<fB<<endl;
@@ -139,9 +131,9 @@
 		contact = false;
 		contactPt = 0.5*(state1.pos+state2.pos);
 	}
-	//////////////////////////////////////////////////////////* PASS VARIABLES TO ScGeom and Phys Functor */////////////////////////////////////////////////////////////
+	//////////////////////////////////////////////////////////* PASS VARIABLES TO ScGeom Functor */////////////////////////////////////////////////////////////
 	//* 1. Get overlap												 						 *//
-	//* 2. Get information on active planes.  If active planes are not the same as the previous, get new physical parameters.  Otherwise keep the same parameters 	 *//
+	//* 2. Get information on active planes.
 	////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 	if (contact == true || c->isReal() || force) {
 		if (contact == true) {
@@ -153,14 +145,6 @@
 			avgNormal = (normalP1 - normalP2);
 			avgNormal.normalize();
 
-			if(hasPhys == true) {
-				//bool calJointLength = phys->calJointLength;
-				//int smallerID = 1;
-				bool twoD = phys->twoDimension;
-				if (twoD == true) {
-					phys->jointLength = 1.0;
-				}
-			}
 			if(s1->fixedNormal==true) {
 				avgNormal = s1->boundaryNormal;
 			}
@@ -181,7 +165,7 @@
 			scm->contactPoint = contactPt;
 			scm->penetrationDepth=penetrationDepth;
 			if(isnan(avgNormal.norm())) {
-				std::cout<<"avgNormal: "<<avgNormal<<endl;
+				//std::cout<<"avgNormal: "<<avgNormal<<endl;
 			}
 			scm->normal = avgNormal;
 
@@ -227,7 +211,7 @@
 	Real fb = evaluatePP(cm1,state1, bracketB); //evaluateFNoSphere(cm1,state1, bracketB); //
 
 	if(fa*fb > 0.00001) {
-		std::cout<<"fa: "<<fa<<", fb: "<<fb<<endl;
+		//std::cout<<"fa: "<<fa<<", fb: "<<fb<<endl;
 	}
 	//if(fabs(fa)<fabs(fb)){bracketRange *= -1.0; Vector3r temp = bracketA; bracketA= bracketB; bracketB = temp;}
 	Real fc = 0.0;
@@ -323,7 +307,7 @@
 
 		counter++;
 		if(counter==10000) {
-			std::cout<<"counter: "<<counter<<", m.norm: "<<m<<", fb: "<<fb<<endl;
+			//std::cout<<"counter: "<<counter<<", m.norm: "<<m<<", fb: "<<fb<<endl;
 		}
 	} while(1);
 	//}while( m.norm() > tol && fabs(fb) > pow(10,-13) );
@@ -332,7 +316,7 @@
 
 
 /* Routine to get value of function (constraint) at a particular position */
-double Ig2_PP_PP_ScGeom::evaluatePP(const shared_ptr<Shape>& cm1, const State& state1, const Vector3r newTrial) {
+Real Ig2_PP_PP_ScGeom::evaluatePP(const shared_ptr<Shape>& cm1, const State& state1, const Vector3r newTrial) {
 
 	PotentialParticle *s1=static_cast<PotentialParticle*>(cm1.get());
 	///////////////////Transforming trial values to local frame of particles//////////////////
@@ -379,7 +363,7 @@
 
 ////////////////////////////// assembling potential planes particle 1//////////////////////////////
 	int planeNo = s1->a.size();
-	vector<double>p;
+	vector<Real>p;
 	Real pSum2 = 0.0;
 	for (int i=0; i<planeNo; i++) {
 		Real plane = s1->a[i]*x + s1->b[i]*y + s1->c[i]*z -s1-> d[i];
@@ -441,7 +425,7 @@
 	Real Fdz = fdx * Q1(0,2) + fdy*Q1(1,2) + fdz*Q1(2,2);
 
 	if (isnan(Fdx) == true || isnan(Fdy) == true || isnan(Fdz)==true) {
-		std::cout<<"Q1(0,0): "<<Q1(0,0)<<","<<Q1(0,1)<<","<<Q1(0,2)<<","<<Q1(1,0)<<","<<Q1(1,1)<<","<<Q1(1,2)<<","<<Q1(2,0)<<","<<Q1(2,1)<<","<<Q1(2,2)<<", q:"<<q0<<","<<q1<<","<<q2<<","<<q3<<", fd: "<<fdx<<","<<fdy<<","<<fdz<<endl;
+		//std::cout<<"Q1(0,0): "<<Q1(0,0)<<","<<Q1(0,1)<<","<<Q1(0,2)<<","<<Q1(1,0)<<","<<Q1(1,1)<<","<<Q1(1,2)<<","<<Q1(2,0)<<","<<Q1(2,1)<<","<<Q1(2,2)<<", q:"<<q0<<","<<q1<<","<<q2<<","<<q3<<", fd: "<<fdx<<","<<fdy<<","<<fdz<<endl;
 	}
 
 	return Vector3r(Fdx,Fdy,Fdz);
@@ -458,20 +442,20 @@
 
 
 	/* Parameters for particles A and B */
-	double rA = s1->r;
-	double kA = s1->k;
-	double RA = s1->R;
-	double rB = s2->r;
-	double kB = s2->k;
-	double RB = s2->R;
+	Real rA = s1->r;
+	Real kA = s1->k;
+	Real RA = s1->R;
+	Real rB = s2->r;
+	Real kB = s2->k;
+	Real RB = s2->R;
 	int planeNoA = s1->a.size();
 	int planeNoB = s2->a.size();
 
 	/* Variables to keep things neat */
-	double ksA = RA/sqrt(kA);
-	double kpA = rA/sqrt(1.0 - kA);
-	double ksB = RB/sqrt(kB);
-	double kpB = rB/sqrt(1.0 - kB);
+	Real ksA = RA/sqrt(kA);
+	Real kpA = rA/sqrt(1.0 - kA);
+	Real ksB = RB/sqrt(kB);
+	Real kpB = rB/sqrt(1.0 - kB);
 	int NUMCON = 3  + 1+ planeNoA + planeNoB;
 	int NUMVAR = 6 + 2  + planeNoA + planeNoB;
 
@@ -485,7 +469,7 @@
 		bkc[4+i] = MSK_BK_UP;
 	};
 
-	double blc[NUMCON];
+	Real blc[NUMCON];
 	blc[0] = state2.pos.x() - state1.pos.x();
 	blc[1] = state2.pos.y() - state1.pos.y();
 	blc[2] = state2.pos.z() - state1.pos.z();
@@ -497,7 +481,7 @@
 		blc[4+planeNoA+i] = -MSK_INFINITY;
 	};
 
-	double buc[NUMCON];
+	Real buc[NUMCON];
 	buc[0] = state2.pos.x() - state1.pos.x();
 	buc[1] = state2.pos.y() - state1.pos.y();
 	buc[2] = state2.pos.z() - state1.pos.z();
@@ -524,7 +508,7 @@
 	};
 
 
-	double blx[NUMVAR];
+	Real blx[NUMVAR];
 	blx[0] = -MSK_INFINITY;
 	blx[1] = -MSK_INFINITY;
 	blx[2] = -MSK_INFINITY;
@@ -537,7 +521,7 @@
 		blx[8+i] = -MSK_INFINITY;
 	};
 
-	double bux[NUMVAR];
+	Real bux[NUMVAR];
 	bux[0] = +MSK_INFINITY;
 	bux[1] = +MSK_INFINITY;
 	bux[2] = +MSK_INFINITY;
@@ -550,7 +534,7 @@
 		bux[8+i] = +MSK_INFINITY;
 	};
 
-	double c[NUMVAR];
+	Real c[NUMVAR];
 	c[0] = 0.0;
 	c[1] = 0.0;
 	c[2] = 0.0;
@@ -563,7 +547,7 @@
 		c[8+i] = 0.0;
 	};
 
-	vector<double> aval;
+	vector<Real> aval;
 	vector<MSKintt> aptrb;
 	vector<MSKintt> aptre;
 	vector<MSKidxt> asub;
@@ -778,7 +762,7 @@
 	totalCount += planeNoB;
 
 	MSKidxt     i,j,csubA[1+ 3 + planeNoA], csubB[1+ 3  + planeNoB] ;
-	double      xx[NUMVAR];
+	Real      xx[NUMVAR];
 	MSKenv_t    & env=mosekEnv;
 	MSKtask_t   task;
 	MSKrescodee  & r=mosekTaskEnv;
@@ -974,12 +958,12 @@
 				}
 
 
-				double xlocalA = xx[0]*ksA;
-				double ylocalA = xx[1]*ksA;
-				double zlocalA = xx[2]*ksA;
-				double xlocalB = xx[3]*ksB;
-				double ylocalB = xx[4]*ksB;
-				double zlocalB = xx[5]*ksB;
+				Real xlocalA = xx[0]*ksA;
+				Real ylocalA = xx[1]*ksA;
+				Real zlocalA = xx[2]*ksA;
+				Real xlocalB = xx[3]*ksB;
+				Real ylocalB = xx[4]*ksB;
+				Real zlocalB = xx[5]*ksB;
 				Vector3r localA = Vector3r(xlocalA,ylocalA,zlocalA);
 				Vector3r localB = Vector3r(xlocalB,ylocalB,zlocalB);
 				xGlobal = state1.ori*localA + state1.pos;
@@ -989,7 +973,7 @@
 			}
 			else
 			{
-				printf("Error while optimizing.\n");
+				LOG_ERROR("Error while optimizing.\n");
 			}
 		}
 
@@ -999,11 +983,11 @@
 			char symname[MSK_MAX_STR_LEN];
 			char desc[MSK_MAX_STR_LEN];
 
-			printf("An error occurred while optimizing.\n");
+			LOG_ERROR("An error occurred while optimizing.\n");
 			MSK_getcodedesc (r,
 			                 symname,
 			                 desc);
-			printf("Error %s - '%s'\n",symname,desc);
+			LOG_ERROR("Error %s - '%s'\n",symname,desc);
 		}
 	}
 	/* Delete the task and the associated data. */
@@ -1042,7 +1026,7 @@
 		counter++;
 		if (counter == 50000 ) {
 			//LOG_WARN("Initial point searching exceeded 500 iterations!");
-			std::cout<<"ptonparticle2 search exceeded 50000 iterations! step:"<<step<<endl;
+			//std::cout<<"ptonparticle2 search exceeded 50000 iterations! step:"<<step<<endl;
 		}
 
 	} while(Mathr::Sign(fprevious)*Mathr::Sign(f)*1.0> 0.0 );
@@ -1065,12 +1049,12 @@
 	int totalIter = 0;
 
 	/* Parameters for particles A and B */
-	double rA = s1->r;
-	double kA = s1->k;
-	double RA = s1->R;
-	double rB = s2->r;
-	double kB = s2->k;
-	double RB = s2->R;
+	Real rA = s1->r;
+	Real kA = s1->k;
+	Real RA = s1->R;
+	Real rB = s2->r;
+	Real kB = s2->k;
+	Real RB = s2->R;
 	int planeNoA = s1->a.size();
 	int planeNoB = s2->a.size();
 	int varNo = 3+1+planeNoA+planeNoB;
@@ -1090,16 +1074,16 @@
 	int blas1planeNoA = std::max(1,planeNoA);
 	int blas1planeNoB = std::max(1,planeNoB);
 	int blas1planeNoAB = std::max(1,planeNoAB);
-	double blas0 = 0.0;
-	double blas1 = 1.0;
-	double blasNeg1 = -1.0;
+	Real blas0 = 0.0;
+	Real blas1 = 1.0;
+	Real blasNeg1 = -1.0;
 
-	double blasQA[9];
-	double blasQB[9];
-	double blasPosA[3];
-	double blasPosB[3];
-	double blasContactPt[3];
-	double blasC[varNo];
+	Real blasQA[9];
+	Real blasQB[9];
+	Real blasPosA[3];
+	Real blasPosB[3];
+	Real blasContactPt[3];
+	Real blasC[varNo];
 	for (int i=0; i<varNo; i++) {
 		blasC[i] = 0.0;
 	}
@@ -1122,16 +1106,16 @@
 //}
 
 	/* Variables to keep things neat */
-	double kAs = sqrt(kA)/RA;
-	double kAp = sqrt(1.0 - kA)/rA;
-	double kBs = sqrt(kB)/RB;
-	double kBp = sqrt(1.0 - kB)/rB;
+	Real kAs = sqrt(kA)/RA;
+	Real kAp = sqrt(1.0 - kA)/rA;
+	Real kBs = sqrt(kB)/RB;
+	Real kBp = sqrt(1.0 - kB)/rB;
 
 	/* penalty */
-	double t = 1.0;
-	double mu=10.0;
-	double planePert = 0.1*rA;
-	double sPert = 1.0; //+ 10.0*planePert*(planeNoA+planeNoB)/(rA*rA);
+	Real t = 1.0;
+	Real mu=10.0;
+	Real planePert = 0.1*rA;
+	Real sPert = 1.0; //+ 10.0*planePert*(planeNoA+planeNoB)/(rA*rA);
 	if (warmstart == true) {
 		t = 0.01;
 		mu= 50.0;
@@ -1139,22 +1123,22 @@
 		sPert = 0.01; ///* pow(10,-1)+ */ sqrt(planePert*planePert*(planeNoA+planeNoB)/(rA*rA));
 	}
 	/* s */
-	double s = 0.0;
-	double m=2.0;
-	double NTTOL = pow(10,-8);
-	double tol = accuracyTol/*pow(10,-4)* RA*pow(10,-6)*/;
-	double gap =0.0;
+	Real s = 0.0;
+	Real m=2.0;
+	Real NTTOL = pow(10,-8);
+	Real tol = accuracyTol/*pow(10,-4)* RA*pow(10,-6)*/;
+	Real gap =0.0;
 	/* x */
-	double blasX[varNo];
-	double blasNewX[varNo];
+	Real blasX[varNo];
+	Real blasNewX[varNo];
 	blasX[0] = contactPt[0];
 	blasX[1] = contactPt[1];
 	blasX[2] = contactPt[2];
 
 	//////////////////// evaluate fA and fB to initialize ////////////////////////////////
 	/* fA */
-	double blasTempP1[3];
-	double blasLocalP1[3];
+	Real blasTempP1[3];
+	Real blasLocalP1[3];
 	for(int i=0; i<3; i++) {
 		blasTempP1[i] = blasContactPt[i] - blasPosA[i];
 	}
@@ -1165,8 +1149,8 @@
 	int  blasK = 3;
 	//int blasLDA = 3;
 	int  blasLDB = 3;
-	double blasAlpha = 1.0;
-	double blasBeta = 0.0;
+	Real blasAlpha = 1.0;
+	Real blasBeta = 0.0;
 	//int blasLDC = 3;
 	int incx=1;
 	int incy=1;
@@ -1178,13 +1162,13 @@
 	/* P1Q */ //Eigen::MatrixXd P1 = Eigen::MatrixXd::Zero(planeNoA,3);
 	/*d1*/    //Eigen::MatrixXd d1 = Eigen::MatrixXd::Zero(planeNoA,1);
 
-	double blasP1[planeNoA*3];
-	double blasD1[planeNoA];
-	double blasP1Q[planeNoA*3];
-	double pertSumA2 = 0.0;
+	Real blasP1[planeNoA*3];
+	Real blasD1[planeNoA];
+	Real blasP1Q[planeNoA*3];
+	Real pertSumA2 = 0.0;
 
 	for (int i=0; i<planeNoA; i++) {
-		double plane = s1->a[i]*blasLocalP1[0] + s1->b[i]*blasLocalP1[1] + s1->c[i]*blasLocalP1[2] - s1->d[i];
+		Real plane = s1->a[i]*blasLocalP1[0] + s1->b[i]*blasLocalP1[1] + s1->c[i]*blasLocalP1[2] - s1->d[i];
 		if (plane<pow(10,-15)) {
 			plane = 0.0;
 			blasX[4+i] = plane + planePert;
@@ -1207,8 +1191,8 @@
 	Real sA = (1.0-kA)*(pertSumA2/pow(rA,2) - 1.0)+kA*(sphereA -1.0);
 
 	/* fB */
-	double blasTempP2[3];
-	double blasLocalP2[3];
+	Real blasTempP2[3];
+	Real blasLocalP2[3];
 	for(int i=0; i<3; i++) {
 		blasTempP2[i] = blasContactPt[i] - blasPosB[i];
 	}
@@ -1220,12 +1204,12 @@
 	// Vector3r localP2 = QB*tempP2;
 	/*P2Q*/ //Eigen::MatrixXd P2 = Eigen::MatrixXd::Zero(planeNoB,3);
 	/*d2*/  //Eigen::MatrixXd d2 = Eigen::MatrixXd::Zero(planeNoB,1);
-	double blasP2[planeNoB*3];
-	double blasD2[planeNoB];
-	double blasP2Q[planeNoB*3];
-	double pertSumB2 = 0.0;
+	Real blasP2[planeNoB*3];
+	Real blasD2[planeNoB];
+	Real blasP2Q[planeNoB*3];
+	Real pertSumB2 = 0.0;
 	for (int i=0; i<planeNoB; i++) {
-		double plane = s2->a[i]*blasLocalP2[0] + s2->b[i]*blasLocalP2[1] + s2->c[i]*blasLocalP2[2] - s2->d[i];
+		Real plane = s2->a[i]*blasLocalP2[0] + s2->b[i]*blasLocalP2[1] + s2->c[i]*blasLocalP2[2] - s2->d[i];
 		if (plane<pow(10,-15)) {
 			plane = 0.0;
 			blasX[4+planeNoA+i] = plane+ planePert;
@@ -1256,15 +1240,15 @@
 // Eigen::MatrixXd c=Eigen::MatrixXd::Zero(varNo,1);
 // c[3] = 1.0;
 
-	double blasA1[(3+planeNoA)*varNo];
-	double blasA2[(3+planeNoB)*varNo];
+	Real blasA1[(3+planeNoA)*varNo];
+	Real blasA2[(3+planeNoB)*varNo];
 	/* Second order cone constraints */
 	/* A1 */
 	//Eigen::MatrixXd A1(3+planeNoA,varNo);
 	//Matrix3r QAs=kAs*QA; //cwise()
-	double blasQAs[9];
+	Real blasQAs[9];
 	int noElements=9;
-	double scaleFactor = kAs;
+	Real scaleFactor = kAs;
 	dcopy_(&noElements, &blasQA[0], &incx, &blasQAs[0], &incx);
 	dscal_(&noElements, &scaleFactor, &blasQAs[0], &incx);
 
@@ -1284,7 +1268,7 @@
 	/* A2 */
 	//Eigen::MatrixXd A2(3+planeNoB,varNo);
 	//Matrix3r QBs=kBs*QB; //cwise();
-	double blasQBs[9];
+	Real blasQBs[9];
 	noElements=9;
 	scaleFactor = kBs;
 	dcopy_(&noElements, &blasQB[0], &incx, &blasQBs[0], &incx);
@@ -1314,8 +1298,8 @@
 	b1[2] = -b1temp[2];
 #endif
 
-	double blasB1[planeNoA3];
-	double blasB1temp[3];
+	Real blasB1[planeNoA3];
+	Real blasB1temp[3];
 	memset(blasB1,0.0,sizeof(blasB1));
 // blasM = 3;   blasN=3;
 //  blasLDA = 3;    blasAlpha = -1.0;  blasBeta=0.0;  blasLDC = 3;
@@ -1334,8 +1318,8 @@
 	b2[2] = -b2temp[2];
 #endif
 
-	double blasB2[planeNoB3];
-	double blasB2temp[3];
+	Real blasB2[planeNoB3];
+	Real blasB2temp[3];
 	memset(blasB2,0.0,sizeof(blasB2));
 //  blasM = 3;   blasN=3; blasLDA = 3; blasAlpha=-1.0; blasBeta=0.0;
 // dgemv_(&transA, &blasM, &blasN, &blasAlpha, &blasQBs[0], &blasLDA, &blasPosB[0], &incx, &blasBeta, &blasB2temp[0], &incy);
@@ -1349,7 +1333,7 @@
 // AL<<P1Q, Eigen::MatrixXd::Zero(planeNoA,1), -1.0*Eigen::MatrixXd::Identity(planeNoA,planeNoA), Eigen::MatrixXd::Zero(planeNoA,planeNoB), //cwise()
 //	      P2Q, Eigen::MatrixXd::Zero(planeNoB,1), Eigen::MatrixXd::Zero(planeNoB,planeNoA), -1.0*Eigen::MatrixXd::Identity(planeNoB,planeNoB);
 
-	double blasAL[planeNoAB*varNo];
+	Real blasAL[planeNoAB*varNo];
 	memset(blasAL,0.0,sizeof(blasAL));
 	for (int i=0; i<planeNoA; i++) {
 		blasAL[i] = blasP1Q[i];
@@ -1382,9 +1366,9 @@
 	bL<<btempU,btempL;
 #endif
 
-	double blasBL[planeNoAB];
-	double blasBTempU[planeNoA];
-	double blasBTempL[planeNoB];
+	Real blasBL[planeNoAB];
+	Real blasBTempU[planeNoA];
+	Real blasBTempL[planeNoB];
 	noElements = planeNoA;
 	dcopy_(&noElements, &blasD1[0], &incx, &blasBTempU[0], &incx);
 	//transA = 'N';	blasM = planeNoA;   blasN = 3;
@@ -1404,13 +1388,13 @@
 		blasBL[planeNoA+i]=blasBTempL[i];
 	}
 
-	double u1;
-	double u2;
-	double blasCCtranspose[varNo2];
+	Real u1;
+	Real u2;
+	Real blasCCtranspose[varNo2];
 	memset(blasCCtranspose,0.0,sizeof(blasCCtranspose));
 	blasCCtranspose[3+varNo*3]=1.0;
 
-	double blasCa1[varNo2];
+	Real blasCa1[varNo2];
 //#if 0
 #if 0
 	Eigen::MatrixXd ca1Transpose = ccTranspose - A1.transpose()*A1;
@@ -1430,7 +1414,7 @@
 
 
 	/* ca2Transpose */
-	double blasCa2[varNo2];
+	Real blasCa2[varNo2];
 	blasCount = 0;
 	dcopy_(&noElements, &blasCCtranspose[0], &incx, &blasCa2[0], &incy);
 
@@ -1441,48 +1425,48 @@
 	dgemm_(&blasT, &blasNT, &varNo, &varNo, &planeNoB3, &blasNeg1, &blasA2[0], &planeNoB3, &blasA2[0], &planeNoB3, &blas1, &blasCa2[0], &varNo);
 
 	/* DL */
-	double blasDL[planeNoAB*planeNoAB];
+	Real blasDL[planeNoAB*planeNoAB];
 	blasCount = 0;
 	memset(blasDL,0.0,sizeof(blasDL));
 
 //#endif
 
 
-	double wLlogsum = 0.0;
-	double val = 0.0;
-	double newval = 0.0;
+	Real wLlogsum = 0.0;
+	Real val = 0.0;
+	Real newval = 0.0;
 	/*Linesearch */
-	double backtrack = 1.0;
-	double penalty = 1.0/t;
+	Real backtrack = 1.0;
+	Real penalty = 1.0/t;
 
 	/* LAPACK */
 	int info;
 	char UPLO ='L';
 	int KD = varNo-1;
 	int nrhs=1;
-	double HessianChol[varNo][varNo];
-
-
-	double blasGA[varNo];
-	double blasGB[varNo];
-	double blasGL[varNo];
-
-	double blasW1[3+planeNoA];
-	double blasW2[3+planeNoB];
-	double blasWL[planeNoAB];
-	double blasVL[planeNoAB];
-	double minWL=0.0;
-	double blasHA[varNo*varNo];
-	double blasHB[varNo*varNo];
-	double blasHL[varNo*varNo];
-	double blasADAtemp[varNo*planeNoAB];
+	Real HessianChol[varNo][varNo];
+
+
+	Real blasGA[varNo];
+	Real blasGB[varNo];
+	Real blasGL[varNo];
+
+	Real blasW1[3+planeNoA];
+	Real blasW2[3+planeNoB];
+	Real blasWL[planeNoAB];
+	Real blasVL[planeNoAB];
+	Real minWL=0.0;
+	Real blasHA[varNo*varNo];
+	Real blasHB[varNo*varNo];
+	Real blasHL[varNo*varNo];
+	Real blasADAtemp[varNo*planeNoAB];
 	noElements = varNo;
-	double blasW1dot=0.0;
-	double blasW2dot=0.0;
-	double blasGrad[varNo];
-	double blasHess[varNo*varNo];
-	double blasStep[varNo];
-	double blasFprime = 0.0;
+	Real blasW1dot=0.0;
+	Real blasW2dot=0.0;
+	Real blasGrad[varNo];
+	Real blasHess[varNo*varNo];
+	Real blasStep[varNo];
+	Real blasFprime = 0.0;
 
 #if 0
 //	MAKE SURE POINTS ARE FEASIBLE //
@@ -1657,7 +1641,7 @@
 #endif
 		dpbsv_( &UPLO, &varNo, &KD, &nrhs, &HessianChol[0][0], &varNo, blasStep, &varNo, &info );
 		if(info != 0) {
-			std::cout<<"chol error"<<", planeA: "<<planeNoA<<", planeB: "<<planeNoB<<endl;
+			//std::cout<<"chol error"<<", planeA: "<<planeNoA<<", planeB: "<<planeNoB<<endl;
 			//return false;
 			/* LU factorization */
 			for (int i=0; i<varNo; i++ ) {
@@ -1669,7 +1653,7 @@
 		}
 
 		if (info!=0) {
-			std::cout<<"linear algebra error"<<endl;
+			//std::cout<<"linear algebra error"<<endl;
 		}
 
 //timingDeltas->checkpoint("Cholesky");
@@ -1779,7 +1763,7 @@
 			count++;
 			//std::cout<<"count: "<<count<<", s : "<<s<<", u1: "<<u1<<", u2: "<<u2<<", wLmincoeff: "<<minWL<<endl;
 			if(count==200) {
-				std::cout<<"count: "<<count<<", totalIter: "<<totalIter<<", backtrack: "<<backtrack<<"s : "<<s<<", u1: "<<u1<<", u2: "<<u2<<", wLmincoeff: "<<minWL<<endl;
+				//std::cout<<"count: "<<count<<", totalIter: "<<totalIter<<", backtrack: "<<backtrack<<"s : "<<s<<", u1: "<<u1<<", u2: "<<u2<<", wLmincoeff: "<<minWL<<endl;
 				//std::cout<<"wL: "<<endl<<wL<<endl<<endl;
 			}
 		}
@@ -1838,7 +1822,7 @@
 
 			count++;
 			if(count==200) {
-				std::cout<<"count: "<<count<<", totalIter: "<<totalIter<<", backtrack: "<<backtrack<<"s : "<<s<<", u1: "<<u1<<", u2: "<<u2<<", wLmincoeff: "<<minWL<<endl;
+				//std::cout<<"count: "<<count<<", totalIter: "<<totalIter<<", backtrack: "<<backtrack<<"s : "<<s<<", u1: "<<u1<<", u2: "<<u2<<", wLmincoeff: "<<minWL<<endl;
 				//std::cout<<"wL: "<<endl<<wL<<endl<<endl;
 			}
 
@@ -1851,7 +1835,7 @@
 
 			count++;
 			if(backtrack<pow(10,-11) ) {
-				std::cout<<"iter: "<<iter<<", totalIter: "<<totalIter<<", backtrack: "<<backtrack<<", val: "<<val<<", newval: "<<newval<<", t: "<<t<<", fprime: "<<blasFprime<<endl;
+				//std::cout<<"iter: "<<iter<<", totalIter: "<<totalIter<<", backtrack: "<<backtrack<<", val: "<<val<<", newval: "<<newval<<", t: "<<t<<", fprime: "<<blasFprime<<endl;
 
 				break;
 			}
@@ -1863,7 +1847,7 @@
 
 
 		if(blasFprime >0.0) {
-			std::cout<<"count: "<<count<<", totalIter: "<<totalIter<<", blasFprime: "<<blasFprime<<endl;
+			//std::cout<<"count: "<<count<<", totalIter: "<<totalIter<<", blasFprime: "<<blasFprime<<endl;
 		}
 
 
@@ -1878,7 +1862,7 @@
 				Real fA = evaluatePP(cm1,state1,contactPt);
 				Real fB = evaluatePP(cm2,state2,contactPt);
 				if(fabs(fA-fB)>0.001 ) {
-					std::cout<<"inside fA-fB: "<<fA-fB<<endl;
+					//std::cout<<"inside fA-fB: "<<fA-fB<<endl;
 				}
 				//timingDeltas->checkpoint("newton");
 				return true;
@@ -1889,12 +1873,12 @@
 		}
 		if(totalIter>100) {
 
-			std::cout<<"totalIter: "<<totalIter<<", t: "<<t<<", gap: "<<2.0*m/t<<", blasFprime: "<<blasFprime<<endl;
+			//std::cout<<"totalIter: "<<totalIter<<", t: "<<t<<", gap: "<<2.0*m/t<<", blasFprime: "<<blasFprime<<endl;
 			for (int i=0; i<varNo; i++) {
-				std::cout<<"blasStep, i"<<i<<", value: "<<blasStep[i]<<endl;
+				//std::cout<<"blasStep, i"<<i<<", value: "<<blasStep[i]<<endl;
 			}
 			for (int i=0; i<varNo; i++) {
-				std::cout<<"blasGrad, i"<<i<<", value: "<<blasGrad[i]<<endl;
+				//std::cout<<"blasGrad, i"<<i<<", value: "<<blasGrad[i]<<endl;
 			}
 			return false;
 			//break;

=== modified file 'pkg/dem/Ig2_PP_PP_ScGeom.hpp'
--- pkg/dem/Ig2_PP_PP_ScGeom.hpp	2016-01-19 00:59:38 +0000
+++ pkg/dem/Ig2_PP_PP_ScGeom.hpp	2016-01-22 22:27:43 +0000
@@ -36,7 +36,7 @@
 
 
 
-		double evaluatePP(const shared_ptr<Shape>& cm1, const State& state1, const Vector3r newTrial);
+		Real evaluatePP(const shared_ptr<Shape>& cm1, const State& state1, const Vector3r newTrial);
 		void getPtOnParticle2(const shared_ptr<Shape>& cm1, const State& state1, Vector3r previousPt, Vector3r normal, Vector3r& newlocalPoint);
 
 		bool contactPtMosekF2(const shared_ptr<Shape>& cm1, const State& state1, const shared_ptr<Shape>& cm2, const State& state2, Vector3r &contactPt);
@@ -56,9 +56,9 @@
 
 
 
-		YADE_CLASS_BASE_DOC_ATTRS_CTOR(Ig2_PP_PP_ScGeom,IGeomFunctor,"IGeom functor for PotentialParticle - PotentialParticle pair",
-			((double, accuracyTol, pow(10,-7),, "accuracy desired, tolerance criteria for SOCP"))
-			((double,interactionDetectionFactor,1.0,,"bool to avoid granular ratcheting")),
+		YADE_CLASS_BASE_DOC_ATTRS_CTOR(Ig2_PP_PP_ScGeom,IGeomFunctor,"EXPERIMENTAL. IGeom functor for PotentialParticle - PotentialParticle pair",
+			((Real, accuracyTol, pow(10,-7),, "accuracy desired, tolerance criteria for SOCP"))
+			((Real,interactionDetectionFactor,1.0,,"bool to avoid granular ratcheting")),
 			//((std::string,myfile,"./PotentialParticles"+"","string")),
 			//timingDeltas=shared_ptr<TimingDeltas>(new TimingDeltas);
 			//mosekTaskEnv = MSK_makeenv(&mosekEnv,NULL,NULL,NULL,NULL);
@@ -83,35 +83,35 @@
 #endif
 
 	/* LAPACK LU */
-	//int dgesv(int varNo, int varNo2, double *H, int varNo3, int *pivot, double* g, int varNo4, int info){
-	extern void dgesv_(const int *N, const int *nrhs, double *Hessian, const int *lda, int *ipiv, double *gradient, const int *ldb, int *info);
+	//int dgesv(int varNo, int varNo2, Real *H, int varNo3, int *pivot, Real* g, int varNo4, int info){
+	extern void dgesv_(const int *N, const int *nrhs, Real *Hessian, const int *lda, int *ipiv, Real *gradient, const int *ldb, int *info);
 	// int ans;
 	// dgesv_(&varNo, &varNo2, H, &varNo3, pivot,g, &varNo4, &ans);
 	// return ans;
 	//}
 
 	/* LAPACK Cholesky */
-	extern void dpbsv_(const char *uplo, const int *n, const int *kd, const int *nrhs, double *AB, const int *ldab, double *B, const int *ldb, int *info);
+	extern void dpbsv_(const char *uplo, const int *n, const int *kd, const int *nrhs, Real *AB, const int *ldab, Real *B, const int *ldb, int *info);
 
 	/* LAPACK QR */
-	extern void dgels_(const char *Trans, const int *m, const int *n, const int *nrhs, double *A, const int *lda, double *B, const int *ldb, const double *work, const int *lwork, int *info);
+	extern void dgels_(const char *Trans, const int *m, const int *n, const int *nrhs, Real *A, const int *lda, Real *B, const int *ldb, const Real *work, const int *lwork, int *info);
 
 
 	/*BLAS */
-	extern void dgemm_(const char *transA, const char *transB, const int *m, const int *n, const int *k, const double *alpha, double *A, const int *lda, double *B, const int *ldb, const double *beta, double *C, const int *ldc);
-
-	extern void dgemv_(const char *trans, const int *m, const int *n, const double *alpha, double *A, const int *lda, double *x, const int *incx, const double *beta, double *y, const int *incy);
-
-	extern void dcopy_(const int *N, double *x, const int *incx, double *y, const int *incy);
-
-	extern double ddot_(const int *N, double *x, const int *incx, double *y, const int *incy);
-
-	extern void daxpy_(const int *N, const double *da, double *dx, const int *incx, double *dy, const int *incy);
-
-	extern void dscal_(const int *N, const double *alpha, double *x, const int *incx);
-
-
-	void dsyev_(const char *jobz, const char *uplo, const int *N, double *A, const int *lda, double *W, double *work, int *lwork, int *info);
+	extern void dgemm_(const char *transA, const char *transB, const int *m, const int *n, const int *k, const Real *alpha, Real *A, const int *lda, Real *B, const int *ldb, const Real *beta, Real *C, const int *ldc);
+
+	extern void dgemv_(const char *trans, const int *m, const int *n, const Real *alpha, Real *A, const int *lda, Real *x, const int *incx, const Real *beta, Real *y, const int *incy);
+
+	extern void dcopy_(const int *N, Real *x, const int *incx, Real *y, const int *incy);
+
+	extern Real ddot_(const int *N, Real *x, const int *incx, Real *y, const int *incy);
+
+	extern void daxpy_(const int *N, const Real *da, Real *dx, const int *incx, Real *dy, const int *incy);
+
+	extern void dscal_(const int *N, const Real *alpha, Real *x, const int *incx);
+
+
+	void dsyev_(const char *jobz, const char *uplo, const int *N, Real *A, const int *lda, Real *W, Real *work, int *lwork, int *info);
 
 
 #ifdef __cplusplus

=== modified file 'pkg/dem/KnKsLaw.cpp'
--- pkg/dem/KnKsLaw.cpp	2016-01-19 00:59:38 +0000
+++ pkg/dem/KnKsLaw.cpp	2016-01-22 22:27:43 +0000
@@ -48,10 +48,10 @@
 		return true;
 	}
 
-	Vector3r shearForceBeforeRotate = shearForce;
+	//Vector3r shearForceBeforeRotate = shearForce;
 	Vector3r shiftVel = Vector3r(0,0,0); //scene->isPeriodic ? (Vector3r)((scene->cell->velGrad*scene->cell->Hsize)*Vector3r((Real) contact->cellDist[0],(Real) contact->cellDist[1],(Real) contact->cellDist[2])) : Vector3r::Zero();
 	geom->rotate(shearForce); //AndGetShear(shearForce,phys->prevNormal,de1,de2,dt,shiftVel,/*avoid ratcheting*/false);
-	Vector3r shearForceAfterRotate = shearForce;
+	//Vector3r shearForceAfterRotate = shearForce;
 	//Linear elasticity giving "trial" shear force
 	Vector3r shift2(0,0,0);
 	Vector3r incidentV = geom->getIncidentVel(de1, de2, scene->dt, shift2, shiftVel, /*preventGranularRatcheting*/false );
@@ -61,7 +61,7 @@
 	phys->shearDir = shearIncrement;
 	phys->shearIncrementForCD += shearIncrement.norm();
 	double du = 0.0;
-	double debugFn = 0.0;
+	//double debugFn = 0.0;
 	//double u_prev = fabs(phys->u_cumulative);
 	if(phys->shearDir.norm() > pow(10,-15)) {
 		phys->shearDir.normalize();
@@ -229,7 +229,7 @@
 	//we need to use correct branches in the periodic case, the following apply for spheres only
 	Vector3r force = -phys->normalForce-dampedShearForce;
 	if(isnan(force.norm())) {
-		std::cout<<"shearForce: "<<shearForce<<", normalForce: "<<phys->normalForce<<", debugFn: "<<debugFn<<", viscous: "<<phys->normalViscous<<", normal: "<<phys->normal<<", geom normal: "<<geom->normal<<", effective_phi: "<<phys->effective_phi<<", shearIncrement: "<<shearIncrement<<", id1: "<<id1<<", id2: "<<id2<<", shearForceBeforeRotate: "<<shearForceBeforeRotate<<", shearForceAfterRotate: " <<shearForceAfterRotate<<endl;
+		//std::cout<<"shearForce: "<<shearForce<<", normalForce: "<<phys->normalForce<<", debugFn: "<<debugFn<<", viscous: "<<phys->normalViscous<<", normal: "<<phys->normal<<", geom normal: "<<geom->normal<<", effective_phi: "<<phys->effective_phi<<", shearIncrement: "<<shearIncrement<<", id1: "<<id1<<", id2: "<<id2<<", shearForceBeforeRotate: "<<shearForceBeforeRotate<<", shearForceAfterRotate: " <<shearForceAfterRotate<<endl;
 	}
 	scene->forces.addForce(id1,force);
 	scene->forces.addForce(id2,-force);

=== modified file 'pkg/dem/KnKsLaw.hpp'
--- pkg/dem/KnKsLaw.hpp	2016-01-19 00:59:38 +0000
+++ pkg/dem/KnKsLaw.hpp	2016-01-22 22:27:43 +0000
@@ -13,7 +13,7 @@
 class KnKsPhys: public FrictPhys {
 	public:
 		virtual ~KnKsPhys();
-		YADE_CLASS_BASE_DOC_ATTRS_CTOR(KnKsPhys,FrictPhys,"IPhys originally for potential particles",
+		YADE_CLASS_BASE_DOC_ATTRS_CTOR(KnKsPhys,FrictPhys,"EXPERIMENTAL. IPhys originally for potential particles",
 			((vector<double>,lambdaIPOPT,0.0,,"Lagrange multiplier for equality constraints"))
 			((vector<int>,cstatCPLEX,,,"Lagrange multiplier for equality constraints"))
 			((vector<int>,rstatCPLEX,,,"Lagrange multiplier for equality constraints"))
@@ -136,7 +136,7 @@
 class Ip2_FrictMat_FrictMat_KnKsPhys: public IPhysFunctor {
 	public:
 		virtual void go(const shared_ptr<Material>& pp1, const shared_ptr<Material>& pp2, const shared_ptr<Interaction>& interaction);
-		YADE_CLASS_BASE_DOC_ATTRS(Ip2_FrictMat_FrictMat_KnKsPhys,IPhysFunctor,"Ip2 functor for :yref:`KnKsPhys`",
+		YADE_CLASS_BASE_DOC_ATTRS(Ip2_FrictMat_FrictMat_KnKsPhys,IPhysFunctor,"EXPERIMENTAL. Ip2 functor for :yref:`KnKsPhys`",
 			((Real,Knormal,0.0,,"allows user to input values directly from python scripts"))
 			((Real,Kshear,0.0,,"allows user to input values directly from python scripts"))
 			((Real, unitWidth2D, 1.0, ,"viscousDamping"))

=== modified file 'pkg/dem/PotentialParticle.hpp'
--- pkg/dem/PotentialParticle.hpp	2016-01-19 00:59:38 +0000
+++ pkg/dem/PotentialParticle.hpp	2016-01-22 22:27:43 +0000
@@ -15,7 +15,7 @@
 	public:
 		virtual ~PotentialParticle ();
 
-		YADE_CLASS_BASE_DOC_ATTRS_CTOR(PotentialParticle,Shape,"Geometry of PotentialParticle.",
+		YADE_CLASS_BASE_DOC_ATTRS_CTOR(PotentialParticle,Shape,"EXPERIMENTAL. Geometry of PotentialParticle.",
 			((int, id, 1,, "idNo"))
 			((bool, isBoundary, false,, "boundary"))
 			((bool, fixedNormal, false,, "use fixed normal"))
@@ -32,10 +32,10 @@
 			((Real , k, 0.1,, "k "))
 			((vector<Vector3r>, vertices,,,"vertices"))
 			((vector<bool> , isBoundaryPlane, ,, "whether it is a boundaryPlane "))
-			((vector<double> , a, ,, "a "))
-			((vector<double> , b, ,, "b "))
-			((vector<double> , c, ,, "c "))
-			((vector<double> , d, ,, "d "))
+			((vector<Real> , a, ,, "a "))
+			((vector<Real> , b, ,, "b "))
+			((vector<Real> , c, ,, "c "))
+			((vector<Real> , d, ,, "d "))
 			,
 			createIndex(); /*ctor*/
 #if 0
@@ -61,8 +61,8 @@
 #ifdef __cplusplus
 extern "C" {
 #endif
-void dgesv_(const int *N, const int *nrhs, double *Hessian, const int *lda, int *ipiv, double *gradient, const int *ldb, int *info);
-void dsyev_(const char *jobz, const char *uplo, const int *N, double *A, const int *lda, double *W, double *work, int *lwork, int *info);
+void dgesv_(const int *N, const int *nrhs, Real *Hessian, const int *lda, int *ipiv, Real *gradient, const int *ldb, int *info);
+void dsyev_(const char *jobz, const char *uplo, const int *N, Real *A, const int *lda, Real *W, Real *work, int *lwork, int *info);
 #ifdef __cplusplus
 };
 #endif

=== modified file 'pkg/dem/PotentialParticle2AABB.hpp'
--- pkg/dem/PotentialParticle2AABB.hpp	2016-01-19 00:59:38 +0000
+++ pkg/dem/PotentialParticle2AABB.hpp	2016-01-22 22:27:43 +0000
@@ -13,7 +13,7 @@
 
 		FUNCTOR1D(PotentialParticle);
 		//REGISTER_ATTRIBUTES(BoundFunctor,(aabbEnlargeFactor));
-		YADE_CLASS_BASE_DOC_ATTRS(PotentialParticle2AABB,BoundFunctor,"Functor creating :yref:`Aabb` from :yref:`PotentialParticle`.",
+		YADE_CLASS_BASE_DOC_ATTRS(PotentialParticle2AABB,BoundFunctor,"EXPERIMENTAL. Functor creating :yref:`Aabb` from :yref:`PotentialParticle`.",
 			((Real,aabbEnlargeFactor,((void)"deactivated",-1),,"see :yref:`Sphere2AABB`."))
 			((Vector3r, halfSize, Vector3r::Zero(),,"halfSize"))
 


Follow ups