← Back to team overview

yade-dev team mailing list archive

[svn] r1830 - in trunk: gui/py gui/qt3 lib lib/py

 

Author: eudoxos
Date: 2009-07-02 12:09:56 +0200 (Thu, 02 Jul 2009)
New Revision: 1830

Added:
   trunk/lib/miniWm3Wrap-generate.py
   trunk/lib/miniWm3Wrap-toExpose.hpp
   trunk/lib/py/_packSpheres.cpp
Modified:
   trunk/gui/py/PythonUI_rc.py
   trunk/gui/py/yadeControl.cpp
   trunk/gui/qt3/QtGUI-python.cpp
   trunk/lib/SConscript
   trunk/lib/py/_eudoxos.cpp
   trunk/lib/py/_packPredicates.cpp
   trunk/lib/py/_utils.cpp
   trunk/lib/py/pack.py
Log:
1. Add automatic converter from python::tuple to Vector3r and vice versa. Wrapped functions can take/return Vector3r directly instead of manual conversion. Clean code that had to do that. Let me know if something breaks, the changes should not touch any python code.
2. Some preliminary work on wrapping Vector+Quaternion classes in python via py++ (not enabled, just the files are there)
3. Add forgotten _packSphere.cpp, thanks to Vincent for reporting.



Modified: trunk/gui/py/PythonUI_rc.py
===================================================================
--- trunk/gui/py/PythonUI_rc.py	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/gui/py/PythonUI_rc.py	2009-07-02 10:09:56 UTC (rev 1830)
@@ -14,9 +14,10 @@
 __builtins__.O=Omega()
 
 #try:
-#	import yade.qt.atexit
-#	atexit.register(yade.qt.close)
-#except ImportError: pass
+#	from miniWm3Wrap import Vector3_less__double__greater_ as Vector3r
+#	from miniWm3Wrap import Vector2_less__double__greater_ as Vector2r
+#	from miniWm3Wrap import Quaternion_less__double__greater_ as Quaternionr
+#except ImportError: pass 
 
 ### direct object creation through automatic wrapper functions
 def listChildClassesRecursive(base):

Modified: trunk/gui/py/yadeControl.cpp
===================================================================
--- trunk/gui/py/yadeControl.cpp	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/gui/py/yadeControl.cpp	2009-07-02 10:09:56 UTC (rev 1830)
@@ -155,13 +155,13 @@
 			throw std::invalid_argument("Invalid  DOF specification `"+s+"', must be ∈{x,y,z,rx,ry,rz}.");
 		}
 	}
-	python::tuple displ_get(){Vector3r ret=proxee->se3.position-proxee->refSe3.position; return python::make_tuple(ret[0],ret[1],ret[2]);}
+	Vector3r displ_get(){return proxee->se3.position-proxee->refSe3.position;}
 	python::tuple rot_get(){Quaternionr relRot=proxee->refSe3.orientation.Conjugate()*proxee->se3.orientation; Vector3r axis; Real angle; relRot.ToAxisAngle(axis,angle); axis*=angle; return python::make_tuple(axis[0],axis[1],axis[2]); }
-	python::tuple pos_get(){const Vector3r& p=proxee->se3.position; return python::make_tuple(p[0],p[1],p[2]);}
-	python::tuple refPos_get(){const Vector3r& p=proxee->refSe3.position; return python::make_tuple(p[0],p[1],p[2]);}
+	Vector3r pos_get(){return proxee->se3.position;}
+	Vector3r refPos_get(){return proxee->refSe3.position;}
 	python::tuple ori_get(){Vector3r axis; Real angle; proxee->se3.orientation.ToAxisAngle(axis,angle); return python::make_tuple(axis[0],axis[1],axis[2],angle);}
-	void pos_set(python::list l){if(python::len(l)!=3) throw invalid_argument("Wrong number of vector3 elements "+lexical_cast<string>(python::len(l))+", should be 3"); proxee->se3.position=Vector3r(python::extract<double>(l[0])(),python::extract<double>(l[1])(),python::extract<double>(l[2])());}
-	void refPos_set(python::list l){if(python::len(l)!=3) throw invalid_argument("Wrong number of vector3 elements "+lexical_cast<string>(python::len(l))+", should be 3"); proxee->refSe3.position=Vector3r(python::extract<double>(l[0])(),python::extract<double>(l[1])(),python::extract<double>(l[2])());}
+	void pos_set(const Vector3r& p){ proxee->se3.position=p; }
+	void refPos_set(const Vector3r& p){ proxee->refSe3.position=p;}
 	void ori_set(python::list l){if(python::len(l)!=4) throw invalid_argument("Wrong number of quaternion elements "+lexical_cast<string>(python::len(l))+", should be 4"); proxee->se3.orientation=Quaternionr(Vector3r(python::extract<double>(l[0])(),python::extract<double>(l[1])(),python::extract<double>(l[2])()),python::extract<double>(l[3])());}
 BASIC_PY_PROXY_TAIL;
 
@@ -428,10 +428,10 @@
 		python::tuple torque_get(long id){ MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.sync(); Vector3r m=rb->bex.getTorque(id); return python::make_tuple(m[0],m[1],m[2]);}
 		python::tuple move_get(long id){ MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.sync(); Vector3r m=rb->bex.getMove(id); return python::make_tuple(m[0],m[1],m[2]);}
 		python::tuple rot_get(long id){ MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.sync(); Vector3r m=rb->bex.getRot(id); return python::make_tuple(m[0],m[1],m[2]);}
-		void force_add(long id, python::tuple f){  MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.addForce (id,tuple2vec(f)); }
-		void torque_add(long id, python::tuple t){ MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.addTorque(id,tuple2vec(t));}
-		void move_add(long id, python::tuple t){ MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.addMove(id,tuple2vec(t));}
-		void rot_add(long id, python::tuple t){ MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.addRot(id,tuple2vec(t));}
+		void force_add(long id, const Vector3r& f){  MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.addForce (id,f); }
+		void torque_add(long id, const Vector3r& t){ MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.addTorque(id,t);}
+		void move_add(long id, const Vector3r& t){ MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.addMove(id,t);}
+		void rot_add(long id, const Vector3r& t){ MetaBody* rb=Omega::instance().getRootBody().get(); rb->bex.addRot(id,t);}
 };
 
 class pyOmega{
@@ -663,19 +663,38 @@
     public:
 	void py_import(pyBodyContainer bc, unsigned int begin=0, bool noInteractingGeometry=false) { import(bc.proxee,begin,noInteractingGeometry); }
 };
-
 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(STLImporter_import_overloads,py_import,1,3);
 
+
+// automatic conversion of Vector3r and 3-tuple
+// this doesn't create any new class in python
+struct custom_Vector3r_to_tuple{
+	static PyObject* convert(Vector3r const& v){
+		return python::incref(python::make_tuple(v[0],v[1],v[2]).ptr());
+	}
+};
+struct custom_Vector3r_from_tuple{
+	custom_Vector3r_from_tuple(){
+		python::converter::registry::push_back(&convertible,&construct,python::type_id<Vector3r>());
+	}
+	static void* convertible(PyObject* obj_ptr){
+		if(!PySequence_Check(obj_ptr) || PySequence_Size(obj_ptr)!=3) return 0;
+		return obj_ptr;
+	}
+	static void construct(PyObject* obj_ptr, python::converter::rvalue_from_python_stage1_data* data){
+		void* storage=((python::converter::rvalue_from_python_storage<Vector3r>*)(data))->storage.bytes;
+		new (storage) Vector3r(python::extract<double>(PySequence_GetItem(obj_ptr,0)),python::extract<double>(PySequence_GetItem(obj_ptr,1)),python::extract<double>(PySequence_GetItem(obj_ptr,2)));
+		data->convertible=storage;
+	}
+};
+
+
 BOOST_PYTHON_MODULE(wrapper)
 {
-	/* http://mail.python.org/pipermail/c++-sig/2004-March/007025.html
-	http://mail.python.org/pipermail/c++-sig/2004-March/007029.html
 
-	UNUSED, deal with boost::python::list instead
+	python::to_python_converter<Vector3r,custom_Vector3r_to_tuple>();
+	custom_Vector3r_from_tuple();
 
-	python::class_<std::vector<std::string> >("_vectSs")
-		.def(python::vector_indexing_suite<std::vector<std::string>,true>());   */
-
 	boost::python::class_<pyOmega>("Omega")
 		.add_property("iter",&pyOmega::iter)
 		.add_property("stopAtIter",&pyOmega::stopAtIter_get,&pyOmega::stopAtIter_set)

Modified: trunk/gui/qt3/QtGUI-python.cpp
===================================================================
--- trunk/gui/qt3/QtGUI-python.cpp	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/gui/qt3/QtGUI-python.cpp	2009-07-02 10:09:56 UTC (rev 1830)
@@ -129,7 +129,7 @@
 		pyGLViewer(size_t _viewNo){init(_viewNo);}
 		python::tuple get_grid(){GLV; return python::make_tuple(glv->drawGridXYZ[0],glv->drawGridXYZ[1],glv->drawGridXYZ[2]);}
 		void set_grid(python::tuple t){GLV; MUTEX; for(int i=0;i<3;i++)glv->drawGridXYZ[i]=python::extract<bool>(t[i])();}
-		#define VEC_GET_SET(property,getter,setter) python::object get_##property(){GLV; return vec2tuple(getter());} void set_##property(python::tuple t){GLV; MUTEX; setter(tuple2vec(t));}
+		#define VEC_GET_SET(property,getter,setter) Vector3r get_##property(){GLV; qglviewer::Vec v=getter(); return Vector3r(v[0],v[1],v[2]); } void set_##property(const Vector3r& t){GLV; MUTEX; setter(qglviewer::Vec(t[0],t[1],t[2]));}
 		VEC_GET_SET(upVector,glv->camera()->upVector,glv->camera()->setUpVector);
 		VEC_GET_SET(lookAt,glv->camera()->position()+glv->camera()->viewDirection,glv->camera()->lookAt);
 		VEC_GET_SET(viewDir,glv->camera()->viewDirection,glv->camera()->setViewDirection);
@@ -142,8 +142,8 @@
 		void set_orthographic(bool b){GLV; MUTEX; return glv->camera()->setType(b ? qglviewer::Camera::ORTHOGRAPHIC : qglviewer::Camera::PERSPECTIVE);}
 		#define FLOAT_GET_SET(property,getter,setter)void set_##property(Real r){GLV; MUTEX; setter(r);} Real get_##property(){GLV; return getter();}
 		FLOAT_GET_SET(sceneRadius,glv->sceneRadius,glv->setSceneRadius);
-		void fitAABB(python::tuple min, python::tuple max){GLV; MUTEX; glv->camera()->fitBoundingBox(tuple2vec(min),tuple2vec(max));}
-		void fitSphere(python::tuple center,Real radius){GLV; MUTEX; glv->camera()->fitSphere(tuple2vec(center),radius);}
+		void fitAABB(const Vector3r& min, const Vector3r& max){GLV; MUTEX; glv->camera()->fitBoundingBox(qglviewer::Vec(min[0],min[1],min[2]),qglviewer::Vec(max[0],max[1],max[2]));}
+		void fitSphere(const Vector3r& center,Real radius){GLV; MUTEX; glv->camera()->fitSphere(qglviewer::Vec(center[0],center[1],center[2]),radius);}
 		void showEntireScene(){GLV; MUTEX; glv->camera()->showEntireScene();}
 		void center(bool median=false){GLV; MUTEX; if(median)glv->centerMedianQuartile(); else glv->centerScene();}
 		python::tuple get_screenSize(){GLV; return python::make_tuple(glv->width(),glv->height());} void set_screenSize(python::tuple t){GLV; MUTEX; vector<int>* ii=new(vector<int>); ii->push_back(viewNo); ii->push_back(python::extract<int>(t[0])()); ii->push_back(python::extract<int>(t[1])()); QApplication::postEvent(ensuredMainWindow(),new QCustomEvent((QEvent::Type)YadeQtMainWindow::EVENT_RESIZE_VIEW,(void*)ii));}

Modified: trunk/lib/SConscript
===================================================================
--- trunk/lib/SConscript	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/lib/SConscript	2009-07-02 10:09:56 UTC (rev 1830)
@@ -29,10 +29,13 @@
 	# say e.g. 'import euclid' (not 'import  yade.euclid')
 	env.Install('$PREFIX/lib/yade$SUFFIX/py',[
 		env.File('euclid.py','py'),
+		# skip this for now
+		#env.SharedLibrary('miniWm3Wrap',['miniWm3Wrap.cpp'],SHLIBPREFIX='',CPPPATH=env['CPPPATH']+['.'])
 	])
 
 
 
+
 if 'qt3' not in env['exclude']:
 	env.Install('$PREFIX/lib/yade$SUFFIX/lib',[
 		env.SharedLibrary('yade-serialization-qt',

Added: trunk/lib/miniWm3Wrap-generate.py
===================================================================
--- trunk/lib/miniWm3Wrap-generate.py	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/lib/miniWm3Wrap-generate.py	2009-07-02 10:09:56 UTC (rev 1830)
@@ -0,0 +1,26 @@
+import os, os.path
+from pyplusplus import module_builder
+from pyplusplus.decl_wrappers import *
+from pyplusplus.module_builder import call_policies
+
+
+#Creating an instance of class that will help you to expose your declarations
+mb = module_builder.module_builder_t( [os.path.abspath("miniWm3Wrap-toExpose.hpp")]
+                                      , working_directory=r"."
+                                      , include_paths=['miniWm3','.']
+                                      , define_symbols=['USE_MINIWM3'] )
+# we don't need system things from wm3
+mb.decls(lambda decl: 'System' in decl.name).exclude() 
+#mb.decls(lambda decl: 'noexpose' in decl.name).exclude() 
+# exclude casting operators
+mb.decls(lambda decl: 'operator double' in decl.name).exclude()
+mb.member_functions(return_type='double &').exclude()
+# we would have to do some magic here
+mb.member_functions(lambda decl: decl.name in ['ToAxisAngle','ToRotationMatrix']).exclude()
+mb.member_functions(lambda decl: decl.name in ['FromRotationMatrix','FromAxisAngle','Slerp','SlerpExtraSpins','Intermediate','Squad','Align']).exclude()
+#mb.member_function(meth).call_policies=call_policies.return_value_policy(call_policies.return_internal_reference)
+
+#mb.print_declarations()
+mb.build_code_creator(module_name='miniWm3Wrap')
+mb.write_module('miniWm3Wrap.cpp')
+

Added: trunk/lib/miniWm3Wrap-toExpose.hpp
===================================================================
--- trunk/lib/miniWm3Wrap-toExpose.hpp	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/lib/miniWm3Wrap-toExpose.hpp	2009-07-02 10:09:56 UTC (rev 1830)
@@ -0,0 +1,16 @@
+//#include<Wm3Vector3.h>
+#include<base/yadeWm3.hpp>
+#include<base/yadeWm3Extra.hpp>
+// instantiate those types so that they are exposed
+// but name them noexpose_*, as we ask for exclusion of such things in the wrapper script
+
+//int i=sizeof(Vector3r);
+//int j=sizeof(Vector2r);
+//int k=sizeof(Quaternionr);
+
+Vector3r noexpose_v3r;
+Vector2r noexpose_v2r;
+Quaternionr noexpose_q;
+//Matrix3r m3r;
+
+

Modified: trunk/lib/py/_eudoxos.cpp
===================================================================
--- trunk/lib/py/_eudoxos.cpp	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/lib/py/_eudoxos.cpp	2009-07-02 10:09:56 UTC (rev 1830)
@@ -65,8 +65,7 @@
  *
  * The code is analogous to AxialGravityEngine and is intended to give initial motion
  * to particles subject to axial compaction to speed up the process. */
-void velocityTowardsAxis(python::tuple _axisPoint, python::tuple _axisDirection, Real timeToAxis, Real subtractDist=0., Real perturbation=0.1){
-	Vector3r axisPoint=tuple2vec(_axisPoint), axisDirection=tuple2vec(_axisDirection);
+void velocityTowardsAxis(const Vector3r& axisPoint, const Vector3r& axisDirection, Real timeToAxis, Real subtractDist=0., Real perturbation=0.1){
 	FOREACH(const shared_ptr<Body>&b, *(Omega::instance().getRootBody()->bodies)){
 		if(!b->isDynamic) continue;
 		ParticleParameters* pp=YADE_CAST<ParticleParameters*>(b->physicalParameters.get());

Modified: trunk/lib/py/_packPredicates.cpp
===================================================================
--- trunk/lib/py/_packPredicates.cpp	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/lib/py/_packPredicates.cpp	2009-07-02 10:09:56 UTC (rev 1830)
@@ -30,15 +30,16 @@
 python::tuple vec2tuple(const Vector2r& v){return boost::python::make_tuple(v[0],v[1]);}
 Vector3r tuple2vec(const python::tuple& t){return Vector3r(python::extract<double>(t[0])(),python::extract<double>(t[1])(),python::extract<double>(t[2])());}
 Vector2r tuple2vec2d(const python::tuple& t){return Vector2r(python::extract<double>(t[0])(),python::extract<double>(t[1])());}
-void ttuple2vvec(const python::tuple& t, Vector3r& v1, Vector3r& v2){ v1=tuple2vec(python::extract<python::tuple>(t[0])()); v2=tuple2vec(python::extract<python::tuple>(t[1])()); }
-python::tuple vvec2ttuple(const Vector3r&v1, const Vector3r&v2){ return python::make_tuple(vec2tuple(v1),vec2tuple(v2)); }
+//void ttuple2vvec(const python::tuple& t, Vector3r& v1, Vector3r& v2){ v1=tuple2vec(python::extract<python::tuple>(t[0])()); v2=tuple2vec(python::extract<python::tuple>(t[1])()); }
+void ttuple2vvec(const python::tuple& t, Vector3r& v1, Vector3r& v2){ v1=python::extract<Vector3r>(t[0])(); v2=python::extract<Vector3r>(t[1])(); }
+python::tuple vvec2ttuple(const Vector3r&v1, const Vector3r&v2){ return python::make_tuple(v1,v2); }
 
 struct Predicate{
 	public:
-		virtual bool operator() (python::tuple pt,Real pad=0.) const = 0;
+		virtual bool operator() (const Vector3r& pt,Real pad=0.) const = 0;
 		virtual python::tuple aabb() const = 0;
-		python::tuple dim() const { Vector3r mn,mx; ttuple2vvec(aabb(),mn,mx); return vec2tuple(mx-mn); }
-		python::tuple center() const { Vector3r mn,mx; ttuple2vvec(aabb(),mn,mx); return vec2tuple(.5*(mn+mx)); }
+		Vector3r dim() const { Vector3r mn,mx; ttuple2vvec(aabb(),mn,mx); return mx-mn; }
+		Vector3r center() const { Vector3r mn,mx; ttuple2vvec(aabb(),mn,mx); return .5*(mn+mx); }
 };
 // make the pad parameter optional
 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(PredicateCall_overloads,operator(),1,2);
@@ -58,7 +59,7 @@
 super(inGtsSurface,self).__init__() so that virtual methods work as expected.
 */
 struct PredicateWrap: Predicate, python::wrapper<Predicate>{
-	bool operator()(python::tuple pt, Real pad=0.) const { return this->get_override("__call__")(pt,pad);}
+	bool operator()(const Vector3r& pt, Real pad=0.) const { return this->get_override("__call__")(pt,pad);}
 	python::tuple aabb() const { return this->get_override("aabb")(); }
 };
 // make the pad parameter optional
@@ -83,7 +84,7 @@
 class PredicateUnion: public PredicateBoolean{
 	public:
 		PredicateUnion(const python::object _A, const python::object _B): PredicateBoolean(_A,_B){}
-		virtual bool operator()(python::tuple pt,Real pad) const {return obj2pred(A)(pt,pad)||obj2pred(B)(pt,pad);}
+		virtual bool operator()(const Vector3r& pt,Real pad) const {return obj2pred(A)(pt,pad)||obj2pred(B)(pt,pad);}
 		virtual python::tuple aabb() const { Vector3r minA,maxA,minB,maxB; ttuple2vvec(obj2pred(A).aabb(),minA,maxA); ttuple2vvec(obj2pred(B).aabb(),minB,maxB); return vvec2ttuple(componentMinVector(minA,minB),componentMaxVector(maxA,maxB));}
 };
 PredicateUnion makeUnion(const python::object& A, const python::object& B){ return PredicateUnion(A,B);}
@@ -91,7 +92,7 @@
 class PredicateIntersection: public PredicateBoolean{
 	public:
 		PredicateIntersection(const python::object _A, const python::object _B): PredicateBoolean(_A,_B){}
-		virtual bool operator()(python::tuple pt,Real pad) const {return obj2pred(A)(pt,pad) && obj2pred(B)(pt,pad);}
+		virtual bool operator()(const Vector3r& pt,Real pad) const {return obj2pred(A)(pt,pad) && obj2pred(B)(pt,pad);}
 		virtual python::tuple aabb() const { Vector3r minA,maxA,minB,maxB; ttuple2vvec(obj2pred(A).aabb(),minA,maxA); ttuple2vvec(obj2pred(B).aabb(),minB,maxB); return vvec2ttuple(componentMaxVector(minA,minB),componentMinVector(maxA,maxB));}
 };
 PredicateIntersection makeIntersection(const python::object& A, const python::object& B){ return PredicateIntersection(A,B);}
@@ -99,7 +100,7 @@
 class PredicateDifference: public PredicateBoolean{
 	public:
 		PredicateDifference(const python::object _A, const python::object _B): PredicateBoolean(_A,_B){}
-		virtual bool operator()(python::tuple pt,Real pad) const {return obj2pred(A)(pt,pad) && !obj2pred(B)(pt,-pad);}
+		virtual bool operator()(const Vector3r& pt,Real pad) const {return obj2pred(A)(pt,pad) && !obj2pred(B)(pt,-pad);}
 		virtual python::tuple aabb() const { return obj2pred(A).aabb(); }
 };
 PredicateDifference makeDifference(const python::object& A, const python::object& B){ return PredicateDifference(A,B);}
@@ -107,7 +108,7 @@
 class PredicateSymmetricDifference: public PredicateBoolean{
 	public:
 		PredicateSymmetricDifference(const python::object _A, const python::object _B): PredicateBoolean(_A,_B){}
-		virtual bool operator()(python::tuple pt,Real pad) const {bool inA=obj2pred(A)(pt,pad), inB=obj2pred(B)(pt,pad); return (inA && !inB) || (!inA && inB);}
+		virtual bool operator()(const Vector3r& pt,Real pad) const {bool inA=obj2pred(A)(pt,pad), inB=obj2pred(B)(pt,pad); return (inA && !inB) || (!inA && inB);}
 		virtual python::tuple aabb() const { Vector3r minA,maxA,minB,maxB; ttuple2vvec(obj2pred(A).aabb(),minA,maxA); ttuple2vvec(obj2pred(B).aabb(),minB,maxB); return vvec2ttuple(componentMinVector(minA,minB),componentMaxVector(maxA,maxB));}
 };
 PredicateSymmetricDifference makeSymmetricDifference(const python::object& A, const python::object& B){ return PredicateSymmetricDifference(A,B);}
@@ -121,11 +122,8 @@
 class inSphere: public Predicate {
 	Vector3r center; Real radius;
 public:
-	inSphere(python::tuple _center, Real _radius){center=tuple2vec(_center); radius=_radius;}
-	virtual bool operator()(python::tuple _pt, Real pad=0.) const {
-		Vector3r pt=tuple2vec(_pt);
-		return ((pt-center).Length()-pad<=radius-pad);
-	}
+	inSphere(const Vector3r& _center, Real _radius){center=_center; radius=_radius;}
+	virtual bool operator()(const Vector3r& pt, Real pad=0.) const { return ((pt-center).Length()-pad<=radius-pad); }
 	virtual python::tuple aabb() const {return vvec2ttuple(Vector3r(center[0]-radius,center[1]-radius,center[2]-radius),Vector3r(center[0]+radius,center[1]+radius,center[2]+radius));}
 };
 
@@ -133,9 +131,8 @@
 class inAlignedBox: public Predicate{
 	Vector3r mn, mx;
 public:
-	inAlignedBox(python::tuple _mn, python::tuple _mx){mn=tuple2vec(_mn); mx=tuple2vec(_mx);}
-	virtual bool operator()(python::tuple _pt, Real pad=0.) const {
-		Vector3r pt=tuple2vec(_pt);
+	inAlignedBox(const Vector3r& _mn, const Vector3r& _mx): mn(_mn), mx(_mx) {}
+	virtual bool operator()(const Vector3r& pt, Real pad=0.) const {
 		return
 			mn[0]+pad<=pt[0] && mx[0]-pad>=pt[0] &&
 			mn[1]+pad<=pt[1] && mx[1]-pad>=pt[1] &&
@@ -148,9 +145,8 @@
 class inCylinder: public Predicate{
 	Vector3r c1,c2,c12; Real radius,ht;
 public:
-	inCylinder(python::tuple _c1, python::tuple _c2, Real _radius){c1=tuple2vec(_c1); c2=tuple2vec(_c2); c12=c2-c1; radius=_radius; ht=c12.Length(); }
-	bool operator()(python::tuple _pt, Real pad=0.) const {
-		Vector3r pt=tuple2vec(_pt);
+	inCylinder(const Vector3r& _c1, const Vector3r& _c2, Real _radius){c1=_c1; c2=_c2; c12=c2-c1; radius=_radius; ht=c12.Length(); }
+	bool operator()(const Vector3r& pt, Real pad=0.) const {
 		Real u=(pt.Dot(c12)-c1.Dot(c12))/(ht*ht); // normalized coordinate along the c1--c2 axis
 		if((u*ht<0+pad) || (u*ht>ht-pad)) return false; // out of cylinder along the axis
 		Real axisDist=((pt-c1).Cross(pt-c2)).Length()/ht;
@@ -164,7 +160,7 @@
 			sqrt((pow(A[1]-B[1],2)+pow(A[2]-B[2],2)))/ht,
 			sqrt((pow(A[0]-B[0],2)+pow(A[2]-B[2],2)))/ht,
 			sqrt((pow(A[0]-B[0],2)+pow(A[1]-B[1],2)))/ht);
-		Vector3r mn(min(A[0],B[0]),min(A[1],B[1]),min(A[2],B[2])), mx(max(A[0],B[0]),max(A[1],B[1]),max(A[2],B[2]));
+		Vector3r mn=componentMinVector(A,B), mx=componentMaxVector(A,B);
 		return vvec2ttuple(mn-radius*k,mx+radius*k);
 	}
 };
@@ -176,14 +172,13 @@
 class inHyperboloid: public Predicate{
 	Vector3r c1,c2,c12; Real R,a,ht,c;
 public:
-	inHyperboloid(python::tuple _c1, python::tuple _c2, Real _R, Real _r){
-		c1=tuple2vec(_c1); c2=tuple2vec(_c2); R=_R; a=_r;
+	inHyperboloid(const Vector3r& _c1, const Vector3r& _c2, Real _R, Real _r){
+		c1=_c1; c2=_c2; R=_R; a=_r;
 		c12=c2-c1; ht=c12.Length();
 		Real uMax=sqrt(pow(R/a,2)-1); c=ht/(2*uMax);
 	}
 	// WARN: this is not accurate, since padding is taken as perpendicular to the axis, not the the surface
-	bool operator()(python::tuple _pt, Real pad=0.) const {
-		Vector3r pt=tuple2vec(_pt);
+	bool operator()(const Vector3r& pt, Real pad=0.) const {
 		Real v=(pt.Dot(c12)-c1.Dot(c12))/(ht*ht); // normalized coordinate along the c1--c2 axis
 		if((v*ht<0+pad) || (v*ht>ht-pad)) return false; // out of cylinder along the axis
 		Real u=(v-.5)*ht/c; // u from the wolfram parametrization; u is 0 in the center
@@ -194,7 +189,7 @@
 	}
 	python::tuple aabb() const {
 		// the lazy way
-		return inCylinder(vec2tuple(c1),vec2tuple(c2),R).aabb();
+		return inCylinder(c1,c2,R).aabb();
 	}
 };
 
@@ -202,9 +197,8 @@
 class inEllipsoid: public Predicate{
 	Vector3r c, abc;
 public:
-	inEllipsoid(python::tuple _c, python::tuple _abc) {c=tuple2vec(_c); abc=tuple2vec(_abc);}
-	bool operator()(python::tuple _pt, Real pad=0.) const {
-		Vector3r pt=tuple2vec(_pt);
+	inEllipsoid(const Vector3r& _c, const Vector3r& _abc) {c=_c; abc=_abc;}
+	bool operator()(const Vector3r& pt, Real pad=0.) const {
 		//Define the ellipsoid X-coordinate of given Y and Z
 		Real x = sqrt((1-pow((pt[1]-c[1]),2)/((abc[1]-pad)*(abc[1]-pad))-pow((pt[2]-c[2]),2)/((abc[2]-pad)*(abc[2]-pad)))*((abc[0]-pad)*(abc[0]-pad)))+c[0]; 
 		Vector3r edgeEllipsoid(x,pt[1],pt[2]); // create a vector of these 3 coordinates
@@ -244,16 +238,15 @@
 class notInNotch: public Predicate{
 	Vector3r c, edge, normal, inside; Real aperture;
 public:
-	notInNotch(python::tuple _c, python::tuple _edge, python::tuple _normal, Real _aperture){
-		c=tuple2vec(_c);
-		edge=tuple2vec(_edge); edge.Normalize();
-		normal=tuple2vec(_normal); normal-=edge*edge.Dot(normal); normal.Normalize();
+	notInNotch(const Vector3r& _c, const Vector3r& _edge, const Vector3r& _normal, Real _aperture){
+		c=_c;
+		edge=_edge; edge.Normalize();
+		normal=_normal; normal-=edge*edge.Dot(normal); normal.Normalize();
 		inside=edge.Cross(normal);
 		aperture=_aperture;
 		// LOG_DEBUG("edge="<<edge<<", normal="<<normal<<", inside="<<inside<<", aperture="<<aperture);
 	}
-	bool operator()(python::tuple _pt, Real pad=0.) const {
-		Vector3r pt=tuple2vec(_pt);
+	bool operator()(const Vector3r& pt, Real pad=0.) const {
 		Real distUp=normal.Dot(pt-c)-aperture/2, distDown=-normal.Dot(pt-c)-aperture/2, distInPlane=-inside.Dot(pt-c);
 		// LOG_DEBUG("pt="<<pt<<", distUp="<<distUp<<", distDown="<<distDown<<", distInPlane="<<distInPlane);
 		if(distInPlane>=pad) return true;
@@ -268,7 +261,8 @@
 	// This predicate is not bounded, return infinities
 	python::tuple aabb() const {
 		Real inf=std::numeric_limits<Real>::infinity();
-		return vvec2ttuple(Vector3r(-inf,-inf,-inf),Vector3r(inf,inf,inf)); }
+		return vvec2ttuple(Vector3r(-inf,-inf,-inf),Vector3r(inf,inf,inf));
+	}
 };
 
 #ifdef YADE_GTS
@@ -309,12 +303,11 @@
 		gts_surface_foreach_vertex(surf,(GtsFunc)vertex_aabb,&bb);
 		return vvec2ttuple(bb.first,bb.second);
 	}
-	bool ptCheck(Vector3r pt) const{
+	bool ptCheck(const Vector3r& pt) const{
 		GtsPoint gp; gp.x=pt[0]; gp.y=pt[1]; gp.z=pt[2];
 		return (bool)gts_point_is_inside_surface(&gp,tree,is_open);
 	}
-	bool operator()(python::tuple _pt, Real pad=0.) const {
-		Vector3r pt=tuple2vec(_pt);
+	bool operator()(const Vector3r& pt, Real pad=0.) const {
 		if(noPad){
 			if(pad!=0. && noPadWarned) LOG_WARN("inGtsSurface constructed with noPad; requested non-zero pad set to zero.");
 			return ptCheck(pt);
@@ -325,8 +318,8 @@
 
 #endif
 
-
 BOOST_PYTHON_MODULE(_packPredicates){
+
 	// base predicate class
 	python::class_<PredicateWrap,/* necessary, as methods are pure virtual*/ boost::noncopyable>("Predicate")
 		.def("__call__",python::pure_virtual(&Predicate::operator()))
@@ -342,12 +335,12 @@
 	python::class_<PredicateDifference,python::bases<PredicateBoolean> >("PredicateDifference","Difference of 2 predicates",python::init<python::object,python::object >());
 	python::class_<PredicateSymmetricDifference,python::bases<PredicateBoolean> >("PredicateSymmetricDifference","SymmetricDifference of 2 predicates",python::init<python::object,python::object >());
 	// primitive predicates
-	python::class_<inSphere,python::bases<Predicate> >("inSphere","Sphere predicate.",python::init<python::tuple,Real>(python::args("center","radius"),"Ctor taking center (as a 3-tuple) and radius"));
-	python::class_<inAlignedBox,python::bases<Predicate> >("inAlignedBox","Axis-aligned box predicate",python::init<python::tuple,python::tuple>(python::args("minAABB","maxAABB"),"Ctor taking minumum and maximum points of the box (as 3-tuples)."));
-	python::class_<inCylinder,python::bases<Predicate> >("inCylinder","Cylinder predicate",python::init<python::tuple,python::tuple,Real>(python::args("centerBottom","centerTop","radius"),"Ctor taking centers of the lateral walls (as 3-tuples) and radius."));
-	python::class_<inHyperboloid,python::bases<Predicate> >("inHyperboloid","Hyperboloid predicate",python::init<python::tuple,python::tuple,Real,Real>(python::args("centerBottom","centerTop","radius","skirt"),"Ctor taking centers of the lateral walls (as 3-tuples), radius at bases and skirt (middle radius)."));
-	python::class_<inEllipsoid,python::bases<Predicate> >("inEllipsoid","Ellipsoid predicate",python::init<python::tuple,python::tuple>(python::args("centerPoint","abc"),"Ctor taking center of the ellipsoid (3-tuple) and its 3 radii (3-tuple)."));
-	python::class_<notInNotch,python::bases<Predicate> >("notInNotch","Outside of infinite, rectangle-shaped notch predicate",python::init<python::tuple,python::tuple,python::tuple,Real>(python::args("centerPoint","edge","normal","aperture"),"Ctor taking point in the symmetry plane, vector pointing along the edge, plane normal and aperture size.\nThe side inside the notch is edge×normal.\nNormal is made perpendicular to the edge.\nAll vectors are normalized at construction time.")); 
+	python::class_<inSphere,python::bases<Predicate> >("inSphere","Sphere predicate.",python::init<const Vector3r&,Real>(python::args("center","radius"),"Ctor taking center (as a 3-tuple) and radius"));
+	python::class_<inAlignedBox,python::bases<Predicate> >("inAlignedBox","Axis-aligned box predicate",python::init<const Vector3r&,const Vector3r&>(python::args("minAABB","maxAABB"),"Ctor taking minumum and maximum points of the box (as 3-tuples)."));
+	python::class_<inCylinder,python::bases<Predicate> >("inCylinder","Cylinder predicate",python::init<const Vector3r&,const Vector3r&,Real>(python::args("centerBottom","centerTop","radius"),"Ctor taking centers of the lateral walls (as 3-tuples) and radius."));
+	python::class_<inHyperboloid,python::bases<Predicate> >("inHyperboloid","Hyperboloid predicate",python::init<const Vector3r&,const Vector3r&,Real,Real>(python::args("centerBottom","centerTop","radius","skirt"),"Ctor taking centers of the lateral walls (as 3-tuples), radius at bases and skirt (middle radius)."));
+	python::class_<inEllipsoid,python::bases<Predicate> >("inEllipsoid","Ellipsoid predicate",python::init<const Vector3r&,const Vector3r&>(python::args("centerPoint","abc"),"Ctor taking center of the ellipsoid (3-tuple) and its 3 radii (3-tuple)."));
+	python::class_<notInNotch,python::bases<Predicate> >("notInNotch","Outside of infinite, rectangle-shaped notch predicate",python::init<const Vector3r&,const Vector3r&,const Vector3r&,Real>(python::args("centerPoint","edge","normal","aperture"),"Ctor taking point in the symmetry plane, vector pointing along the edge, plane normal and aperture size.\nThe side inside the notch is edge×normal.\nNormal is made perpendicular to the edge.\nAll vectors are normalized at construction time.")); 
 	#ifdef YADE_GTS
 		python::class_<inGtsSurface,python::bases<Predicate> >("inGtsSurface","GTS surface predicate",python::init<python::object,python::optional<bool> >(python::args("surface","noPad"),"Ctor taking a gts.Surface() instance, which must not be modified during instance lifetime.\nThe optional noPad can disable padding (if set to True), which speeds up calls several times.\nNote: padding checks inclusion of 6 points along +- cardinal directions in the pad distance from given point, which is not exact."));
 	#endif

Added: trunk/lib/py/_packSpheres.cpp
===================================================================
--- trunk/lib/py/_packSpheres.cpp	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/lib/py/_packSpheres.cpp	2009-07-02 10:09:56 UTC (rev 1830)
@@ -0,0 +1,143 @@
+// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
+#include<boost/python.hpp>
+#include<yade/extra/boost_python_len.hpp>
+#include<yade/lib-base/Logging.hpp>
+#include<yade/lib-base/yadeWm3.hpp>
+#include<yade/lib-base/yadeWm3Extra.hpp>
+// #include<yade/gui-py/_utils.hpp> // will be: yade/lib-py/_utils.hpp> at some point
+#include<Wm3Vector3.h>
+
+#include<yade/core/Omega.hpp>
+#include<yade/core/MetaBody.hpp>
+#include<yade/pkg-common/InteractingSphere.hpp>
+
+#include<yade/extra/Shop.hpp>
+
+using namespace boost;
+using namespace std;
+#ifdef LOG4CXX
+	log4cxx::LoggerPtr logger=log4cxx::Logger::getLogger("yade.pack.spheres");
+#endif
+
+// copied from _packPredicates.cpp :-(
+python::tuple vec2tuple(const Vector3r& v){return boost::python::make_tuple(v[0],v[1],v[2]);}
+Vector3r tuple2vec(const python::tuple& t){return Vector3r(python::extract<double>(t[0])(),python::extract<double>(t[1])(),python::extract<double>(t[2])());}
+Vector3r tuple2vec(python::tuple& t){return Vector3r(python::extract<double>(t[0])(),python::extract<double>(t[1])(),python::extract<double>(t[2])());}
+
+struct SpherePack{
+	struct Sph{ Vector3r c; Real r; Sph(const Vector3r& _c, Real _r): c(_c), r(_r){};
+		python::tuple asTuple() const { return python::make_tuple(c,r); }
+	};
+	vector<Sph> pack;
+	SpherePack(){};
+	SpherePack(const python::list& l){ fromList(l); }
+	// add single sphere
+	void add(const Vector3r& c, Real r){ pack.push_back(Sph(c,r)); }
+	// I/O
+	void fromList(const python::list& l);
+	python::list toList() const;
+	void fromFile(const string file);
+	void toFile(const string file) const;
+	void fromSimulation();
+	// spatial characteristics
+	Vector3r dim() const {Vector3r mn,mx; aabb(mn,mx); return mx-mn;}
+	python::tuple aabb_py() const { Vector3r mn,mx; aabb(mn,mx); return python::make_tuple(mn,mx); }
+	void aabb(Vector3r& mn, Vector3r& mx) const {
+		Real inf=std::numeric_limits<Real>::infinity(); mn=Vector3r(inf,inf,inf); mx=Vector3r(-inf,-inf,-inf);
+		FOREACH(const Sph& s, pack){ Vector3r r(s.r,s.r,s.r); mn=componentMinVector(mn,s.c-r); mx=componentMaxVector(mx,s.c+r);}
+	}
+	Vector3r midPt() const {Vector3r mn,mx; aabb(mn,mx); return .5*(mn+mx);}
+	Real relDensity() const {
+		Real sphVol=0; Vector3r dd=dim();
+		FOREACH(const Sph& s, pack) sphVol+=pow(s.r,3);
+		sphVol*=(4/3.)*Mathr::PI;
+		return sphVol/(dd[0]*dd[1]*dd[2]);
+	}
+	// transformations
+	void translate(const Vector3r& shift){ FOREACH(Sph& s, pack) s.c+=shift; }
+	void rotate(const Vector3r& axis, Real angle){ Vector3r mid=midPt(); Quaternionr q(axis,angle); FOREACH(Sph& s, pack) s.c=q*(s.c-mid)+mid; }
+	void scale(Real scale){ Vector3r mid=midPt(); FOREACH(Sph& s, pack) {s.c=scale*(s.c-mid)+mid; s.r*=abs(scale); } }
+	// iteration 
+	size_t len() const{ return pack.size(); }
+	python::tuple getitem(size_t idx){ if(idx<0 || idx>=pack.size()) throw runtime_error("Index "+lexical_cast<string>(idx)+" out of range 0.."+lexical_cast<string>(pack.size()-1)); return pack[idx].asTuple(); }
+	struct iterator{
+		const SpherePack& sPack; size_t pos;
+		iterator(const SpherePack& _sPack): sPack(_sPack), pos(0){}
+		iterator iter(){ return *this;}
+		python::tuple next(){
+			if(pos==sPack.pack.size()-1){ PyErr_SetNone(PyExc_StopIteration); python::throw_error_already_set(); }
+			return sPack.pack[pos++].asTuple();
+		}
+	};
+	SpherePack::iterator getIterator() const{ return SpherePack::iterator(*this);};
+};
+
+void SpherePack::fromList(const python::list& l){
+	pack.clear();
+	size_t len=python::len(l);
+	for(size_t i=0; i<len; i++){
+		const python::tuple& t=python::extract<python::tuple>(l[i]);
+		const Vector3r t0=python::extract<Vector3r>(t[0]);
+		pack.push_back(Sph(t0,python::extract<double>(t[1])));
+	}
+};
+
+python::list SpherePack::toList() const {
+	python::list ret;
+	FOREACH(const Sph& s, pack) ret.append(python::make_tuple(s.c,s.r));
+	return ret;
+};
+
+void SpherePack::fromFile(string file) {
+	typedef pair<Vector3r,Real> pairVector3rReal;
+	vector<pairVector3rReal> ss;
+	Vector3r mn,mx;
+	ss=Shop::loadSpheresFromFile(file,mn,mx);
+	pack.clear();
+	FOREACH(const pairVector3rReal& s, ss) pack.push_back(Sph(s.first,s.second));
+}
+
+void SpherePack::toFile(const string fname) const {
+	ofstream f(fname.c_str());
+	if(!f.good()) throw runtime_error("Unable to open file `"+fname+"'");
+	FOREACH(const Sph& s, pack) f<<s.c[0]<<" "<<s.c[1]<<" "<<s.c[2]<<" "<<s.r<<endl;
+	f.close();
+};
+
+void SpherePack::fromSimulation() {
+	pack.clear();
+	MetaBody* rootBody=Omega::instance().getRootBody().get();
+	FOREACH(const shared_ptr<Body>& b, *rootBody->bodies){
+		shared_ptr<InteractingSphere>	intSph=dynamic_pointer_cast<InteractingSphere>(b->interactingGeometry);
+		if(!intSph) continue;
+		pack.push_back(Sph(b->physicalParameters->se3.position,intSph->radius));
+	}
+}
+
+
+
+BOOST_PYTHON_MODULE(_packSpheres){
+	python::class_<SpherePack>("SpherePack","Set of spheres as centers and radii",python::init<python::optional<python::list> >(python::args("list"),"Empty constructor, optionally taking list [ ((cx,cy,cz),r), … ] for initial data." ))
+		.def("add",&SpherePack::add,"Add single sphere to packing, given center as 3-tuple and radius")
+		.def("toList",&SpherePack::toList,"Return packing data as python list.")
+		.def("fromList",&SpherePack::fromList,"Make packing from given list, same format as for constructor. Discards current data.")
+		.def("load",&SpherePack::fromFile,"Load packing from external text file (current data will be discarded).")
+		.def("save",&SpherePack::toFile,"Save packing to external text file (will be overwritten).")
+		.def("fromSimulation",&SpherePack::fromSimulation,"Make packing corresponding to the current simulation. Discards current data.")
+		.def("aabb",&SpherePack::aabb_py,"Get axis-aligned bounding box coordinates, as 2 3-tuples.")
+		.def("dim",&SpherePack::dim,"Return dimensions of the packing in terms of aabb(), as a 3-tuple.")
+		.def("center",&SpherePack::midPt,"Return coordinates of the bounding box center.")
+		.def("relDensity",&SpherePack::relDensity,"Relative packing density, measured as sum of spheres' volumes / aabb volume.\n(Sphere overlaps are ignored.)")
+		.def("translate",&SpherePack::translate,"Translate all spheres by given vector.")
+		.def("rotate",&SpherePack::rotate,"Rotate all spheres around packing center (in terms of aabb()), given axis and angle of the rotation.")
+		.def("scale",&SpherePack::scale,"Scale the packing around its center (in terms of aabb()) by given factor (may be negative).")
+		.def("__len__",&SpherePack::len,"Get number of spheres in the packing")
+		.def("__getitem__",&SpherePack::getitem,"Get entry at given index, as tuple of center and radius.")
+		.def("__iter__",&SpherePack::getIterator,"Return iterator over spheres.")
+		;
+	python::class_<SpherePack::iterator>("SpherePackIterator",python::init<SpherePack::iterator&>())
+		.def("__iter__",&SpherePack::iterator::iter)
+		.def("next",&SpherePack::iterator::next)
+	;
+}
+

Modified: trunk/lib/py/_utils.cpp
===================================================================
--- trunk/lib/py/_utils.cpp	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/lib/py/_utils.cpp	2009-07-02 10:09:56 UTC (rev 1830)
@@ -41,7 +41,7 @@
 		maximum=componentMaxVector(maximum,b->physicalParameters->se3.position+(centers?Vector3r::ZERO:rrr));
 	}
 	Vector3r dim=maximum-minimum;
-	return python::make_tuple(vec2tuple(minimum+.5*cutoff*dim),vec2tuple(maximum-.5*cutoff*dim));
+	return python::make_tuple(minimum+.5*cutoff*dim,maximum-.5*cutoff*dim);
 }
 BOOST_PYTHON_FUNCTION_OVERLOADS(aabbExtrema_overloads,aabbExtrema,0,2);
 
@@ -60,7 +60,7 @@
 
 python::tuple coordsAndDisplacements(int axis,python::tuple AABB=python::tuple()){
 	Vector3r bbMin(Vector3r::ZERO), bbMax(Vector3r::ZERO); bool useBB=python::len(AABB)>0;
-	if(useBB){bbMin=tuple2vec(extract<python::tuple>(AABB[0])());bbMax=tuple2vec(extract<python::tuple>(AABB[1])());}
+	if(useBB){bbMin=extract<Vector3r>(AABB[0])();bbMax=extract<Vector3r>(AABB[1])();}
 	python::list retCoord,retDispl;
 	FOREACH(const shared_ptr<Body>&b, *Omega::instance().getRootBody()->bodies){
 		if(useBB && !isInBB(b->physicalParameters->se3.position,bbMin,bbMax)) continue;
@@ -81,7 +81,7 @@
 Real PWaveTimeStep(){return Shop::PWaveTimeStep();};
 
 Real elasticEnergyInAABB(python::tuple AABB){
-	Vector3r bbMin=tuple2vec(extract<python::tuple>(AABB[0])()), bbMax=tuple2vec(extract<python::tuple>(AABB[1])());
+	Vector3r bbMin=extract<Vector3r>(AABB[0])(), bbMax=extract<Vector3r>(AABB[1])();
 	shared_ptr<MetaBody> rb=Omega::instance().getRootBody();
 	Real E=0;
 	FOREACH(const shared_ptr<Interaction>&i, *rb->transientInteractions){
@@ -120,7 +120,7 @@
  */
 python::tuple interactionAnglesHistogram(int axis, int mask=0, size_t bins=20, python::tuple aabb=python::tuple(), Real minProjLen=1e-6){
 	if(axis<0||axis>2) throw invalid_argument("Axis must be from {0,1,2}=x,y,z.");
-	Vector3r bbMin(Vector3r::ZERO), bbMax(Vector3r::ZERO); bool useBB=python::len(aabb)>0; if(useBB){bbMin=tuple2vec(extract<python::tuple>(aabb[0])());bbMax=tuple2vec(extract<python::tuple>(aabb[1])());}
+	Vector3r bbMin(Vector3r::ZERO), bbMax(Vector3r::ZERO); bool useBB=python::len(aabb)>0; if(useBB){bbMin=extract<Vector3r>(aabb[0])();bbMax=extract<Vector3r>(aabb[1])();}
 	Real binStep=Mathr::PI/bins; int axis2=(axis+1)%3, axis3=(axis+2)%3;
 	vector<Real> cummProj(bins,0.);
 	shared_ptr<MetaBody> rb=Omega::instance().getRootBody();
@@ -143,7 +143,7 @@
 BOOST_PYTHON_FUNCTION_OVERLOADS(interactionAnglesHistogram_overloads,interactionAnglesHistogram,1,4);
 
 python::tuple bodyNumInteractionsHistogram(python::tuple aabb=python::tuple()){
-	Vector3r bbMin(Vector3r::ZERO), bbMax(Vector3r::ZERO); bool useBB=python::len(aabb)>0; if(useBB){bbMin=tuple2vec(extract<python::tuple>(aabb[0])());bbMax=tuple2vec(extract<python::tuple>(aabb[1])());}
+	Vector3r bbMin(Vector3r::ZERO), bbMax(Vector3r::ZERO); bool useBB=python::len(aabb)>0; if(useBB){bbMin=extract<Vector3r>(aabb[0])();bbMax=extract<Vector3r>(aabb[1])();}
 	const shared_ptr<MetaBody>& rb=Omega::instance().getRootBody();
 	vector<int> bodyNumInta; bodyNumInta.resize(rb->bodies->size(),-1 /* uninitialized */);
 	int maxInta=0;
@@ -165,9 +165,9 @@
 }
 BOOST_PYTHON_FUNCTION_OVERLOADS(bodyNumInteractionsHistogram_overloads,bodyNumInteractionsHistogram,0,1);
 
-python::tuple inscribedCircleCenter(python::list v0, python::list v1, python::list v2)
+Vector3r inscribedCircleCenter(const Vector3r& v0, const Vector3r& v1, const Vector3r& v2)
 {
-	return vec2tuple(Shop::inscribedCircleCenter(Vector3r(python::extract<double>(v0[0]),python::extract<double>(v0[1]),python::extract<double>(v0[2])), Vector3r(python::extract<double>(v1[0]),python::extract<double>(v1[1]),python::extract<double>(v1[2])), Vector3r(python::extract<double>(v2[0]),python::extract<double>(v2[1]),python::extract<double>(v2[2]))));
+	return Shop::inscribedCircleCenter(v0,v1,v2);
 }
 
 python::dict getViscoelasticFromSpheresInteraction(Real m, Real tc, Real en, Real es)
@@ -199,11 +199,11 @@
  * is position relative to axisPt; moment from moment is m; such moment per body is
  * projected onto axis.
  */
-Real sumBexTorques(python::tuple ids, python::tuple _axis, python::tuple _axisPt){
+Real sumBexTorques(python::tuple ids, const Vector3r& axis, const Vector3r& axisPt){
 	shared_ptr<MetaBody> rb=Omega::instance().getRootBody();
 	rb->bex.sync();
 	Real ret=0;
-	Vector3r axis=tuple2vec(_axis), axisPt=tuple2vec(_axisPt); size_t len=python::len(ids);
+	size_t len=python::len(ids);
 	for(size_t i=0; i<len; i++){
 		const Body* b=(*rb->bodies)[python::extract<int>(ids[i])].get();
 		const Vector3r& m=rb->bex.getTorque(b->getId());
@@ -219,11 +219,11 @@
  * @param direction direction in which forces are summed
  *
  */
-Real sumBexForces(python::tuple ids, python::tuple _direction){
+Real sumBexForces(python::tuple ids, const Vector3r& direction){
 	shared_ptr<MetaBody> rb=Omega::instance().getRootBody();
 	rb->bex.sync();
 	Real ret=0;
-	Vector3r direction=tuple2vec(_direction); size_t len=python::len(ids);
+	size_t len=python::len(ids);
 	for(size_t i=0; i<len; i++){
 		body_id_t id=python::extract<int>(ids[i]);
 		const Vector3r& f=rb->bex.getForce(id);
@@ -325,8 +325,8 @@
 
 	(This could be easily extended to return sum of only normal forces or only of shear forces.)
 */
-python::tuple forcesOnPlane(python::tuple _planePt, python::tuple _normal){
-	Vector3r ret(Vector3r::ZERO), planePt(tuple2vec(_planePt)), normal(tuple2vec(_normal));
+Vector3r forcesOnPlane(const Vector3r& planePt, const Vector3r&  normal){
+	Vector3r ret(Vector3r::ZERO);
 	MetaBody* rootBody=Omega::instance().getRootBody().get();
 	FOREACH(const shared_ptr<Interaction>&I, *rootBody->interactions){
 		if(!I->isReal()) continue;
@@ -342,14 +342,14 @@
 		// otherwise, reverse its contribution
 		ret+=(dot1<0.?1.:-1.)*(nsi->normalForce+nsi->shearForce);
 	}
-	return vec2tuple(ret);
+	return ret;
 }
 
 /* Less general than forcesOnPlane, computes force on plane perpendicular to axis, passing through coordinate coord. */
-python::tuple forcesOnCoordPlane(Real coord, int axis){
+Vector3r forcesOnCoordPlane(Real coord, int axis){
 	Vector3r planePt(Vector3r::ZERO); planePt[axis]=coord;
 	Vector3r normal(Vector3r::ZERO); normal[axis]=1;
-	return forcesOnPlane(vec2tuple(planePt),vec2tuple(normal));
+	return forcesOnPlane(planePt,normal);
 }
 
 
@@ -361,9 +361,8 @@
  * dH_dTheta is the inclination of the spiral (height increase per radian),
  * theta0 is the angle for zero height (by given axis).
  */
-python::tuple spiralProject(python::tuple _pt, Real dH_dTheta, int axis=2, Real periodStart=std::numeric_limits<Real>::quiet_NaN(), Real theta0=0){
+python::tuple spiralProject(const Vector3r& pt, Real dH_dTheta, int axis=2, Real periodStart=std::numeric_limits<Real>::quiet_NaN(), Real theta0=0){
 	int ax1=(axis+1)%3,ax2=(axis+2)%3;
-	Vector3r pt=tuple2vec(_pt);
 	Real r=sqrt(pow(pt[ax1],2)+pow(pt[ax2],2));
 	Real theta;
 	if(r>Mathr::ZERO_TOLERANCE){
@@ -393,7 +392,7 @@
 // for now, don't return anything, since we would have to include the whole yadeControl.cpp because of pyInteraction
 void Shop__createExplicitInteraction(body_id_t id1, body_id_t id2){ (void) Shop::createExplicitInteraction(id1,id2);}
 
-python::tuple Shop__scalarOnColorScale(Real scalar){ return vec2tuple(Shop::scalarOnColorScale(scalar));}
+//Vector3r Shop__scalarOnColorScale(Real scalar){ return Shop::scalarOnColorScale(scalar);}
 
 BOOST_PYTHON_FUNCTION_OVERLOADS(unbalancedForce_overloads,Shop::unbalancedForce,0,1);
 Real Shop__kineticEnergy(){return Shop::kineticEnergy();}
@@ -423,7 +422,7 @@
 	def("createInteraction",Shop__createExplicitInteraction);
 	def("spiralProject",spiralProject,spiralProject_overloads(args("axis","periodStart","theta0")));
 	def("pointInsidePolygon",pointInsidePolygon);
-	def("scalarOnColorScale",Shop__scalarOnColorScale);
+	def("scalarOnColorScale",Shop::scalarOnColorScale);
 	def("highlightNone",highlightNone);
 	def("wireAll",wireAll);
 	def("wireNone",wireNone);

Modified: trunk/lib/py/pack.py
===================================================================
--- trunk/lib/py/pack.py	2009-07-01 18:27:44 UTC (rev 1829)
+++ trunk/lib/py/pack.py	2009-07-02 10:09:56 UTC (rev 1830)
@@ -198,7 +198,6 @@
 			sp.scale(scale)
 			return filterSpherePack(predicate,sp,**kw)
 		print "No suitable packing in database found, running triaxial"
-	#if len(O.bodies)!=0 or len(O.engines)!=0: raise RuntimeError("triaxialPack needs empty simulation (no bodies, no engines) to run.")
 	V=(4/3)*pi*radius**3; N=assumedFinalDensity*fullDim[0]*fullDim[1]*fullDim[2]/V;
 	##
 	O.switchWorld()