yade-dev team mailing list archive
-
yade-dev team
-
Mailing list archive
-
Message #11429
[Branch ~yade-pkg/yade/git-trunk] Rev 3425: Merge github.com:yade/trunk into chaoUnsat
Merge authors:
Anton Gladky (gladky-anton)
Anton Gladky (gladky-anton)
Bruno Chareyre (bruno-chareyre)
Christian Jakob (jakob-ifgt)
Jan Stránský (honzik)
------------------------------------------------------------
revno: 3425 [merge]
committer: Chao Yuan <chaoyuan2012@xxxxxxxxx>
timestamp: Fri 2014-05-23 16:06:21 +0200
message:
Merge github.com:yade/trunk into chaoUnsat
removed:
extra/
extra/floating_point_utilities_v3/
extra/floating_point_utilities_v3/README
extra/floating_point_utilities_v3/boost/
extra/floating_point_utilities_v3/boost/math/
extra/floating_point_utilities_v3/boost/math/detail/
extra/floating_point_utilities_v3/boost/math/detail/fp_traits.hpp
extra/floating_point_utilities_v3/boost/math/fpclassify.hpp
extra/floating_point_utilities_v3/boost/math/nonfinite_num_facets.hpp
extra/floating_point_utilities_v3/boost/math/signbit.hpp
added:
examples/conveyor/
examples/conveyor/conveyor.geo
examples/conveyor/conveyor.mesh
examples/conveyor/conveyor.py
gui/qt4/XYZ.xpm
gui/qt4/YZX.xpm
gui/qt4/ZXY.xpm
gui/qt4/yade-favicon.xpm
modified:
CMakeLists.txt
ChangeLog
core/Body.cpp
core/Body.hpp
core/BodyContainer.cpp
core/BodyContainer.hpp
core/Clump.cpp
core/Clump.hpp
core/Dispatcher.hpp
core/EnergyTracker.hpp
core/FileGenerator.hpp
core/ForceContainer.hpp
core/Functor.hpp
core/InteractionContainer.cpp
core/Omega.cpp
core/Omega.hpp
core/Scene.cpp
core/State.cpp
core/main/pyboot.cpp
doc/sphinx/installation.rst
examples/packs/packs.py
gui/qt4/GLViewer.cpp
gui/qt4/GLViewer.hpp
gui/qt4/GLViewerDisplay.cpp
gui/qt4/GLViewerMouse.cpp
gui/qt4/_GLViewer.cpp
gui/qt4/controller.ui
gui/qt4/img.qrc
lib/factory/DynLibManager.cpp
lib/multimethods/DynLibDispatcher.hpp
lib/serialization/ObjectIO.hpp
lib/serialization/Serializable.cpp
lib/serialization/Serializable.hpp
lib/smoothing/WeightedAverage2d.hpp
lib/triangulation/Network.ipp
pkg/common/Collider.cpp
pkg/common/Collider.hpp
pkg/common/Cylinder.hpp
pkg/common/Facet.cpp
pkg/common/Gl1_NormPhys.cpp
pkg/common/GravityEngines.cpp
pkg/common/Grid.hpp
pkg/common/InsertionSortCollider.cpp
pkg/common/InsertionSortCollider.hpp
pkg/common/InteractionLoop.cpp
pkg/common/InteractionLoop.hpp
pkg/common/MatchMaker.cpp
pkg/common/OpenGLRenderer.cpp
pkg/common/OpenGLRenderer.hpp
pkg/common/ParallelEngine.cpp
pkg/common/ParallelEngine.hpp
pkg/common/Recorder.cpp
pkg/common/ZECollider.cpp
pkg/dem/CapillaryStressRecorder.cpp
pkg/dem/CapillaryTriaxialTest.cpp
pkg/dem/CohFrictMat.hpp
pkg/dem/CohesiveTriaxialTest.cpp
pkg/dem/ConcretePM.cpp
pkg/dem/Disp2DPropLoadEngine.cpp
pkg/dem/DomainLimiter.cpp
pkg/dem/FacetTopologyAnalyzer.cpp
pkg/dem/FlatGridCollider.cpp
pkg/dem/GeneralIntegratorInsertionSortCollider.cpp
pkg/dem/GlobalStiffnessTimeStepper.cpp
pkg/dem/Ig2_Sphere_Sphere_ScGeom.cpp
pkg/dem/Integrator.cpp
pkg/dem/Ip2_CohFrictMat_CohFrictMat_CohFrictPhys.hpp
pkg/dem/JointedCohesiveFrictionalPM.cpp
pkg/dem/KinemCNDEngine.cpp
pkg/dem/KinemCNLEngine.cpp
pkg/dem/KinemCNSEngine.cpp
pkg/dem/KinemCTDEngine.cpp
pkg/dem/NewtonIntegrator.cpp
pkg/dem/NewtonIntegrator.hpp
pkg/dem/PeriIsoCompressor.cpp
pkg/dem/PeriIsoCompressor.hpp
pkg/dem/Polyhedra.cpp
pkg/dem/Polyhedra.hpp
pkg/dem/Polyhedra_Ig2.cpp
pkg/dem/Polyhedra_splitter.cpp
pkg/dem/Polyhedra_support.cpp
pkg/dem/RungeKuttaCashKarp54Integrator.cpp
pkg/dem/RungeKuttaCashKarp54Integrator.hpp
pkg/dem/SampleCapillaryPressureEngine.cpp
pkg/dem/ScGeom.hpp
pkg/dem/Shop.hpp
pkg/dem/Shop_01.cpp
pkg/dem/Shop_02.cpp
pkg/dem/SimpleShear.cpp
pkg/dem/SpherePack.cpp
pkg/dem/SpherePack.hpp
pkg/dem/SpheresFactory.cpp
pkg/dem/TesselationWrapper.cpp
pkg/dem/TesselationWrapper.hpp
pkg/dem/Tetra.cpp
pkg/dem/TriaxialCompressionEngine.cpp
pkg/dem/TriaxialStateRecorder.cpp
pkg/dem/TriaxialStressController.hpp
pkg/dem/TriaxialTest.cpp
pkg/dem/UniaxialStrainer.cpp
pkg/dem/VTKRecorder.cpp
pkg/dem/ViscoelasticCapillarPM.hpp
pkg/pfv/DummyFlowEngine.cpp
pkg/pfv/FlowEngine.hpp
pkg/pfv/SoluteFlowEngine.cpp
py/WeightedAverage2d.cpp
py/_polyhedra_utils.cpp
py/_utils.cpp
py/pack/_packObb.cpp
py/pack/_packSpheres.cpp
py/polyhedra_utils.py
py/wrapper/customConverters.cpp
py/wrapper/yadeWrapper.cpp
py/ymport.py
--
lp:yade
https://code.launchpad.net/~yade-pkg/yade/git-trunk
Your team Yade developers is subscribed to branch lp:yade.
To unsubscribe from this branch go to https://code.launchpad.net/~yade-pkg/yade/git-trunk/+edit-subscription
=== modified file 'CMakeLists.txt'
--- CMakeLists.txt 2014-05-08 07:11:18 +0000
+++ CMakeLists.txt 2014-05-23 13:37:50 +0000
@@ -61,7 +61,7 @@
ENDIF()
#===========================================================
-ADD_DEFINITIONS(" -DYADE_PTR_CAST=static_pointer_cast -DYADE_CAST=static_cast ")
+ADD_DEFINITIONS(" -DYADE_PTR_CAST=boost::static_pointer_cast -DYADE_CAST=static_cast ")
IF (CMAKE_CXX_FLAGS)
#If flags are set, add only neccessary flags
IF (DEBUG)
@@ -87,7 +87,10 @@
#===========================================================
# Add possibility to use local boost installation (e.g. -DLocalBoost=1.46.1)
-FIND_PACKAGE(Boost ${LocalBoost} COMPONENTS python thread filesystem iostreams regex serialization system REQUIRED)
+IF ( NOT LocalBoost )
+ SET(LocalBoost "1.47.0") # Minimal required Boost version
+ENDIF ( NOT LocalBoost )
+FIND_PACKAGE(Boost ${LocalBoost} COMPONENTS python thread filesystem iostreams regex serialization system date_time REQUIRED)
INCLUDE_DIRECTORIES (${Boost_INCLUDE_DIRS})
# for checking purpose
MESSAGE("-- Boost_VERSION: " ${Boost_VERSION})
@@ -324,7 +327,6 @@
ENDIF(ENABLE_GL2PS)
INCLUDE_DIRECTORIES(${PYTHON_INCLUDE_DIRS})
-INCLUDE_DIRECTORIES(${CMAKE_SOURCE_DIR}/extra/floating_point_utilities_v3)
INCLUDE_DIRECTORIES(${CMAKE_BINARY_DIR})
#===========================================================
=== modified file 'ChangeLog'
--- ChangeLog 2014-01-10 20:30:37 +0000
+++ ChangeLog 2014-05-18 15:33:35 +0000
@@ -1,4 +1,249 @@
==================================================
+yade-1.09.0
+Sun, 18 May 2014 17:32:07 +0200
+
+Alexander Eulitz (1):
+ corrected a little bug in description of yadedaily-installation and added example and folder structure for compilation
+
+Anton Gladky (97):
+ Remove RELEASE-file.
+ Fix setting of wall's color.
+ +1 reference.
+ Replace some bazaar-links by github.
+ Update installation instructions.
+ Update INSTALL file.
+ Fix version definition for IPython>1.0.0
+ Fix warning for IPython > 1.0.0
+ Add radiusTopInner, radiusBottomInner to facetCone and facetCylinder.
+ Increase number of steps in checkWeight.py
+ Prevent returning a reference to local temp object.
+ Prevent binding a reference member to a temp. value.
+ Remove notice on the main page about daily packages on Launchpad.
+ Some more changes on the main page.
+ Add Lambert formulation into capillary models.
+ Use enum instead of string to keep capyllar type.
+ Update config of mini-dinstall.
+ Do not ignore k* and c* parameters if mass==0
+ Add billiard example script.
+ Introduce YADE_ODEINT feature
+ Implement binary-arch only builds for yadedaily.
+ Fix split delimiter
+ Fix library name for new openblas.
+ Output some additional messages, when DEBUG mode is enabled.
+ Fix compilation with libqglviewer>=2.5.1
+ Fix compilation with libqglviewer>=2.5.1
+ Add informational message, if VTK6 is found.
+ Disable some debug-messages, because they break compilation.
+ Check, whether manipulatedFrame exist, if not - create it.
+ Set mouse parameters, only if frame is created.
+ Better fix for QGLviewer next version.
+ Fix compilation.
+ Move all force and torque calculation into separate function
+ Move capillary functions out of ViscEl-classes.
+ Implement Soulie capillary model.
+ Add an example to test different capillary models.
+ Deprecate getViscoelasticFromSpheresInteraction.
+ Update examples and test-scripts due to deprecating of getViscoelasticFromSpheresInteraction.
+ Update Warning about last changes.
+ Use MatchMaker to set tc, et and en in ViscEl model
+ Update URL in getViscoelastic
+ Fix compilation in ViscElCap.
+ Minor description update.
+ Replace isnan by isfinite to let the numbers be 0.
+ Remove last capillar-parameters from ViscEl.
+ Remove massMultiply paramter
+ Fix compilation.
+ Implement experimental SPH-model
+ Add gradients and laplacian of the kernel functions.
+ Implement some more kernel functions.
+ Remove duplicated code.
+ Normalize parameters of kernel functions.
+ Produce meaningful error message.
+ Add Cs parameters to particles, visualize them in VTK.
+ Export in VTK some more SPH-parameters.
+ Get a coordination number from body.
+ Use bool return type for force calculation.
+ Add watercolumn example for SPH.
+ Add example script to test different kernel functions.
+ Add README to examples SPH.
+ Fix conflict.
+ Fix eigen3 inclusions.
+ Add one more example for sph.
+ Split all capillary function into smaller one.
+ Add YADE_SPH macroses to fix FTBFS, when SPH disabled
+ Minor fix (replace #ifdef by #endif)
+ Add an opportunity to change liquid volume during simulation.
+ Disable temporarly Cs calculation in SPH.
+ Fix interaction removal in VeiscoElPM
+ Store an information about active liquid contacts.
+ Add -= operator to OpenMPAccumulator.
+ Fix compilation with clang, when openmp is switched off.
+ Add OpenMPVector for thread-safe vector work.
+ Minor fix in installation section of documentation.
+ Export current value from PIDController.
+ Add a note in installation section of docs.
+ Do not link libloki and boost_date_time.
+ Fix scrolling direction for libQGLviewer > 2.5.0
+ One more minor fix in zooming.
+ Implement Liquid Migration model (experimental).
+ Replace LIQCONTROL by LIQMIGRATION.
+ Fix compilation with clang.
+ Set capillary parameters to 0. instead of -1.
+ Fix Id export in ymport.textClumps
+ Remove YADE_DEPREC_DOF_LIST prepocessor.
+ Add blockedMovement parameter to state of body
+ Add conveyor example.
+ Minor fix in documentation/installation.
+ Add mask parameter to NewtonIntegrator
+ Replace png-pictures by xpm.
+ Fix the beginning camera position in GUI.
+ Remove integrateInertia=False from packs.py.
+ Add discretization parameter to appendClumped.
+ Do not use getTorqueUnsynced and forces.getForceUnsynced in clumps
+ Make addForceTorqueFromMembers more readable.
+ Revert last change in Newtonintegrator.
+ One more revert in NewtonIntegrator.
+
+Bruno Chareyre (60):
+ avoid crash when Vh==NULL in FlowEngine. The sphere is ignored in the flow problem, otherwise FlowEngine runs as usual.
+ Merge branch 'master' of github.com:yade/trunk
+ remove redundant "from yade import *" in example scripts, as it mess-up scopes
+ small change in PFV checkTest
+ fix a bug in ISCollider that would create interactions with unbounded bodies
+ remove deprecated code linked to queuing requestErase'd interactions in an older version of the collider
+ Merge pull request #39 from lsibille/master
+ Merge pull request #38 from Kubeu/patch-4
+ Merge pull request #37 from Kubeu/patch-3
+ Merge pull request #36 from Kubeu/patch-2
+ Better behavior of QGLViewer for shift+select and moving bodies (fixes LP bug 806469)
+ let libparmetis be used as an alternative of libmetis
+ Add hideBody/showBody to selectively display bodies in the 3D view
+ Merge pull request #40 from burak-er/master
+ Parallel InsertionSortCollider
+ fix compilation issues for ENABLE_OPENMP=OFF
+ some renaming and code cleaning in PFV code
+ some renaming and code cleaning in PFV code (part2)
+ PFV: First step in refactoring templates
+ dummy engine for showing how to derive from FlowEngine + a preliminary version of DFNFlow
+ make FlowEngine a template yade class
+ Periodic version of flow engine in separate source files
+ PFV: simplify (c++ wise) value assignement to Info types. More refactoring. Final step of code cleaning.
+ fix a bug in PFV code (fictious vetices not defined correctly)
+ minor changes in FlowEngine
+ remove a useless data member
+ fix compile error due to dirty hack (cpp's included by another cpp)
+ Added documentation for changing the velocity gradient of periodic cell
+ TriaxialStressController: reference sample sizes can be modified by users (was previously read-only)
+ ignore *~ files in git status
+ update biblio references
+ Hack YADE_CLASS macro to make it work with c++ templates (introduces a macro for pyClass name different from c++ class name)
+ new YADE_CLASS_PYCLASS_... macro, missing in previous commit
+ update bibliographic reference in a script
+ introduce CellInfo::getInfo() for more generic interpolation between triangulations
+ better detection of changes in Cell::velGrad
+ fix the example script periodic-simple-shear.py
+ - introduce SoluteFlowEngine (from Thomas Sweijen) - move Flow classes to a separate folder
+ fix include paths after moving files to pkg/pfv
+ fix include path pkg/pfv
+ Bugfixes in PeriodicFlowEngine, as discussed with Donia
+ remove useless FlowBoundingSphere.cpp
+ fix https://bugs.launchpad.net/yade/+bug/1301443
+ undef flag, so SoluteFlow doesn't break compilation on buildbot.
+ update about openblas+openmp on 12.04
+ initialize CellInfo members (avoids hardly detectable bugs) + remove artifact facets from loop when cell1==cell2
+ remove an inacurate reference, introduce another one
+ fix bad link to capillary files
+ clean of commented blocks
+ Merge pull request #43 from bchareyre/pc
+ fix gravity checkScript (es -> 'et')
+ enable run/pause from QGLViewer (retun key) + fix compile warning
+ remove empty file
+ add FlowEngine::doInterpolate to force interpolation during mesh swap
+ Add user defined boundary condition to FlowEngine
+ add authors in files headers
+ -fix bibliographic link
+ add missing #ifdef, breaking compilation without LINSOLV + better volume computation
+ fix compile error in 298f0b6
+ switch to 1-thread colliding when problem detected in parallel run (fix https://bugs.launchpad.net/yade/+bug/1314736)
+
+Burak Er (1):
+ added an adaptive Runge Kutta integrator scheme. Also, added an example using this integrator.
+
+Christian Jakob (15):
+ allow user to set an output folder for PFV-based saveVtk() method
+ Merge branch 'master' of github.com:yade/trunk
+ fix compilation bug in InsertionSortCollider.hpp
+ fix a bug in inertia tensor calculation for clumps if integrateInertia=True
+ extend/fix replaceByClumps() method for multiple overlapping clump templates
+ absorb bool integrateInertia from Clump::updateProperties by int discretization
+ Merge branch 'master' of github.com:yade/trunk
+ Parallelize replaceByClumps(): drastically reduce generation time of clump replacement if discretization>0
+ fix bugs in Clump::updateProperties, fixes https://bugs.launchpad.net/yade/+bug/1273172
+ introduce updateClumpProperties() method in yadeWrapper - can be used e.g. when clumps are imported in yade
+ update of O.bodies.erase(): it can erase clump members too when erasing a clump
+ Merge branch 'master' of github.com:yade/trunk
+ remove typenames from Polyhedra.cpp (fixes compiler error)
+ let ymport.textClumps() return all ids from members and clumps
+ fix some indents
+
+Francois (2):
+ Undo modifications about ViscElMat into Ip2_FrictMat_FrictMat_FrictPhys. The young modulus and poisson ratio have to be set for both materials to perform a contact between a frictMat body and a viscElMat body. Add a comment for that.
+ Fix 2 bugs linked to the Grids : - in utils.py : remove a factor 2 in the calculation of the bending stiffness kr. - in Grid.cpp : fix a bug that occured in the Sphere-GridConnection contact. The contact was not detected in a very specific case : if the sphere was next to a node and the node goes from a convex (angle>180°) form to a concav (angle<180°) form.
+
+Jan Stransky (13):
+ added vtk export of polyhedral particles
+ improvement of previous commit (vtk polyhedra export)
+ added example of paraview sphere "solid sections" improvement of export.textExt function to support arbitrary quantity export
+ added O.stopAtTime (question246284)
+ chenged return type of O.stopAtTime from previous commit
+ fixed some errors and warnings for documentation build
+ one more little info inside code
+ export.VTKExporter: improved comments, fixed bug (thanks Jan Havelka for reporting), updated corresponding example script
+ code cleanup in ConcretePM, fixed one more bug in export.VTKExporter
+ added exportContactPoints function to exporter.VTKExporter, updated example script
+ fixed export.VTKExporter.exportContactPoints for nonexisting interactions
+ Polyhedra implementation improvement (Contributed by Jan Elias)
+ modification of utils.calm function (bug 1318513)
+
+Jerome Duriez (15):
+ Change in the doc of ymport.text/textExt to better reflect the behaviour
+ A doc sentence for pericell recorder in VTKRecorder
+ Typo in doc of CohFric Law2 : the shear adhesion is a_s, not a_n
+ Typos and link syntax in doc of CohFrictPhys
+ Typo correction in porosity() doc : porosity instead of poro sity (in 2 words)
+ Use of correct version of requestErase() in JCFpm (https://bugs.launchpad.net/yade/+bug/1273775)
+ Small changes in JCFpm IP logic : it is now possible to have new contacts that are always cohesive, and "poisson"=0 is possible (=> ks = 0 rather than infinity...)
+ Small improvement in JCFPM doc about the cracks file, and typo in user.rst
+ Mistake in hyperlink previous commit
+ Copy paste mistake in State and typo UniaxialStrainer doc
+ Proposal of correction of UniaxialStrainer, in relation with https://bugs.launchpad.net/yade/+bug/1300167
+ Add of an external reference, about the "derivation" of bodyStressTensor
+ Correction of copy-paste mistake in doc of Bound
+ Hyperlink about sortAxis in InsertionSortCollider doc
+ Minor changes (not affecting results) in these scripts towards an easier understanding
+
+Klaus Thoeni (2):
+ Correct shear stiffness averaging for Ip2_FrictMat_FrictMat_ViscoFrictPhys
+ new simple contact law with normal viscose damping which allows to specify kn and ks/kn in Ip2
+
+Kubeu (3):
+ Added Antons hint to first install external depencies of Yade before following installation instructions
+ small typo fix
+ typofix
+
+Luc Sibille (10):
+ add test on alphaKtw to allow nil value of twisting stiffness
+ engine to compute a fluid flow with the lattice Boltzmann method LBM
+ Definition of the basic elements used by the LBM engine
+ definition of the compilation option ENABLE_LBMFLOW to make the compilation of the LBM engine optional, this option is disable by default
+ remove all LBM file
+ Merge remote-tracking branch 'upstream/master'
+ definition of the LBM engine inside a lbm directory, with license GPLv2
+ definition of the compilation option ENABLE_LBMFLOW to make the compilation of the LBM engine optional, this option is disable by default
+ A buoyancy example for the DEM-LBM coupling
+ Merge branch 'master' of github.com:yade/trunk
+
+==================================================
yade-1.07.0
Fri, 10 Jan 2014 21:23:33 +0100
=== modified file 'core/Body.cpp'
--- core/Body.cpp 2014-04-09 14:03:16 +0000
+++ core/Body.cpp 2014-05-23 13:05:19 +0000
@@ -12,8 +12,8 @@
const shared_ptr<Body>& Body::byId(Body::id_t _id, shared_ptr<Scene> rb){return (*(rb->bodies))[_id];}
// return list of interactions of this particle
-python::list Body::py_intrs(){
- python::list ret;
+boost::python::list Body::py_intrs(){
+ boost::python::list ret;
for(Body::MapId2IntrT::iterator it=this->intrs.begin(),end=this->intrs.end(); it!=end; ++it) { //Iterate over all bodie's interactions
if(!(*it).second->isReal()) continue;
ret.append((*it).second);
=== modified file 'core/Body.hpp'
--- core/Body.hpp 2014-05-08 05:57:04 +0000
+++ core/Body.hpp 2014-05-23 13:05:19 +0000
@@ -62,7 +62,7 @@
* (otherwise, GLViewer would depend on Clump and therefore Clump would have to go to core...) */
virtual void userForcedDisplacementRedrawHook(){return;}
- python::list py_intrs();
+ boost::python::list py_intrs();
Body::id_t getId() const {return id;};
unsigned int coordNumber(); // Number of neighboring particles
@@ -95,8 +95,8 @@
((Real,Cs,0.0,, "Color field (only for SPH-model)")) // [Mueller2003], (15)
#endif
#ifdef YADE_LIQMIGRATION
- ((Real,Vf, -1.0,, "Individual amount of liquid"))
- ((Real,Vmin,-1.0,, "Minimal amount of liquid"))
+ ((Real,Vf, 0.0,, "Individual amount of liquid"))
+ ((Real,Vmin, 0.0,, "Minimal amount of liquid"))
#endif
,
/* ctor */,
=== modified file 'core/BodyContainer.cpp'
--- core/BodyContainer.cpp 2013-02-19 06:53:16 +0000
+++ core/BodyContainer.cpp 2014-05-21 12:37:11 +0000
@@ -46,30 +46,42 @@
scene->doSort = true;
body[id]=b;
+
+ // Notify ForceContainer about new id
+ scene->forces.addMaxId(id);
return id;
}
-bool BodyContainer::erase(Body::id_t id){
+bool BodyContainer::erase(Body::id_t id, bool eraseClumpMembers){//default is false (as before)
if(!exists(id)) return false;
lowestFree=min(lowestFree,id);
- const shared_ptr<Body>& b=Body::byId(id); //If the body is the last member of clump, the clump should be removed as well
+ const shared_ptr<Body>& b=Body::byId(id);
+
if ((b) and (b->isClumpMember())) {
const shared_ptr<Body>& clumpBody=Body::byId(b->clumpId);
const shared_ptr<Clump> clump=YADE_PTR_CAST<Clump>(clumpBody->shape);
Clump::del(clumpBody, b);
- if (clump->members.size()==0) { //Clump has no members any more. Remove it
- this->erase(b->clumpId);
+ if (clump->members.size()==0) this->erase(b->clumpId,false); //Clump has no members any more. Remove it
+ }
+
+ if ((b) and (b->isClump())){
+ //erase all members if eraseClumpMembers is true:
+ const shared_ptr<Clump>& clump=YADE_PTR_CAST<Clump>(b->shape);
+ std::map<Body::id_t,Se3r>& members = clump->members;
+ FOREACH(MemberMap::value_type& mm, members){
+ const Body::id_t& memberId=mm.first;
+ if (eraseClumpMembers) this->erase(memberId,false); // erase members
+ //when the last members is erased, the clump will be erased automatically, see above
+ else Body::byId(memberId)->clumpId=Body::id_t(-1); // make members standalones
}
}
-
const shared_ptr<Scene>& scene=Omega::instance().getScene();
- for(Body::MapId2IntrT::iterator it=b->intrs.begin(),end=b->intrs.end(); it!=end; ++it) { //Iterate over all bodie's interactions
+ for(Body::MapId2IntrT::iterator it=b->intrs.begin(),end=b->intrs.end(); it!=end; ++it) { //Iterate over all body's interactions
scene->interactions->requestErase((*it).second);
}
body[id]=shared_ptr<Body>();
return true;
}
-
=== modified file 'core/BodyContainer.hpp'
--- core/BodyContainer.hpp 2013-03-06 17:30:45 +0000
+++ core/BodyContainer.hpp 2014-05-15 17:50:26 +0000
@@ -34,6 +34,7 @@
class BodyContainer: public Serializable{
private:
typedef std::vector<shared_ptr<Body> > ContainerT;
+ typedef std::map<Body::id_t,Se3r> MemberMap;
ContainerT body;
Body::id_t lowestFree;
Body::id_t findFreeId();
@@ -86,7 +87,7 @@
const shared_ptr<Body>& operator[](unsigned int id) const { return body[id]; }
bool exists(Body::id_t id) const { return (id>=0) && ((size_t)id<body.size()) && ((bool)body[id]); }
- bool erase(Body::id_t id);
+ bool erase(Body::id_t id, bool eraseClumpMembers);
REGISTER_CLASS_AND_BASE(BodyContainer,Serializable);
REGISTER_ATTRIBUTES(Serializable,(body));
=== modified file 'core/Clump.cpp'
--- core/Clump.cpp 2014-03-15 15:30:36 +0000
+++ core/Clump.cpp 2014-05-23 13:05:19 +0000
@@ -10,10 +10,10 @@
YADE_PLUGIN((Clump));
CREATE_LOGGER(Clump);
-python::dict Clump::members_get(){
- python::dict ret;
+boost::python::dict Clump::members_get(){
+ boost::python::dict ret;
FOREACH(MemberMap::value_type& b, members){
- ret[b.first]=python::make_tuple(b.second.position,b.second.orientation);
+ ret[b.first]=boost::python::make_tuple(b.second.position,b.second.orientation);
}
return ret;
}
@@ -21,8 +21,8 @@
void Clump::add(const shared_ptr<Body>& clumpBody, const shared_ptr<Body>& subBody){
Body::id_t subId=subBody->getId();
const shared_ptr<Clump> clump=YADE_PTR_CAST<Clump>(clumpBody->shape);
- if(clump->members.count(subId)!=0) throw std::invalid_argument(("Body #"+lexical_cast<string>(subId)+" is already part of this clump #"+lexical_cast<string>(clumpBody->id)).c_str());
- if(subBody->isClumpMember()) throw std::invalid_argument(("Body #"+lexical_cast<string>(subId)+" is already a clump member of #"+lexical_cast<string>(subBody->clumpId)).c_str());
+ if(clump->members.count(subId)!=0) throw std::invalid_argument(("Body #"+boost::lexical_cast<string>(subId)+" is already part of this clump #"+boost::lexical_cast<string>(clumpBody->id)).c_str());
+ if(subBody->isClumpMember()) throw std::invalid_argument(("Body #"+boost::lexical_cast<string>(subId)+" is already a clump member of #"+boost::lexical_cast<string>(subBody->clumpId)).c_str());
else if(subBody->isClump()){
const shared_ptr<Clump> subClump=YADE_PTR_CAST<Clump>(subBody->shape);
FOREACH(const MemberMap::value_type& mm, subClump->members){
@@ -48,15 +48,19 @@
void Clump::del(const shared_ptr<Body>& clumpBody, const shared_ptr<Body>& subBody){
// erase the subBody; removing body that is not part of the clump throws
const shared_ptr<Clump> clump=YADE_PTR_CAST<Clump>(clumpBody->shape);
- if(clump->members.erase(subBody->id)!=1) throw std::invalid_argument(("Body #"+lexical_cast<string>(subBody->id)+" not part of clump #"+lexical_cast<string>(clumpBody->id)+"; not removing.").c_str());
+ if(clump->members.erase(subBody->id)!=1) throw std::invalid_argument(("Body #"+boost::lexical_cast<string>(subBody->id)+" not part of clump #"+boost::lexical_cast<string>(clumpBody->id)+"; not removing.").c_str());
subBody->clumpId=Body::ID_NONE;
LOG_DEBUG("Removed body #"<<subBody->id<<" from clump #"<<clumpBody->id);
}
void Clump::addForceTorqueFromMembers(const State* clumpState, Scene* scene, Vector3r& F, Vector3r& T){
FOREACH(const MemberMap::value_type& mm, members){
- const Body::id_t& memberId=mm.first; const shared_ptr<Body>& member=Body::byId(memberId,scene); assert(member->isClumpMember()); State* memberState=member->state.get();
- const Vector3r& f=scene->forces.getForce(memberId); const Vector3r& t=scene->forces.getTorque(memberId);
+ const Body::id_t& memberId=mm.first;
+ const shared_ptr<Body>& member=Body::byId(memberId,scene);
+ assert(member->isClumpMember());
+ State* memberState=member->state.get();
+ const Vector3r& f=scene->forces.getForce(memberId);
+ const Vector3r& t=scene->forces.getTorque(memberId);
F+=f;
T+=t+(memberState->pos-clumpState->pos).cross(f);
}
=== modified file 'core/Clump.hpp'
--- core/Clump.hpp 2014-02-27 08:27:24 +0000
+++ core/Clump.hpp 2014-05-23 13:05:19 +0000
@@ -97,7 +97,7 @@
//! Recalculate body's inertia tensor in rotated coordinates.
static Matrix3r inertiaTensorRotate(const Matrix3r& I, const Quaternionr& rot);
- python::dict members_get();
+ boost::python::dict members_get();
YADE_CLASS_BASE_DOC_ATTRS_CTOR_PY(Clump,Shape,"Rigid aggregate of bodies",
((MemberMap,members,,Attr::hidden,"Ids and relative positions+orientations of members of the clump (should not be accessed directly)"))
=== modified file 'core/Dispatcher.hpp'
--- core/Dispatcher.hpp 2010-11-07 11:46:20 +0000
+++ core/Dispatcher.hpp 2014-05-23 13:05:19 +0000
@@ -40,17 +40,17 @@
#define _YADE_DIM_DISPATCHER_FUNCTOR_DOC_ATTRS_CTOR_PY(Dim,DispatcherT,FunctorT,doc,attrs,ctor,py) \
typedef FunctorT FunctorType; \
void updateScenePtr(){ FOREACH(shared_ptr<FunctorT> f, functors){ f->scene=scene; }} \
- void postLoad(DispatcherT&){ clearMatrix(); FOREACH(shared_ptr<FunctorT> f, functors) add(static_pointer_cast<FunctorT>(f)); } \
+ void postLoad(DispatcherT&){ clearMatrix(); FOREACH(shared_ptr<FunctorT> f, functors) add(boost::static_pointer_cast<FunctorT>(f)); } \
virtual void add(FunctorT* f){ add(shared_ptr<FunctorT>(f)); } \
virtual void add(shared_ptr<FunctorT> f){ bool dupe=false; string fn=f->getClassName(); FOREACH(const shared_ptr<FunctorT>& f, functors) { if(fn==f->getClassName()) dupe=true; } if(!dupe) functors.push_back(f); addFunctor(f); } \
BOOST_PP_CAT(_YADE_DISPATCHER,BOOST_PP_CAT(Dim,D_FUNCTOR_ADD))(FunctorT,f) \
boost::python::list functors_get(void) const { boost::python::list ret; FOREACH(const shared_ptr<FunctorT>& f, functors){ ret.append(f); } return ret; } \
void functors_set(const vector<shared_ptr<FunctorT> >& ff){ functors.clear(); FOREACH(const shared_ptr<FunctorT>& f, ff) add(f); postLoad(*this); } \
- void pyHandleCustomCtorArgs(python::tuple& t, python::dict& d){ if(python::len(t)==0)return; if(python::len(t)!=1) throw invalid_argument("Exactly one list of " BOOST_PP_STRINGIZE(FunctorT) " must be given."); typedef std::vector<shared_ptr<FunctorT> > vecF; vecF vf=boost::python::extract<vecF>(t[0])(); functors_set(vf); t=python::tuple(); } \
+ void pyHandleCustomCtorArgs(boost::python::tuple& t, boost::python::dict& d){ if(boost::python::len(t)==0)return; if(boost::python::len(t)!=1) throw invalid_argument("Exactly one list of " BOOST_PP_STRINGIZE(FunctorT) " must be given."); typedef std::vector<shared_ptr<FunctorT> > vecF; vecF vf=boost::python::extract<vecF>(t[0])(); functors_set(vf); t=boost::python::tuple(); } \
YADE_CLASS_BASE_DOC_ATTRS_CTOR_PY(DispatcherT,Dispatcher,"Dispatcher calling :yref:`functors<" BOOST_PP_STRINGIZE(FunctorT) ">` based on received argument type(s).\n\n" doc, \
((vector<shared_ptr<FunctorT> >,functors,,,"Functors active in the dispatch mechanism [overridden below].")) /*additional attrs*/ attrs, \
/*ctor*/ ctor, /*py*/ py .add_property("functors",&DispatcherT::functors_get,&DispatcherT::functors_set,"Functors associated with this dispatcher." " :yattrtype:`vector<shared_ptr<" BOOST_PP_STRINGIZE(FunctorT) "> >` ") \
- .def("dispMatrix",&DispatcherT::dump,python::arg("names")=true,"Return dictionary with contents of the dispatch matrix.").def("dispFunctor",&DispatcherT::getFunctor,"Return functor that would be dispatched for given argument(s); None if no dispatch; ambiguous dispatch throws."); \
+ .def("dispMatrix",&DispatcherT::dump,boost::python::arg("names")=true,"Return dictionary with contents of the dispatch matrix.").def("dispFunctor",&DispatcherT::getFunctor,"Return functor that would be dispatched for given argument(s); None if no dispatch; ambiguous dispatch throws."); \
)
#define YADE_DISPATCHER1D_FUNCTOR_DOC_ATTRS_CTOR_PY(DispatcherT,FunctorT,doc,attrs,ctor,py) _YADE_DIM_DISPATCHER_FUNCTOR_DOC_ATTRS_CTOR_PY(1,DispatcherT,FunctorT,doc,attrs,ctor,py)
@@ -65,13 +65,13 @@
s*/
template<class topIndexable>
std::string Dispatcher_indexToClassName(int idx){
- scoped_ptr<topIndexable> top(new topIndexable);
+ boost::scoped_ptr<topIndexable> top(new topIndexable);
std::string topName=top->getClassName();
typedef std::pair<string,DynlibDescriptor> classItemType;
FOREACH(classItemType clss, Omega::instance().getDynlibsDescriptor()){
if(Omega::instance().isInheritingFrom_recursive(clss.first,topName) || clss.first==topName){
// create instance, to ask for index
- shared_ptr<topIndexable> inst=dynamic_pointer_cast<topIndexable>(ClassFactory::instance().createShared(clss.first));
+ shared_ptr<topIndexable> inst=boost::dynamic_pointer_cast<topIndexable>(ClassFactory::instance().createShared(clss.first));
assert(inst);
if(inst->getClassIndex()<0 && inst->getClassName()!=top->getClassName()){
throw logic_error("Class "+inst->getClassName()+" didn't use REGISTER_CLASS_INDEX("+inst->getClassName()+","+top->getClassName()+") and/or forgot to call createIndex() in the ctor. [[ Please fix that! ]]");
@@ -88,8 +88,8 @@
//! Return sequence (hierarchy) of class indices of given indexable; optionally convert to names
template<typename TopIndexable>
-python::list Indexable_getClassIndices(const shared_ptr<TopIndexable> i, bool convertToNames){
- int depth=1; python::list ret; int idx0=i->getClassIndex();
+boost::python::list Indexable_getClassIndices(const shared_ptr<TopIndexable> i, bool convertToNames){
+ int depth=1; boost::python::list ret; int idx0=i->getClassIndex();
if(convertToNames) ret.append(Dispatcher_indexToClassName<TopIndexable>(idx0));
else ret.append(idx0);
if(idx0<0) return ret; // don't continue and call getBaseClassIndex(), since we are at the top already
@@ -107,7 +107,7 @@
template<typename DispatcherT>
std::vector<shared_ptr<typename DispatcherT::functorType> > Dispatcher_functors_get(shared_ptr<DispatcherT> self){
std::vector<shared_ptr<typename DispatcherT::functorType> > ret;
- FOREACH(const shared_ptr<Functor>& functor, self->functors){ shared_ptr<typename DispatcherT::functorType> functorRightType(dynamic_pointer_cast<typename DispatcherT::functorType>(functor)); if(!functorRightType) throw logic_error("Internal error: Dispatcher of type "+self->getClassName()+" did not contain Functor of the required type "+typeid(typename DispatcherT::functorType).name()+"?"); ret.push_back(functorRightType); }
+ FOREACH(const shared_ptr<Functor>& functor, self->functors){ shared_ptr<typename DispatcherT::functorType> functorRightType(boost::dynamic_pointer_cast<typename DispatcherT::functorType>(functor)); if(!functorRightType) throw logic_error("Internal error: Dispatcher of type "+self->getClassName()+" did not contain Functor of the required type "+typeid(typename DispatcherT::functorType).name()+"?"); ret.push_back(functorRightType); }
return ret;
}
@@ -150,13 +150,13 @@
typedef DynLibDispatcher<TYPELIST_1(baseClass),FunctorType,typename FunctorType::ReturnType,typename FunctorType::ArgumentTypes,autoSymmetry> dispatcherBase;
shared_ptr<FunctorType> getFunctor(shared_ptr<baseClass> arg){ return dispatcherBase::getExecutor(arg); }
- python::dict dump(bool convertIndicesToNames){
- python::dict ret;
+ boost::python::dict dump(bool convertIndicesToNames){
+ boost::python::dict ret;
FOREACH(const DynLibDispatcher_Item1D& item, dispatcherBase::dataDispatchMatrix1D()){
if(convertIndicesToNames){
string arg1=Dispatcher_indexToClassName<argType1>(item.ix1);
- ret[python::make_tuple(arg1)]=item.functorName;
- } else ret[python::make_tuple(item.ix1)]=item.functorName;
+ ret[boost::python::make_tuple(arg1)]=item.functorName;
+ } else ret[boost::python::make_tuple(item.ix1)]=item.functorName;
}
return ret;
}
@@ -201,13 +201,13 @@
typedef FunctorType functorType;
typedef DynLibDispatcher<TYPELIST_2(baseClass1,baseClass2),FunctorType,typename FunctorType::ReturnType,typename FunctorType::ArgumentTypes,autoSymmetry> dispatcherBase;
shared_ptr<FunctorType> getFunctor(shared_ptr<baseClass1> arg1, shared_ptr<baseClass2> arg2){ return dispatcherBase::getExecutor(arg1,arg2); }
- python::dict dump(bool convertIndicesToNames){
- python::dict ret;
+ boost::python::dict dump(bool convertIndicesToNames){
+ boost::python::dict ret;
FOREACH(const DynLibDispatcher_Item2D& item, dispatcherBase::dataDispatchMatrix2D()){
if(convertIndicesToNames){
string arg1=Dispatcher_indexToClassName<argType1>(item.ix1), arg2=Dispatcher_indexToClassName<argType2>(item.ix2);
- ret[python::make_tuple(arg1,arg2)]=item.functorName;
- } else ret[python::make_tuple(item.ix1,item.ix2)]=item.functorName;
+ ret[boost::python::make_tuple(arg1,arg2)]=item.functorName;
+ } else ret[boost::python::make_tuple(item.ix1,item.ix2)]=item.functorName;
}
return ret;
}
=== modified file 'core/EnergyTracker.hpp'
--- core/EnergyTracker.hpp 2013-03-28 12:02:15 +0000
+++ core/EnergyTracker.hpp 2014-05-23 13:03:50 +0000
@@ -36,7 +36,7 @@
}
Real getItem_py(const std::string& name){
int id=-1; findId(name,id,false,false);
- if (id<0) {PyErr_SetString(PyExc_KeyError,("Unknown energy name '"+name+"'.").c_str()); python::throw_error_already_set(); }
+ if (id<0) {PyErr_SetString(PyExc_KeyError,("Unknown energy name '"+name+"'.").c_str()); py::throw_error_already_set(); }
return energies.get(id);
}
void setItem_py(const std::string& name, Real val){
=== modified file 'core/FileGenerator.hpp'
--- core/FileGenerator.hpp 2010-11-07 11:46:20 +0000
+++ core/FileGenerator.hpp 2014-05-23 13:05:19 +0000
@@ -31,7 +31,7 @@
/*attrs*/,
/*ctor*/
,
- .def("generate",&FileGenerator::pyGenerate,(python::arg("out")),"Generate scene, save to given file")
+ .def("generate",&FileGenerator::pyGenerate,(boost::python::arg("out")),"Generate scene, save to given file")
.def("load",&FileGenerator::pyLoad,"Generate scene, save to temporary file and load immediately");
);
DECLARE_LOGGER;
=== modified file 'core/ForceContainer.hpp'
--- core/ForceContainer.hpp 2014-01-20 16:13:36 +0000
+++ core/ForceContainer.hpp 2014-05-21 12:37:11 +0000
@@ -50,6 +50,7 @@
std::vector<vvector> _torqueData;
std::vector<vvector> _moveData;
std::vector<vvector> _rotData;
+ std::vector<Body::id_t> _maxId;
vvector _force, _torque, _move, _rot, _permForce, _permTorque;
std::vector<size_t> sizeOfThreads;
size_t size;
@@ -62,8 +63,10 @@
inline void ensureSize(Body::id_t id, int threadN){
assert(nThreads>omp_get_thread_num());
- if (threadN<0) resizePerm(min((size_t)1.5*(id+100),(size_t)(id+2000)));
- else if (sizeOfThreads[threadN]<=(size_t)id) resize(min((size_t)1.5*(id+100),(size_t)(id+2000)),threadN);
+ const Body::id_t idMaxTmp = max(id, _maxId[threadN]);
+ _maxId[threadN] = 0;
+ if (threadN<0) resizePerm(min((size_t)1.5*(idMaxTmp+100),(size_t)(idMaxTmp+2000)));
+ else if (sizeOfThreads[threadN]<=(size_t)idMaxTmp) resize(min((size_t)1.5*(idMaxTmp+100),(size_t)(idMaxTmp+2000)),threadN);
}
inline void ensureSynced(){ if(!synced) throw runtime_error("ForceContainer not thread-synchronized; call sync() first!"); }
@@ -78,6 +81,7 @@
_forceData.push_back(vvector()); _torqueData.push_back(vvector());
_moveData.push_back(vvector()); _rotData.push_back(vvector());
sizeOfThreads.push_back(0);
+ _maxId.push_back(0);
}
}
const Vector3r& getForce(Body::id_t id) { ensureSynced(); return ((size_t)id<size)?_force[id]:_zero; }
@@ -88,6 +92,7 @@
void addMove(Body::id_t id, const Vector3r& m) { ensureSize(id,omp_get_thread_num()); synced=false; moveRotUsed=true; _moveData[omp_get_thread_num()][id]+=m;}
const Vector3r& getRot(Body::id_t id) { ensureSynced(); return ((size_t)id<size)?_rot[id]:_zero; }
void addRot(Body::id_t id, const Vector3r& r) { ensureSize(id,omp_get_thread_num()); synced=false; moveRotUsed=true; _rotData[omp_get_thread_num()][id]+=r;}
+ void addMaxId(Body::id_t id) { _maxId[omp_get_thread_num()]=id;}
void addPermForce(Body::id_t id, const Vector3r& f){ ensureSize(id,-1); synced=false; _permForce[id]=f; permForceUsed=true;}
void addPermTorque(Body::id_t id, const Vector3r& t){ ensureSize(id,-1); synced=false; _permTorque[id]=t; permForceUsed=true;}
@@ -97,8 +102,10 @@
/*! Function to allow friend classes to get force even if not synced. Used for clumps by NewtonIntegrator.
* Dangerous! The caller must know what it is doing! (i.e. don't read after write
* for a particular body id. */
- Vector3r& getForceUnsynced (Body::id_t id){return ((size_t)id<size)?_force[id]:_zero;}
- Vector3r& getTorqueUnsynced(Body::id_t id){return ((size_t)id<size)?_torque[id]:_zero;}
+ const Vector3r& getForceUnsynced (Body::id_t id){assert ((size_t)id<size); return _force[id];}
+ const Vector3r& getTorqueUnsynced(Body::id_t id){assert ((size_t)id<size); return _torque[id];}
+ void addForceUnsynced(Body::id_t id, const Vector3r& f){ assert ((size_t)id<size); _force[id]+=f; }
+ void addTorqueUnsynced(Body::id_t id, const Vector3r& m){ assert ((size_t)id<size); _torque[id]+=m; }
/* To be benchmarked: sum thread data in getForce/getTorque upon request for each body individually instead of by the sync() function globally */
// this function is used from python so that running simulation is not slowed down by sync'ing on occasions
@@ -209,9 +216,14 @@
std::vector<Vector3r> _move;
std::vector<Vector3r> _rot;
std::vector<Vector3r> _permForce, _permTorque;
+ Body::id_t _maxId;
size_t size;
size_t permSize;
- inline void ensureSize(Body::id_t id){ if(size<=(size_t)id) resize(min((size_t)1.5*(id+100),(size_t)(id+2000)));}
+ inline void ensureSize(Body::id_t id){
+ const Body::id_t idMaxTmp = max(id, _maxId);
+ _maxId = 0;
+ if(size<=(size_t)idMaxTmp) resize(min((size_t)1.5*(idMaxTmp+100),(size_t)(idMaxTmp+2000)));
+ }
#if 0
const Vector3r& getForceUnsynced (Body::id_t id){ return getForce(id);}
const Vector3r& getTorqueUnsynced(Body::id_t id){ return getForce(id);}
@@ -220,7 +232,7 @@
// dummy function to avoid template resolution failure
friend class boost::serialization::access; template<class ArchiveT> void serialize(ArchiveT & ar, unsigned int version){}
public:
- ForceContainer(): size(0), permSize(0), moveRotUsed(false), permForceUsed(false), syncCount(0), lastReset(0){}
+ ForceContainer(): size(0), permSize(0), moveRotUsed(false), permForceUsed(false), syncCount(0), lastReset(0), _maxId(0){}
const Vector3r& getForce(Body::id_t id){ensureSize(id); return _force[id];}
void addForce(Body::id_t id,const Vector3r& f){ensureSize(id); _force[id]+=f;}
const Vector3r& getTorque(Body::id_t id){ensureSize(id); return _torque[id];}
@@ -231,6 +243,7 @@
void addRot(Body::id_t id,const Vector3r& f){ensureSize(id); moveRotUsed=true; _rot[id]+=f;}
void addPermForce(Body::id_t id, const Vector3r& f){ ensureSize(id); _permForce[id]=f; permForceUsed=true;}
void addPermTorque(Body::id_t id, const Vector3r& t){ ensureSize(id); _permTorque[id]=t; permForceUsed=true;}
+ void addMaxId(Body::id_t id) { _maxId=id;}
const Vector3r& getPermForce(Body::id_t id) { ensureSize(id); return _permForce[id]; }
const Vector3r& getPermTorque(Body::id_t id) { ensureSize(id); return _permTorque[id]; }
// single getters do the same as globally synced ones in the non-parallel flavor
=== modified file 'core/Functor.hpp'
--- core/Functor.hpp 2013-09-27 12:11:28 +0000
+++ core/Functor.hpp 2014-05-23 13:05:19 +0000
@@ -50,7 +50,7 @@
{
public:
typedef _DispatchType1 DispatchType1; typedef _ReturnType ReturnType; typedef _ArgumentTypes ArgumentTypes;
- #define FUNCTOR1D(type1) public: std::string get1DFunctorType1(void){return string(#type1);} int checkArgTypes(const shared_ptr<DispatchType1>& arg1){ return (bool)dynamic_pointer_cast<type1>(arg1)?1:0; }
+ #define FUNCTOR1D(type1) public: std::string get1DFunctorType1(void){return string(#type1);} int checkArgTypes(const shared_ptr<DispatchType1>& arg1){ return (bool)boost::dynamic_pointer_cast<type1>(arg1)?1:0; }
virtual std::string get1DFunctorType1(void){throw runtime_error("Class "+this->getClassName()+" did not use FUNCTOR1D to declare its argument type?"); }
virtual vector<string> getFunctorTypes(void){vector<string> ret; ret.push_back(get1DFunctorType1()); return ret;};
// check that the object can be correctly cast to the derived class handled by the functor (will be used if ever utils.createInteraction can be called with list of functors only)
@@ -72,7 +72,7 @@
{
public:
typedef _DispatchType1 DispatchType1; typedef _DispatchType2 DispatchType2; typedef _ReturnType ReturnType; typedef _ArgumentTypes ArgumentTypes;
- #define FUNCTOR2D(type1,type2) public: std::string get2DFunctorType1(void){return string(#type1);}; std::string get2DFunctorType2(void){return string(#type2);}; int checkArgTypes(const shared_ptr<DispatchType1>& arg1, const shared_ptr<DispatchType2>& arg2){ if(dynamic_pointer_cast<type1>(arg1)&&dynamic_pointer_cast<type2>(arg2)) return 1; if(dynamic_pointer_cast<type1>(arg2)&&dynamic_pointer_cast<type2>(arg1)) return -1; return 0; }
+ #define FUNCTOR2D(type1,type2) public: std::string get2DFunctorType1(void){return string(#type1);}; std::string get2DFunctorType2(void){return string(#type2);}; int checkArgTypes(const shared_ptr<DispatchType1>& arg1, const shared_ptr<DispatchType2>& arg2){ if(boost::dynamic_pointer_cast<type1>(arg1)&&boost::dynamic_pointer_cast<type2>(arg2)) return 1; if(boost::dynamic_pointer_cast<type1>(arg2)&&boost::dynamic_pointer_cast<type2>(arg1)) return -1; return 0; }
virtual std::string get2DFunctorType1(void){throw logic_error("Class "+this->getClassName()+" did not use FUNCTOR2D to declare its argument types?");}
virtual std::string get2DFunctorType2(void){throw logic_error("Class "+this->getClassName()+" did not use FUNCTOR2D to declare its argument types?");}
virtual vector<string> getFunctorTypes(){vector<string> ret; ret.push_back(get2DFunctorType1()); ret.push_back(get2DFunctorType2()); return ret;};
=== modified file 'core/InteractionContainer.cpp'
--- core/InteractionContainer.cpp 2014-02-03 11:21:42 +0000
+++ core/InteractionContainer.cpp 2014-05-23 13:05:19 +0000
@@ -79,7 +79,7 @@
}
}
if(linIx<0) {
- LOG_ERROR("InteractionContainer::erase: attempt to delete interaction with a deleted body (the definition of linPos in the call to erase() should fix the problem) for ##"+lexical_cast<string>(id1)+"+"+lexical_cast<string>(id2));
+ LOG_ERROR("InteractionContainer::erase: attempt to delete interaction with a deleted body (the definition of linPos in the call to erase() should fix the problem) for ##"+boost::lexical_cast<string>(id1)+"+"+boost::lexical_cast<string>(id2));
return false;}
// iid is not the last element; we have to move last one to its place
if (linIx<(int)currSize-1) {
=== modified file 'core/Omega.cpp'
--- core/Omega.cpp 2012-02-13 11:17:02 +0000
+++ core/Omega.cpp 2014-05-23 13:05:19 +0000
@@ -82,14 +82,14 @@
}
void Omega::cleanupTemps(){
- filesystem::path tmpPath(tmpFileDir);
- filesystem::remove_all(tmpPath);
+ boost::filesystem::path tmpPath(tmpFileDir);
+ boost::filesystem::remove_all(tmpPath);
}
std::string Omega::tmpFilename(){
if(tmpFileDir.empty()) throw runtime_error("tmpFileDir empty; Omega::initTemps not yet called()?");
boost::mutex::scoped_lock lock(tmpFileCounterMutex);
- return tmpFileDir+"/tmp-"+lexical_cast<string>(tmpFileCounter++);
+ return tmpFileDir+"/tmp-"+boost::lexical_cast<string>(tmpFileCounter++);
}
void Omega::reset(){
@@ -145,9 +145,9 @@
try {
LOG_DEBUG("Factoring plugin "<<name);
f = ClassFactory::instance().createShared(name);
- dynlibs[name].isIndexable = dynamic_pointer_cast<Indexable>(f);
- dynlibs[name].isFactorable = dynamic_pointer_cast<Factorable>(f);
- dynlibs[name].isSerializable = dynamic_pointer_cast<Serializable>(f);
+ dynlibs[name].isIndexable = boost::dynamic_pointer_cast<Indexable>(f);
+ dynlibs[name].isFactorable = boost::dynamic_pointer_cast<Factorable>(f);
+ dynlibs[name].isSerializable = boost::dynamic_pointer_cast<Serializable>(f);
for(int i=0;i<f->getBaseClassNumber();i++){
dynlibs[name].baseClasses.insert(f->getBaseClassName(i));
}
@@ -167,7 +167,7 @@
if(getenv("YADE_DEBUG")) cerr<<endl<<"[[[ Round "<<i<<" ]]]: ";
std::list<string> done;
for(std::list<string>::iterator I=pythonables.begin(); I!=pythonables.end(); ){
- shared_ptr<Serializable> s=static_pointer_cast<Serializable>(ClassFactory::instance().createShared(*I));
+ shared_ptr<Serializable> s=boost::static_pointer_cast<Serializable>(ClassFactory::instance().createShared(*I));
try{
if(getenv("YADE_DEBUG")) cerr<<"{{"<<*I<<"}}";
s->pyRegisterClass(wrapperScope);
@@ -236,8 +236,8 @@
}
void Omega::loadSimulation(const string& f, bool quiet){
- bool isMem=algorithm::starts_with(f,":memory:");
- if(!isMem && !filesystem::exists(f)) throw runtime_error("Simulation file to load doesn't exist: "+f);
+ bool isMem=boost::algorithm::starts_with(f,":memory:");
+ if(!isMem && !boost::filesystem::exists(f)) throw runtime_error("Simulation file to load doesn't exist: "+f);
if(isMem && memSavedSimulations.count(f)==0) throw runtime_error("Cannot load nonexistent memory-saved simulation "+f);
if(!quiet) LOG_INFO("Loading file "+f);
@@ -269,7 +269,7 @@
//shared_ptr<Scene> scene = getScene();
shared_ptr<Scene>& scene = scenes[currentSceneNb];
//shared_ptr<Scene>& scene = getScene();
- if(algorithm::starts_with(f,":memory:")){
+ if(boost::algorithm::starts_with(f,":memory:")){
if(memSavedSimulations.count(f)>0 && !quiet) LOG_INFO("Overwriting in-memory saved simulation "<<f);
ostringstream oss;
yade::ObjectIO::save<typeof(scene),boost::archive::binary_oarchive>(oss,"scene",scene);
=== modified file 'core/Omega.hpp'
--- core/Omega.hpp 2012-02-13 11:17:02 +0000
+++ core/Omega.hpp 2014-05-23 13:03:50 +0000
@@ -48,7 +48,6 @@
class Scene;
class ThreadRunner;
-using namespace boost;
using namespace boost::posix_time;
using namespace std;
=== modified file 'core/Scene.cpp'
--- core/Scene.cpp 2014-05-08 05:57:04 +0000
+++ core/Scene.cpp 2014-05-23 13:05:19 +0000
@@ -46,7 +46,7 @@
string gecos(pw->pw_gecos), gecos2; size_t p=gecos.find(","); if(p!=string::npos) boost::algorithm::erase_tail(gecos,gecos.size()-p); for(size_t i=0;i<gecos.size();i++){gecos2.push_back(((unsigned char)gecos[i])<128 ? gecos[i] : '?'); }
tags.push_back(boost::algorithm::replace_all_copy(string("author=")+gecos2+" ("+string(pw->pw_name)+"@"+hostname+")"," ","~"));
tags.push_back(string("isoTime="+boost::posix_time::to_iso_string(boost::posix_time::second_clock::local_time())));
- string id=boost::posix_time::to_iso_string(boost::posix_time::second_clock::local_time())+"p"+lexical_cast<string>(getpid());
+ string id=boost::posix_time::to_iso_string(boost::posix_time::second_clock::local_time())+"p"+boost::lexical_cast<string>(getpid());
tags.push_back("id="+id);
tags.push_back("d.id="+id);
tags.push_back("id.d="+id);
@@ -150,7 +150,7 @@
bool Scene::timeStepperPresent(){
int n=0;
FOREACH(const shared_ptr<Engine>&e, engines){ if(dynamic_cast<TimeStepper*>(e.get())) n++; }
- if(n>1) throw std::runtime_error(string("Multiple ("+lexical_cast<string>(n)+") TimeSteppers in the simulation?!").c_str());
+ if(n>1) throw std::runtime_error(string("Multiple ("+boost::lexical_cast<string>(n)+") TimeSteppers in the simulation?!").c_str());
return n>0;
}
@@ -159,7 +159,7 @@
FOREACH(const shared_ptr<Engine>&e, engines){
TimeStepper* ts=dynamic_cast<TimeStepper*>(e.get()); if(ts) { ret=ts->active; n++; }
}
- if(n>1) throw std::runtime_error(string("Multiple ("+lexical_cast<string>(n)+") TimeSteppers in the simulation?!").c_str());
+ if(n>1) throw std::runtime_error(string("Multiple ("+boost::lexical_cast<string>(n)+") TimeSteppers in the simulation?!").c_str());
return ret;
}
@@ -169,7 +169,7 @@
TimeStepper* ts=dynamic_cast<TimeStepper*>(e.get());
if(ts) { ts->setActive(a); n++; }
}
- if(n>1) throw std::runtime_error(string("Multiple ("+lexical_cast<string>(n)+") TimeSteppers in the simulation?!").c_str());
+ if(n>1) throw std::runtime_error(string("Multiple ("+boost::lexical_cast<string>(n)+") TimeSteppers in the simulation?!").c_str());
return n>0;
}
@@ -178,9 +178,9 @@
void Scene::checkStateTypes(){
FOREACH(const shared_ptr<Body>& b, *bodies){
if(!b || !b->material) continue;
- if(b->material && !b->state) throw std::runtime_error("Body #"+lexical_cast<string>(b->getId())+": has Body::material, but NULL Body::state.");
+ if(b->material && !b->state) throw std::runtime_error("Body #"+boost::lexical_cast<string>(b->getId())+": has Body::material, but NULL Body::state.");
if(!b->material->stateTypeOk(b->state.get())){
- throw std::runtime_error("Body #"+lexical_cast<string>(b->getId())+": Body::material type "+b->material->getClassName()+" doesn't correspond to Body::state type "+b->state->getClassName()+" (should be "+b->material->newAssocState()->getClassName()+" instead).");
+ throw std::runtime_error("Body #"+boost::lexical_cast<string>(b->getId())+": Body::material type "+b->material->getClassName()+" doesn't correspond to Body::state type "+b->state->getClassName()+" (should be "+b->material->newAssocState()->getClassName()+" instead).");
}
}
}
=== modified file 'core/State.cpp'
--- core/State.cpp 2010-12-15 12:48:11 +0000
+++ core/State.cpp 2014-05-23 13:05:19 +0000
@@ -21,36 +21,12 @@
return ret;
}
-#ifdef YADE_DEPREC_DOF_LIST
-// support deprecated syntax, later take std::string arg directly (more efficient)
-void State::blockedDOFs_vec_set(const python::object& dofs0){
- python::extract<std::string> dofStr(dofs0);
- python::extract<std::vector<std::string> > dofLst(dofs0);
+void State::blockedDOFs_vec_set(const std::string& dofs){
blockedDOFs=0;
- if(dofStr.check()){
- string dofs(dofStr());
-#else
- void State::blockedDOFs_vec_set(const std::string& dofs){
- blockedDOFs=0;
-#endif
FOREACH(char c, dofs){
#define _GET_DOF(DOF_ANY,ch) if(c==ch) { blockedDOFs|=State::DOF_ANY; continue; }
_GET_DOF(DOF_X,'x'); _GET_DOF(DOF_Y,'y'); _GET_DOF(DOF_Z,'z'); _GET_DOF(DOF_RX,'X'); _GET_DOF(DOF_RY,'Y'); _GET_DOF(DOF_RZ,'Z');
#undef _GET_DOF
- throw std::invalid_argument("Invalid DOF specification `"+lexical_cast<string>(c)+"' in '"+dofs+"', characters must be ∈{x,y,z,X,Y,Z}.");
- }
-#ifdef YADE_DEPREC_DOF_LIST
- } else
- if(dofLst.check()){
- LOG_WARN("Specifying State.blockedDOFs as list ['x','y','rx','rz'] is deprecated, use string 'xyXZ' instead.");
- FOREACH(const std::string s, dofLst()){
- #define _GET_DOF(DOF_ANY,str) if(s==str) { blockedDOFs|=State::DOF_ANY; continue; }
- _GET_DOF(DOF_X,"x"); _GET_DOF(DOF_Y,"y"); _GET_DOF(DOF_Z,"z"); _GET_DOF(DOF_RX,"rx"); _GET_DOF(DOF_RY,"ry"); _GET_DOF(DOF_RZ,"rz");
- #undef _GET_DOF
- throw std::invalid_argument("Invalid DOF specification `"+s+"', must be ∈{x,y,z,rx,ry,rz}.");
- }
- } else {
- throw std::invalid_argument("Invalid type: State.blockedDOFs must be either list of strings or string.");
+ throw std::invalid_argument("Invalid DOF specification `"+boost::lexical_cast<string>(c)+"' in '"+dofs+"', characters must be ∈{x,y,z,X,Y,Z}.");
}
-#endif
}
=== modified file 'core/main/pyboot.cpp'
--- core/main/pyboot.cpp 2012-04-13 16:27:00 +0000
+++ core/main/pyboot.cpp 2014-05-23 13:20:43 +0000
@@ -26,7 +26,7 @@
#endif
/* Initialize yade, loading given plugins */
-void yadeInitialize(python::list& pp, const std::string& confDir){
+void yadeInitialize(boost::python::list& pp, const std::string& confDir){
PyEval_InitThreads();
@@ -38,16 +38,16 @@
#ifdef YADE_DEBUG
ofstream gdbBatch;
O.gdbCrashBatch=O.tmpFilename();
- gdbBatch.open(O.gdbCrashBatch.c_str()); gdbBatch<<"attach "<<lexical_cast<string>(getpid())<<"\nset pagination off\nthread info\nthread apply all backtrace\ndetach\nquit\n"; gdbBatch.close();
+ gdbBatch.open(O.gdbCrashBatch.c_str()); gdbBatch<<"attach "<<boost::lexical_cast<string>(getpid())<<"\nset pagination off\nthread info\nthread apply all backtrace\ndetach\nquit\n"; gdbBatch.close();
signal(SIGABRT,crashHandler);
signal(SIGSEGV,crashHandler);
#endif
- vector<string> ppp; for(int i=0; i<python::len(pp); i++) ppp.push_back(python::extract<string>(pp[i]));
+ vector<string> ppp; for(int i=0; i<boost::python::len(pp); i++) ppp.push_back(boost::python::extract<string>(pp[i]));
Omega::instance().loadPlugins(ppp);
}
void yadeFinalize(){ Omega::instance().cleanupTemps(); }
BOOST_PYTHON_MODULE(boot){
- python::scope().attr("initialize")=&yadeInitialize;
- python::scope().attr("finalize")=&yadeFinalize; //,"Finalize yade (only to be used internally).")
+ boost::python::scope().attr("initialize")=&yadeInitialize;
+ boost::python::scope().attr("finalize")=&yadeFinalize; //,"Finalize yade (only to be used internally).")
}
=== modified file 'doc/sphinx/installation.rst'
--- doc/sphinx/installation.rst 2014-04-26 12:37:18 +0000
+++ doc/sphinx/installation.rst 2014-05-14 12:31:59 +0000
@@ -26,7 +26,8 @@
sudo apt-get install yadedaily
If you have another distribution, not Ubuntu Precise (Version 12.04), be sure to use the
-correct name in the first line (for instance, jessie, trusty or wheezy).
+correct name in the first line (for instance, jessie, trusty or wheezy). For the list
+of currently supported distributions, please visit `yade-dem.org/packages <http://yade-dem.org/packages/>`_.
After that you can normally start Yade using "yadedaily" or "yadedaily-batch" command.
yadedaily on older distributions can have some disabled features due to older library
=== added directory 'examples/conveyor'
=== added file 'examples/conveyor/conveyor.geo'
--- examples/conveyor/conveyor.geo 1970-01-01 00:00:00 +0000
+++ examples/conveyor/conveyor.geo 2014-05-15 14:47:33 +0000
@@ -0,0 +1,24 @@
+acc = 100.0;
+wid = 500.0;
+len = 1500.0;
+h = 300.0;
+Point(1) = {0, 0, -wid/5.0, acc};
+Point(2) = {-wid, 0, 0, acc};
+Point(3) = {wid, 0, 0, acc};
+Point(4) = {wid/1.1, 0, -wid/10.0, acc};
+Point(5) = {-wid/1.1, 0, -wid/10.0, acc};
+Point(6) = {wid/2.0, 0, +wid/10.0, acc};
+Point(7) = {-wid/2.0, 0, +wid/10.0, acc};
+Point(8) = {-wid, 0, h, acc};
+Point(9) = {wid, 0, h, acc};
+
+Spline(1) = {2, 5, 7, 1, 6, 4, 3};
+Line(2) = {8, 2};
+Line(3) = {3, 9};
+
+Extrude {0, len, 0} {
+ Line{2, 1, 3};
+}
+Line(16) = {8, 9};
+Line Loop(17) = {16, -3, -1, -2};
+Plane Surface(18) = {17};
=== added file 'examples/conveyor/conveyor.mesh'
--- examples/conveyor/conveyor.mesh 1970-01-01 00:00:00 +0000
+++ examples/conveyor/conveyor.mesh 2014-05-15 14:47:33 +0000
@@ -0,0 +1,1360 @@
+ MeshVersionFormatted 2
+ Dimension
+ 3
+ Vertices
+ 441
+ 0 0 -100 1
+ -500 0 0 2
+ 500 0 0 3
+ 454.54545454545 0 -50 4
+ -454.54545454545 0 -50 5
+ 250 0 50 6
+ -250 0 50 7
+ -500 0 300 8
+ 500 0 300 9
+ -500 1500 300 10
+ -500 1500 0 11
+ -454.54545454545 1500 -50 13
+ -250 1500 50 14
+ 0 1500 -100 15
+ 250 1500 50 16
+ 454.54545454545 1500 -50 17
+ 500 1500 0 18
+ 500 1500 300 20
+ -439.88134513266 0 -44.523673195083 1
+ -362.83621367891 0 7.7663721559698 1
+ -279.5676899846 0 48.28686863902 1
+ -192.63906004976 0 24.407224564095 1
+ -120.43749167986 0 -34.43426658243 1
+ -44.683026495718 0 -88.284497185875 1
+ 44.683026492925 0 -88.284497187232 1
+ 120.43749167789 0 -34.434266584101 1
+ 192.63906004808 0 24.407224562925 1
+ 279.56768998311 0 48.286868639328 1
+ 362.83621367809 0 7.7663721565244 1
+ 439.88134513224 0 -44.523673194873 1
+ -500 0 199.99999999993 2
+ -500 0 100.00000000007 2
+ 500 0 99.999999999799 3
+ 500 0 199.99999999973 3
+ -500 1500 199.99999999993 4
+ -500 1500 100.00000000007 4
+ -500 99.99999999974 300 5
+ -500 199.99999999954 300 5
+ -500 299.9999999991 300 5
+ -500 399.99999999856 300 5
+ -500 499.99999999802 300 5
+ -500 599.99999999783 300 5
+ -500 699.99999999767 300 5
+ -500 799.99999999751 300 5
+ -500 899.99999999735 300 5
+ -500 999.99999999719 300 5
+ -500 1099.9999999976 300 5
+ -500 1199.9999999982 300 5
+ -500 1299.9999999988 300 5
+ -500 1399.9999999994 300 5
+ -500 99.99999999974 0 6
+ -500 199.99999999954 0 6
+ -500 299.9999999991 0 6
+ -500 399.99999999856 0 6
+ -500 499.99999999802 0 6
+ -500 599.99999999783 0 6
+ -500 699.99999999767 0 6
+ -500 799.99999999751 0 6
+ -500 899.99999999735 0 6
+ -500 999.99999999719 0 6
+ -500 1099.9999999976 0 6
+ -500 1199.9999999982 0 6
+ -500 1299.9999999988 0 6
+ -500 1399.9999999994 0 6
+ -439.88134513266 1500 -44.523673195083 8
+ -362.83621367891 1500 7.7663721559698 8
+ -279.5676899846 1500 48.28686863902 8
+ -192.63906004976 1500 24.407224564095 8
+ -120.43749167986 1500 -34.43426658243 8
+ -44.683026495718 1500 -88.284497185875 8
+ 44.683026492925 1500 -88.284497187232 8
+ 120.43749167789 1500 -34.434266584101 8
+ 192.63906004808 1500 24.407224562925 8
+ 279.56768998311 1500 48.286868639328 8
+ 362.83621367809 1500 7.7663721565244 8
+ 439.88134513224 1500 -44.523673194873 8
+ 500 99.99999999974 0 10
+ 500 199.99999999954 0 10
+ 500 299.9999999991 0 10
+ 500 399.99999999856 0 10
+ 500 499.99999999802 0 10
+ 500 599.99999999783 0 10
+ 500 699.99999999767 0 10
+ 500 799.99999999751 0 10
+ 500 899.99999999735 0 10
+ 500 999.99999999719 0 10
+ 500 1099.9999999976 0 10
+ 500 1199.9999999982 0 10
+ 500 1299.9999999988 0 10
+ 500 1399.9999999994 0 10
+ 500 1500 99.999999999799 12
+ 500 1500 199.99999999973 12
+ 500 99.99999999974 300 14
+ 500 199.99999999954 300 14
+ 500 299.9999999991 300 14
+ 500 399.99999999856 300 14
+ 500 499.99999999802 300 14
+ 500 599.99999999783 300 14
+ 500 699.99999999767 300 14
+ 500 799.99999999751 300 14
+ 500 899.99999999735 300 14
+ 500 999.99999999719 300 14
+ 500 1099.9999999976 300 14
+ 500 1199.9999999982 300 14
+ 500 1299.9999999988 300 14
+ 500 1399.9999999994 300 14
+ -400 0 300 16
+ -300.00000000001 0 300 16
+ -200.00000000004 0 300 16
+ -100.00000000004 0 300 16
+ -3.3310243452433E-11 0 300 16
+ 100.00000000002 0 300 16
+ 200.00000000001 0 300 16
+ 300.00000000001 0 300 16
+ 400 0 300 16
+ -500 166.21866874528 159.75083113068 7
+ -500 437.50117236506 152.20689287958 7
+ -500 847.01463282802 108.35835794242 7
+ -500 641.54811440665 141.65047276936 7
+ -500 978.50960553792 115.54626313201 7
+ -500 1205.1158731829 155.62785850948 7
+ -500 1275.2154194998 134.24489795919 7
+ -500 1059.1178455821 159.10491705026 7
+ -500 80.559548921413 165.40972915315 7
+ -500 113.2787192178 79.530785309051 7
+ -500 1371.1997701567 92.47834235736 7
+ -500 1353.9062404729 208.03589526189 7
+ -500 1254.2112854197 222.28488129946 7
+ -500 249.35196470432 203.88033646342 7
+ -500 595.25949073613 87.458267312908 7
+ -500 597.26401796604 210.0001937624 7
+ -500 346.20055023987 110.69787810395 7
+ -500 356.85084344219 219.31650052337 7
+ -500 516.09027078317 225.68095328363 7
+ -500 511.0783337831 77.682192335459 7
+ -500 1023.6013345509 221.35896129905 7
+ -500 1072.0922729334 82.897678152178 7
+ -500 1141.3361476427 211.69845363885 7
+ -500 1182.0415109408 70.096898961194 7
+ -500 684.28898227798 222.3506005235 7
+ -500 439.81221755297 241.87863305981 7
+ -500 433.5270543112 67.926479981809 7
+ -500 1435.7815677179 153.40975585569 7
+ -500 1439.5833956784 69.944297514942 7
+ -500 1127.7703161142 135.86182216961 7
+ -500 143.00440867938 228.18820355302 7
+ -500 550.69893928777 150.92856580591 7
+ -500 738.18256634503 138.1205525456 7
+ -500 1437.937561638 232.2891302235 7
+ -500 64.712791520106 238.71958654122 7
+ -500 930.70198521745 216.73436690612 7
+ -500 229.17498381765 92.309971834517 7
+ -500 804.2836506274 231.74006879719 7
+ -500 674.47653904811 72.009760258069 7
+ -500 751.93474764327 63.697734149218 7
+ -258.49815801904 1029.4446306734 50.490543174729 11
+ 309.07637276422 1171.6185479741 38.624632032514 11
+ -270.40838069042 432.3630421446 49.797575832967 11
+ -26.306785135095 946.40040159306 -95.685421778899 11
+ -209.97018344876 169.03774510529 35.43184071908 11
+ 201.08759170351 177.37803505227 30.047367485698 11
+ -451.78233766894 185.07400082333 -49.333692609851 11
+ 328.98271125587 611.6050344343 28.789561461469 11
+ 311.34132002391 870.14747751944 37.623917688882 11
+ -447.55034424496 77.647293211656 -47.933990016274 11
+ 407.71950478472 85.104464311252 -24.151431465974 11
+ 407.55190260049 1416.9120732463 -24.032832326847 11
+ -97.422052017176 406.07097805139 -53.412800205045 11
+ -83.770206775152 1113.8009069829 -63.887058139507 11
+ 206.19118130886 1011.735002295 33.215188364471 11
+ 177.58966387898 446.38366347476 13.346917582037 11
+ 119.9558204085 850.25993541261 -34.842583911559 11
+ 175.99436683117 632.11986994507 12.111465695579 11
+ -68.155810485193 1415.7951850061 -74.793824963828 11
+ 227.82206333622 1159.5120405972 44.172520628839 11
+ -177.83320932462 625.9531930534 13.534589779048 11
+ -97.146145060625 791.4361678918 -53.631541140496 11
+ -93.212553875755 688.35369809189 -56.720808906719 11
+ -77.040358411636 292.23411294469 -68.746861236776 11
+ -234.37092786247 350.94502372983 46.54610663453 11
+ 203.44347612981 360.57451196451 31.533595378719 11
+ -287.18256766009 119.28686302678 46.450366032262 11
+ -269.48199587244 1125.1435438346 49.905009251172 11
+ 240.24355351527 1412.88810685 48.231877048281 11
+ 126.05598202086 1305.5534575256 -29.650935066679 11
+ 259.89966174213 100.49209202871 50.489402140543 11
+ 129.66047250954 106.68342009124 -26.56722844088 11
+ 46.697698548582 990.97061970115 -87.289261550043 11
+ -149.4951393717 1417.3813847219 -9.5951112503981 11
+ 52.15486248165 1254.6116946328 -84.429236720891 11
+ 244.07980919212 274.06350743544 49.088219795251 11
+ 420.0358721711 440.59816786922 -32.645715280822 11
+ -231.45106264402 1386.9049738033 45.54934014485 11
+ 352.26473871125 263.20521892359 14.790387939939 11
+ 280.73468247852 198.42758057584 48.03830606846 11
+ 292.6007688904 1335.674727326 44.848300300521 11
+ -75.978854312104 189.74893543627 -69.49240850829 11
+ 296.58657921327 985.9607533456 43.522671661154 11
+ -282.45100426722 245.21181034342 47.650731046031 11
+ 98.839469930576 1155.4364327048 -52.285014258655 11
+ -163.66962936343 332.60337180353 2.2514734490401 11
+ -186.51908212567 439.97566477397 20.050146054677 11
+ 1.4522518129397 1423.0442896469 -99.985727420668 11
+ -338.51051373454 643.3799980435 23.341680137276 11
+ -180.67517392215 1086.1095146987 15.705442983906 11
+ -202.97413221105 270.08273531094 31.240714534771 11
+ -249.55868635503 804.00294098247 49.94996929506 11
+ 285.87042393378 708.47308446107 46.802276695553 11
+ -188.78712862376 1191.6293111452 21.689273482676 11
+ 55.797339260116 455.73697880727 -82.392940736399 11
+ 120.20587043 1030.2975113349 -34.630653828654 11
+ -24.090812569112 782.18111792408 -96.355186508028 11
+ -7.1072128383882 1054.0310793571 -99.664500712601 11
+ -66.956314108988 1001.4379215797 -75.574922686281 11
+ 249.34685730137 623.15672871309 49.924902238811 11
+ -123.75987670644 527.73354371515 -31.609859183523 11
+ 264.62598635727 432.09141387938 50.32392571906 11
+ 100.08686689976 949.74798629097 -51.287047846811 11
+ -53.906937050527 591.31161694133 -83.4620814547 11
+ -102.69964000375 1310.6803203086 -49.180953442472 11
+ -6.2396948345539 248.26366943128 -99.740662744245 11
+ -104.72175284324 945.94630095175 -47.537138191795 11
+ -248.09123443661 915.5417294035 49.762427529082 11
+ 6.4731570902513 372.78578040125 -99.72110845657 11
+ 172.20037999608 799.81486599712 9.1325714571594 11
+ -121.28692164862 1203.8875763276 -33.713439908897 11
+ -415.22853967963 1077.8420651703 -29.3913374699 11
+ -141.22315436968 228.32457348158 -16.651480982012 11
+ 7.4462599644253 83.587440752646 -99.632139812808 11
+ 52.483239910439 169.90535986743 -84.249736032651 11
+ -170.7266472537 745.50251875714 7.9609625593085 11
+ 348.16289970859 1078.9477658949 17.416853386858 11
+ 208.55713442011 531.2110868512 34.616405500207 11
+ 231.59806876608 917.79952773124 45.601935732933 11
+ 425.88084607278 171.99429524159 -36.45270232898 11
+ 151.67806186767 1410.4104382475 -7.7461039123897 11
+ -146.1350176708 108.06444736426 -12.453415260621 11
+ -130.16589366105 1023.5468692542 -26.134199908089 11
+ 34.200901552608 882.03568944359 -92.894706615011 11
+ 162.71248541762 942.10659606129 1.4657235837283 11
+ -480.39957878992 361.26974901204 -45.547631263764 11
+ -183.92598145533 984.41891125181 18.143056587304 11
+ 182.24273858785 76.179882064658 16.887165343022 11
+ 66.963611810091 71.392922984506 -75.570197268982 11
+ 209.98304630872 717.6140932054 35.439188318634 11
+ 57.699293536969 1085.5405492856 -81.291077075812 11
+ 245.6197871922 808.43026773307 49.374493752924 11
+ 281.52778398243 336.69260355381 47.862442686452 11
+ -249.96691906775 601.56296659448 49.996352730081 11
+ -159.15878602663 866.31010423584 -1.4722056472899 11
+ 482.57558464313 786.80303061173 -43.140736728993 11
+ 30.888610431698 554.20830937121 -94.140714057626 11
+ -216.71866629312 525.12372672567 39.091436612403 11
+ -63.324115242945 862.94261578761 -77.885184610607 11
+ 103.3394141155 613.95769637398 -48.662131529352 11
+ -404.4822752824 749.15962038261 -21.851120361267 11
+ 18.413753435568 682.07191406862 -97.830406143302 11
+ 113.1305584928 390.34647681009 -40.588953623835 11
+ -251.61511078231 691.22477697689 50.161168273409 11
+ 184.96170438063 863.82095477681 18.908884429568 11
+ 477.89354767936 1314.4164033175 -47.543940465301 11
+ -25.874554778003 484.99517724402 -95.82009112161 11
+ 441.88143922639 527.20399071122 -45.502460858978 11
+ 121.85166237216 734.30013712281 -33.233688837231 11
+ -109.03329551531 609.96616944861 -43.995511530682 11
+ -297.59593617845 1317.2127350779 43.16794566293 11
+ -395.92628162112 1253.6586968279 -15.703984493996 11
+ -64.776150185884 93.160888145244 -76.971703985724 11
+ -11.764985705836 155.43643846248 -99.09469168573 11
+ 174.3911412518 1113.56182751 10.859461346917 11
+ 173.35935483009 1218.2235296772 10.048399117056 11
+ 75.588382718042 277.08366866643 -69.765146108675 11
+ -217.63416281933 1273.1555760995 39.556438842476 11
+ 124.86527035176 201.56371553707 -30.667415194173 11
+ 12.24447588345 1140.9799101308 -99.020945056435 11
+ 120.35414919124 509.57005486517 -34.504939489206 11
+ -465.50594522415 577.52074120516 -51.075798510848 11
+ 53.91077209708 786.24662226099 -83.459939214777 11
+ 477.71017500724 337.68661191211 -47.66447865145 11
+ 254.6660160515 1088.3941432336 50.377280850383 11
+ -174.37535993631 1330.61449116 10.847086888783 11
+ 263.05958471568 1249.0081302782 50.405903222674 11
+ 70.645670324681 1383.481987147 -73.144736113871 11
+ 210.51529933826 1321.6352678877 35.742021559126 11
+ 161.52828490451 280.1683192443 0.49021768306379 11
+ -285.25995117824 1215.5749361982 46.961076822033 11
+ 481.75404321036 1053.8061658422 -44.138694652998 11
+ -483.48014433658 1272.990678459 -41.892753047336 11
+ 463.80295384905 969.43352043038 -51.083373414481 11
+ -40.56067725033 1227.3039037439 -90.214029912829 11
+ -222.05974780785 79.167127963071 41.691148458665 11
+ -157.96093117533 1267.1172131832 -2.4692613979466 11
+ -472.41375918675 1401.1060457221 -50.060354988374 11
+ -461.74014417468 467.79875141136 -50.993809324787 11
+ 478.67706648534 1137.1382667593 -46.992760158858 11
+ 92.379638978753 1447.8639186796 -57.367616999693 11
+ -13.339961849886 1335.5101175143 -98.842112129115 11
+ 427.14951840648 342.05102184803 -37.252212469172 11
+ 362.62170348002 708.69051737711 7.9121672363243 11
+ -460.91960579512 307.97116427716 -50.930931321154 11
+ -316.51451479951 340.79659287002 35.218511132902 11
+ 295.37185319485 524.07281971907 43.939482738019 11
+ 469.51766880878 1233.3030355863 -50.708121130288 11
+ -140.59017469205 1151.1921016968 -17.193688172418 11
+ -480.87134797353 655.20501751247 -45.087261818097 11
+ 477.28723000053 1410.2134969609 -47.930982714784 11
+ 487.07930725831 887.22815383318 -34.738209005138 11
+ 485.22768890676 260.05400045885 -38.932117037524 11
+ 433.74700000309 1338.5921868296 -41.214509919899 11
+ 440.24706880994 739.4364546536 -44.706756394177 11
+ 480.63927920294 563.79173863854 -45.31754403563 11
+ -482.50874691209 425.93418151293 -43.226471711588 11
+ -472.98108473004 1015.7128033459 -49.887175642466 11
+ -399.60261320391 543.39188928194 -18.353764549053 11
+ -464.06184107243 1251.701601259 -51.087217828098 11
+ 475.38226756727 477.92332393455 -48.951502230175 11
+ -487.19173012822 836.5449300547 -34.439885505848 11
+ -439.66496307747 857.36513630247 -44.414519043483 11
+ 439.76155970774 1070.3595275345 -44.463323103559 11
+ -453.64828377688 371.1582674714 -49.808067872581 11
+ -392.23557903461 290.86257996925 -13.038237883057 11
+ -458.02408161775 1189.7582430329 -50.598613151576 11
+ 478.64499736176 87.173344117713 -47.016518003017 11
+ -483.73456503241 929.92831188915 -41.510037421737 11
+ -480.30520932533 750.06980839712 -45.636113048791 11
+ 449.99071508236 852.51420468998 -48.791796300696 11
+ 456.15191612805 258.64519978743 -50.301243171354 11
+ 484.18577150827 177.79392997653 -40.793502539514 11
+ 417.55118822314 1177.4325371887 -30.97550664823 11
+ -436.04182264041 652.76141598374 -42.501360028894 11
+ 442.15482877215 1270.5563575711 -45.631828459136 11
+ -484.06826221682 225.89330723077 -40.984943014623 11
+ 484.28532358328 668.4308393518 -40.628560396126 11
+ -414.73352363375 1415.9553568621 -29.05113665771 11
+ -481.54297059487 1318.0573012627 -44.376508041812 11
+ 468.74894939394 402.80025802255 -50.821508522922 11
+ -446.24186047954 1331.1052351316 -47.423278047196 11
+ -487.06503930379 1097.2188519237 -34.775676363792 11
+ -422.94283201772 973.07779474436 -34.562629930155 11
+ -372.52586681014 102.80556488818 1.063729841025 11
+ 383.29311554248 810.96802565904 -6.5914711790423 11
+ 432.39570272501 620.55381221144 -40.432729216034 11
+ 154.41721093564 573.46809238912 -5.4365683800604 11
+ -343.13550126179 1061.0377292092 20.54998669241 11
+ 112.82258706563 1233.4562786351 -40.846254426353 11
+ 365.95996639924 1269.4205335147 5.6296838759071 11
+ 352.3566136618 376.06826161625 14.730878293716 11
+ -376.30977848722 424.217867603 -1.6066502201143 11
+ 392.41181747604 998.61219504694 -13.165570200064 11
+ -326.27923379605 55.523106978739 30.254678542706 11
+ 318.51263042873 781.34187454994 34.246502618765 11
+ -363.34350096324 1154.0331761463 7.4210977663806 11
+ -362.54693037665 188.64816381019 7.9629587997713 11
+ 386.82301953169 916.38442534423 -9.1310258312517 11
+ -392.02660349934 1348.889509557 -12.887254213511 11
+ 381.33719201028 524.71811031351 -5.1891938678163 11
+ -307.64420653543 525.10258115316 39.240336904541 11
+ -343.5205611163 846.28665298224 20.31354088965 11
+ -330.99931903314 957.81662946231 27.6726382674 11
+ 347.4702557452 151.13770506691 17.854307307358 11
+ 345.10507914121 459.50975467949 19.334300186977 11
+ -328.815722319 1414.6313507616 28.881139792988 11
+ 326.45962010185 1418.089359143 30.158093936703 11
+ 333.11071397002 67.346852281374 26.481879446845 11
+ -387.76802489025 913.1734699119 -9.8123809742012 11
+ 368.49108549348 1355.7377760119 3.8807879599646 11
+ -318.81666547397 746.81079787354 34.096567007307 11
+ 500 270.28236611415 153.159385701 15
+ 500 180.78042327992 163.13492063487 15
+ 500 474.0019313797 150.42708279681 15
+ 500 587.03658565476 150.07092191938 15
+ 500 861.17651593493 139.14052856793 15
+ 500 704.15340852392 128.8010616776 15
+ 500 966.64271288781 101.07558134961 15
+ 500 1196.3349605626 135.10819539539 15
+ 500 1289.1241361944 147.3661194078 15
+ 500 93.922632544823 116.95902170382 15
+ 500 112.0634920632 231.48809523803 15
+ 500 1405.8358587109 150.94261130962 15
+ 500 1257.7893518504 70.833333333329 15
+ 500 1346.8046320694 70.881381628344 15
+ 500 1348.1056615728 228.17961562068 15
+ 500 214.61451247103 74.090136054399 15
+ 500 1092.7578190047 113.11074906549 15
+ 500 333.88521021504 226.50269449172 15
+ 500 330.7349887067 75.688041084058 15
+ 500 545.36320299409 75.152291624885 15
+ 500 545.4507091471 225.17492088621 15
+ 500 1026.2799448658 214.73146091449 15
+ 500 1167.4819899339 63.8702444256 15
+ 500 1141.5957528697 214.00305211933 15
+ 500 435.06841370713 75.416132853242 15
+ 500 435.59345062519 225.55190842119 15
+ 500 233.87676366774 228.79133597881 15
+ 500 1428.7362381578 63.584179785852 15
+ 500 1243.6739745335 220.76896300681 15
+ 500 48.480658136141 54.239755425904 15
+ 500 379.92772679132 151.124207558 15
+ 500 780.05807480932 155.52056483706 15
+ 500 930.67390922397 213.63904920337 15
+ 500 1430.7883040566 235.82444538601 15
+ 500 820.14032102512 216.95573511599 15
+ 500 1042.1817712935 55.117048242365 15
+ 500 684.93831956774 222.07498222571 15
+ 500 661.24467275424 69.677281796905 15
+ 500 769.52920211466 80.85789309753 15
+ 500 859.46968618645 64.214800603014 15
+ -0.81462932724889 0 97.636268535275 18
+ -139.85718816121 0 158.61010619842 18
+ 138.14646657356 0 157.45607707312 18
+ -367.44288752686 0 155.2345449976 18
+ 367.44288752644 0 155.23454499772 18
+ -231.12102700525 0 208.49061874194 18
+ 230.87663820627 0 208.32575743857 18
+ -0.16292586612424 -0 -13.288205311999 18
+ 110.3710335661 0 68.968201390013 18
+ -110.71184787811 0 69.085959464396 18
+ 44.101039491352 0 205.54835382314 18
+ -56.987561922027 0 208.39901318911 18
+ 209.79152991163 0 107.11232733922 18
+ -210.06485428202 0 107.28335692276 18
+ -408.88213332683 0 85.722930270628 18
+ 408.88213332647 0 85.722930270944 18
+ 292.29208962293 0 131.70029191028 18
+ -292.33611285296 0 131.72885405967 18
+ 420.88385594015 0 220.8838559401 18
+ -420.88385594029 0 220.88385594027 18
+ -436.42338438925 0 22.995307196009 18
+ 436.4233843894 0 22.995307196167 18
+ -148.39400707645 0 236.90586730686 18
+ 142.62482885424 0 234.26603766697 18
+ -335.29731388756 0 219.38964562325 18
+ 335.24924521597 0 219.35740838111 18
+ -77.09280682215 0 133.4328368468 18
+ 69.963291817927 0 131.6829686574 18
+ -439.4417753588 0 152.3682662417 18
+ 439.44177535861 0 152.36826624166 18
+ 341.8840469659 0 77.512213083231 18
+ -341.88404696694 0 77.512213081832 18
+ -67.088900315855 0 6.2458496393847 18
+ 67.088900315276 0 6.2458496384531 18
+ Edges
+ 108
+ 2 19 1
+ 19 20 1
+ 20 21 1
+ 21 22 1
+ 22 23 1
+ 23 24 1
+ 24 25 1
+ 25 26 1
+ 26 27 1
+ 27 28 1
+ 28 29 1
+ 29 30 1
+ 30 3 1
+ 8 31 2
+ 31 32 2
+ 32 2 2
+ 3 33 3
+ 33 34 3
+ 34 9 3
+ 10 35 4
+ 35 36 4
+ 36 11 4
+ 8 37 5
+ 37 38 5
+ 38 39 5
+ 39 40 5
+ 40 41 5
+ 41 42 5
+ 42 43 5
+ 43 44 5
+ 44 45 5
+ 45 46 5
+ 46 47 5
+ 47 48 5
+ 48 49 5
+ 49 50 5
+ 50 10 5
+ 2 51 6
+ 51 52 6
+ 52 53 6
+ 53 54 6
+ 54 55 6
+ 55 56 6
+ 56 57 6
+ 57 58 6
+ 58 59 6
+ 59 60 6
+ 60 61 6
+ 61 62 6
+ 62 63 6
+ 63 64 6
+ 64 11 6
+ 11 65 8
+ 65 66 8
+ 66 67 8
+ 67 68 8
+ 68 69 8
+ 69 70 8
+ 70 71 8
+ 71 72 8
+ 72 73 8
+ 73 74 8
+ 74 75 8
+ 75 76 8
+ 76 17 8
+ 3 77 10
+ 77 78 10
+ 78 79 10
+ 79 80 10
+ 80 81 10
+ 81 82 10
+ 82 83 10
+ 83 84 10
+ 84 85 10
+ 85 86 10
+ 86 87 10
+ 87 88 10
+ 88 89 10
+ 89 90 10
+ 90 17 10
+ 17 91 12
+ 91 92 12
+ 92 18 12
+ 9 93 14
+ 93 94 14
+ 94 95 14
+ 95 96 14
+ 96 97 14
+ 97 98 14
+ 98 99 14
+ 99 100 14
+ 100 101 14
+ 101 102 14
+ 102 103 14
+ 103 104 14
+ 104 105 14
+ 105 106 14
+ 106 18 14
+ 8 107 16
+ 107 108 16
+ 108 109 16
+ 109 110 16
+ 110 111 16
+ 111 112 16
+ 112 113 16
+ 113 114 16
+ 114 115 16
+ 115 9 16
+ Triangles
+ 801
+ 125 32 2 7
+ 51 125 2 7
+ 31 32 124 7
+ 125 124 32 7
+ 52 125 51 7
+ 116 124 125 7
+ 64 126 63 7
+ 127 128 122 7
+ 40 141 41 7
+ 117 134 141 7
+ 134 41 141 7
+ 142 54 55 7
+ 135 117 142 7
+ 55 135 142 7
+ 46 136 47 7
+ 123 136 120 7
+ 137 60 61 7
+ 137 123 120 7
+ 127 122 126 7
+ 135 55 56 7
+ 56 130 135 7
+ 41 134 42 7
+ 131 42 134 7
+ 49 127 50 7
+ 49 128 127 7
+ 129 39 38 7
+ 133 39 129 7
+ 47 138 48 7
+ 139 61 62 7
+ 42 140 43 7
+ 42 131 140 7
+ 48 128 49 7
+ 48 138 128 7
+ 122 128 121 7
+ 138 121 128 7
+ 139 62 63 7
+ 139 122 121 7
+ 133 40 39 7
+ 141 40 133 7
+ 54 132 53 7
+ 54 142 132 7
+ 119 140 131 7
+ 122 63 126 7
+ 122 139 63 7
+ 143 36 35 7
+ 143 127 126 7
+ 36 144 11 7
+ 64 144 126 7
+ 144 64 11 7
+ 121 145 139 7
+ 138 145 121 7
+ 138 123 145 7
+ 143 144 36 7
+ 143 126 144 7
+ 117 141 133 7
+ 138 47 136 7
+ 123 138 136 7
+ 137 61 139 7
+ 137 145 123 7
+ 145 137 139 7
+ 116 146 124 7
+ 37 146 38 7
+ 147 134 117 7
+ 135 147 117 7
+ 149 35 10 7
+ 50 149 10 7
+ 31 150 8 7
+ 150 37 8 7
+ 150 31 124 7
+ 148 140 119 7
+ 150 146 37 7
+ 124 146 150 7
+ 146 129 38 7
+ 116 129 146 7
+ 149 50 127 7
+ 143 149 127 7
+ 149 143 35 7
+ 132 133 129 7
+ 117 133 132 7
+ 132 142 117 7
+ 130 119 147 7
+ 119 131 147 7
+ 130 147 135 7
+ 147 131 134 7
+ 152 132 129 7
+ 116 152 129 7
+ 46 45 151 7
+ 151 120 136 7
+ 120 151 118 7
+ 136 46 151 7
+ 60 137 120 7
+ 153 118 151 7
+ 153 45 44 7
+ 151 45 153 7
+ 43 153 44 7
+ 148 153 140 7
+ 153 148 118 7
+ 43 140 153 7
+ 52 152 125 7
+ 53 152 52 7
+ 152 116 125 7
+ 53 132 152 7
+ 59 120 118 7
+ 120 59 60 7
+ 118 58 59 7
+ 119 154 148 7
+ 154 119 130 7
+ 154 56 57 7
+ 130 56 154 7
+ 155 58 118 7
+ 155 148 154 7
+ 148 155 118 7
+ 155 57 58 7
+ 154 57 155 7
+ 161 195 191 11
+ 69 174 70 11
+ 194 191 195 11
+ 193 68 67 11
+ 195 161 186 11
+ 69 189 174 11
+ 201 179 168 11
+ 168 202 201 11
+ 202 180 201 11
+ 156 205 183 11
+ 160 206 199 11
+ 180 206 201 11
+ 206 180 199 11
+ 212 177 178 11
+ 188 213 159 11
+ 169 214 213 11
+ 214 159 213 11
+ 217 171 181 11
+ 188 218 211 11
+ 220 174 189 11
+ 222 159 214 11
+ 228 179 201 11
+ 179 228 197 11
+ 169 238 214 11
+ 240 170 211 11
+ 156 242 205 11
+ 243 186 161 11
+ 187 243 161 11
+ 244 25 26 11
+ 187 244 26 11
+ 181 248 217 11
+ 248 181 191 11
+ 211 246 188 11
+ 228 206 160 11
+ 201 206 228 11
+ 230 244 187 11
+ 238 205 242 11
+ 233 215 173 11
+ 246 213 188 11
+ 240 218 172 11
+ 211 218 240 11
+ 222 214 238 11
+ 69 68 189 11
+ 68 193 189 11
+ 160 199 182 11
+ 71 70 203 11
+ 70 174 203 11
+ 26 243 187 11
+ 26 27 243 11
+ 159 239 188 11
+ 172 218 239 11
+ 218 188 239 11
+ 237 228 160 11
+ 237 197 228 11
+ 164 198 234 11
+ 198 170 234 11
+ 170 240 234 11
+ 202 158 180 11
+ 168 216 202 11
+ 194 248 191 11
+ 215 163 208 11
+ 211 200 246 11
+ 242 156 223 11
+ 223 207 250 11
+ 250 231 177 11
+ 207 231 250 11
+ 224 168 179 11
+ 253 216 176 11
+ 249 253 176 11
+ 254 177 212 11
+ 239 254 212 11
+ 257 178 219 11
+ 171 258 181 11
+ 249 259 204 11
+ 225 260 172 11
+ 260 240 172 11
+ 234 240 260 11
+ 245 208 247 11
+ 225 245 247 11
+ 73 184 74 11
+ 262 216 168 11
+ 216 262 219 11
+ 178 257 212 11
+ 164 234 247 11
+ 234 260 247 11
+ 260 225 247 11
+ 202 253 158 11
+ 253 202 216 11
+ 159 222 254 11
+ 159 254 239 11
+ 250 177 254 11
+ 254 222 250 11
+ 249 176 259 11
+ 221 179 197 11
+ 224 179 221 11
+ 219 262 252 11
+ 209 183 205 11
+ 222 238 242 11
+ 250 222 242 11
+ 223 250 242 11
+ 231 178 177 11
+ 178 231 176 11
+ 259 176 231 11
+ 25 244 229 11
+ 24 25 229 11
+ 230 229 244 11
+ 176 265 178 11
+ 219 265 216 11
+ 265 219 178 11
+ 265 176 216 11
+ 237 268 197 11
+ 221 269 230 11
+ 269 229 230 11
+ 269 221 197 11
+ 270 200 211 11
+ 170 270 211 11
+ 272 224 221 11
+ 161 274 187 11
+ 274 230 187 11
+ 190 275 200 11
+ 233 276 171 11
+ 276 258 171 11
+ 210 258 276 11
+ 268 269 197 11
+ 268 229 269 11
+ 225 172 264 11
+ 268 23 24 11
+ 23 268 237 11
+ 229 268 24 11
+ 252 276 255 11
+ 276 252 210 11
+ 236 73 72 11
+ 262 168 224 11
+ 224 210 262 11
+ 262 210 252 11
+ 259 231 207 11
+ 224 258 210 11
+ 224 272 258 11
+ 245 264 173 11
+ 255 173 264 11
+ 264 245 225 11
+ 271 270 175 11
+ 271 200 270 11
+ 266 273 193 11
+ 278 264 172 11
+ 239 278 172 11
+ 280 175 270 11
+ 170 280 270 11
+ 175 282 271 11
+ 284 185 271 11
+ 185 284 236 11
+ 285 181 258 11
+ 286 183 209 11
+ 273 286 209 11
+ 193 281 189 11
+ 281 193 273 11
+ 220 189 281 11
+ 157 282 175 11
+ 219 252 257 11
+ 255 257 252 11
+ 257 255 264 11
+ 278 239 212 11
+ 290 226 169 11
+ 22 291 21 11
+ 291 182 21 11
+ 226 292 209 11
+ 273 292 281 11
+ 292 273 209 11
+ 220 292 226 11
+ 220 281 292 11
+ 291 160 182 11
+ 160 291 237 11
+ 283 190 185 11
+ 267 286 266 11
+ 286 273 266 11
+ 283 185 236 11
+ 71 203 283 11
+ 196 284 282 11
+ 282 284 271 11
+ 285 161 191 11
+ 285 274 161 11
+ 181 285 191 11
+ 72 296 236 11
+ 283 296 71 11
+ 296 283 236 11
+ 296 72 71 11
+ 283 297 190 11
+ 299 208 163 11
+ 301 180 158 11
+ 209 304 226 11
+ 304 209 205 11
+ 304 169 226 11
+ 79 80 279 11
+ 180 301 199 11
+ 237 22 23 11
+ 22 237 291 11
+ 275 213 246 11
+ 275 246 200 11
+ 169 213 275 11
+ 275 290 169 11
+ 230 272 221 11
+ 230 274 272 11
+ 285 272 274 11
+ 272 285 258 11
+ 304 238 169 11
+ 205 238 304 11
+ 309 261 306 11
+ 294 314 277 11
+ 63 62 288 11
+ 87 295 287 11
+ 84 307 251 11
+ 263 316 311 11
+ 82 311 81 11
+ 192 316 263 11
+ 305 56 277 11
+ 57 56 305 11
+ 295 88 303 11
+ 295 87 88 11
+ 80 81 316 11
+ 311 316 81 11
+ 174 297 203 11
+ 220 297 174 11
+ 297 283 203 11
+ 300 241 53 11
+ 53 241 54 11
+ 308 79 279 11
+ 78 79 308 11
+ 163 215 302 11
+ 302 215 233 11
+ 85 307 84 11
+ 293 11 64 11
+ 293 65 11 11
+ 312 55 54 11
+ 287 319 289 11
+ 325 317 58 11
+ 289 326 307 11
+ 298 327 279 11
+ 327 308 279 11
+ 331 303 261 11
+ 309 331 261 11
+ 336 279 80 11
+ 316 336 80 11
+ 57 325 58 11
+ 57 305 325 11
+ 337 335 315 11
+ 336 298 279 11
+ 336 192 298 11
+ 316 192 336 11
+ 84 251 83 11
+ 317 325 318 11
+ 59 58 317 11
+ 317 324 59 11
+ 328 77 78 11
+ 308 328 78 11
+ 330 277 314 11
+ 53 332 300 11
+ 332 53 52 11
+ 320 241 300 11
+ 300 321 320 11
+ 55 294 277 11
+ 56 55 277 11
+ 312 294 55 11
+ 331 329 303 11
+ 335 64 63 11
+ 288 335 63 11
+ 335 293 64 11
+ 335 288 315 11
+ 289 86 287 11
+ 287 86 87 11
+ 86 289 307 11
+ 307 85 86 11
+ 62 315 288 11
+ 322 315 62 11
+ 232 329 157 11
+ 329 295 303 11
+ 232 319 329 11
+ 330 305 277 11
+ 330 325 305 11
+ 306 261 90 11
+ 261 89 90 11
+ 321 199 301 11
+ 312 54 241 11
+ 241 320 312 11
+ 3 323 30 11
+ 323 3 77 11
+ 323 77 328 11
+ 328 308 327 11
+ 61 338 62 11
+ 338 322 62 11
+ 324 313 60 11
+ 324 60 59 11
+ 220 226 290 11
+ 275 190 290 11
+ 297 290 190 11
+ 220 290 297 11
+ 312 320 294 11
+ 293 335 337 11
+ 333 83 251 11
+ 311 82 333 11
+ 83 333 82 11
+ 51 165 162 11
+ 51 332 52 11
+ 162 332 51 11
+ 306 17 76 11
+ 90 17 306 11
+ 89 303 88 11
+ 261 303 89 11
+ 198 280 170 11
+ 198 232 280 11
+ 186 27 28 11
+ 186 243 27 11
+ 257 278 212 11
+ 264 278 257 11
+ 65 334 66 11
+ 65 293 334 11
+ 326 251 307 11
+ 310 251 326 11
+ 217 233 171 11
+ 302 233 217 11
+ 338 227 322 11
+ 300 162 321 11
+ 300 332 162 11
+ 165 19 20 11
+ 280 157 175 11
+ 232 157 280 11
+ 310 333 251 11
+ 342 263 311 11
+ 333 342 311 11
+ 343 233 173 11
+ 343 255 276 11
+ 255 343 173 11
+ 233 343 276 11
+ 344 156 183 11
+ 190 345 185 11
+ 271 345 200 11
+ 345 271 185 11
+ 345 190 200 11
+ 346 331 309 11
+ 347 248 194 11
+ 298 347 194 11
+ 301 348 321 11
+ 348 320 321 11
+ 192 347 298 11
+ 20 340 165 11
+ 163 342 299 11
+ 248 347 217 11
+ 310 341 299 11
+ 341 310 326 11
+ 158 348 301 11
+ 348 294 320 11
+ 294 348 314 11
+ 287 295 319 11
+ 295 329 319 11
+ 313 339 227 11
+ 344 227 339 11
+ 340 162 165 11
+ 198 349 232 11
+ 349 319 232 11
+ 21 350 20 11
+ 340 350 182 11
+ 350 340 20 11
+ 350 21 182 11
+ 351 247 208 11
+ 351 299 341 11
+ 299 351 208 11
+ 352 267 322 11
+ 227 352 322 11
+ 199 353 182 11
+ 353 340 182 11
+ 354 164 341 11
+ 326 354 341 11
+ 302 356 163 11
+ 357 158 253 11
+ 249 357 253 11
+ 352 344 183 11
+ 227 344 352 11
+ 356 342 163 11
+ 263 342 356 11
+ 356 192 263 11
+ 349 289 319 11
+ 354 198 164 11
+ 349 198 354 11
+ 326 289 354 11
+ 349 354 289 11
+ 306 167 309 11
+ 194 327 298 11
+ 327 194 235 11
+ 328 327 235 11
+ 324 339 313 11
+ 324 317 318 11
+ 338 313 227 11
+ 313 338 60 11
+ 338 61 60 11
+ 346 282 157 11
+ 346 196 282 11
+ 329 346 157 11
+ 346 329 331 11
+ 314 204 330 11
+ 204 357 249 11
+ 158 357 348 11
+ 357 314 348 11
+ 204 314 357 11
+ 162 353 321 11
+ 353 162 340 11
+ 353 199 321 11
+ 359 156 344 11
+ 339 359 344 11
+ 195 360 194 11
+ 360 235 194 11
+ 192 361 347 11
+ 361 217 347 11
+ 361 192 356 11
+ 361 302 217 11
+ 356 302 361 11
+ 186 360 195 11
+ 235 360 166 11
+ 166 323 235 11
+ 323 328 235 11
+ 223 358 207 11
+ 359 223 156 11
+ 358 223 359 11
+ 183 286 352 11
+ 286 267 352 11
+ 355 337 267 11
+ 266 355 267 11
+ 193 362 266 11
+ 362 355 266 11
+ 29 30 166 11
+ 30 323 166 11
+ 67 362 193 11
+ 362 67 66 11
+ 334 355 362 11
+ 334 362 66 11
+ 76 167 306 11
+ 167 76 75 11
+ 184 236 284 11
+ 236 184 73 11
+ 284 196 184 11
+ 363 184 196 11
+ 364 166 360 11
+ 186 364 360 11
+ 166 364 29 11
+ 359 365 358 11
+ 365 359 339 11
+ 366 346 309 11
+ 346 366 196 11
+ 167 366 309 11
+ 363 366 167 11
+ 363 196 366 11
+ 364 28 29 11
+ 186 28 364 11
+ 74 363 75 11
+ 363 74 184 11
+ 363 167 75 11
+ 330 204 256 11
+ 325 330 256 11
+ 358 318 256 11
+ 318 325 256 11
+ 318 339 324 11
+ 318 365 339 11
+ 365 318 358 11
+ 367 256 204 11
+ 259 367 204 11
+ 207 367 259 11
+ 367 207 358 11
+ 256 367 358 11
+ 165 2 19 11
+ 51 2 165 11
+ 215 245 173 11
+ 215 208 245 11
+ 267 315 322 11
+ 267 337 315 11
+ 351 164 247 11
+ 341 164 351 11
+ 342 310 299 11
+ 333 310 342 11
+ 337 334 293 11
+ 355 334 337 11
+ 34 377 33 15
+ 378 34 9 15
+ 93 378 9 15
+ 378 377 34 15
+ 94 378 93 15
+ 369 377 378 15
+ 88 380 89 15
+ 376 380 375 15
+ 381 90 89 15
+ 88 390 380 15
+ 390 375 380 15
+ 94 394 378 15
+ 394 369 378 15
+ 395 90 381 15
+ 380 381 89 15
+ 380 376 381 15
+ 379 381 376 15
+ 393 96 97 15
+ 388 370 393 15
+ 97 388 393 15
+ 80 392 81 15
+ 370 387 392 15
+ 387 81 392 15
+ 90 395 17 15
+ 395 91 17 15
+ 389 102 103 15
+ 388 97 98 15
+ 388 371 370 15
+ 81 387 82 15
+ 371 387 370 15
+ 95 394 94 15
+ 95 385 394 15
+ 369 394 368 15
+ 385 368 394 15
+ 383 79 78 15
+ 386 79 383 15
+ 383 369 368 15
+ 368 386 383 15
+ 391 103 104 15
+ 87 390 88 15
+ 87 384 390 15
+ 379 376 382 15
+ 77 383 78 15
+ 383 377 369 15
+ 377 383 77 15
+ 386 80 79 15
+ 392 80 386 15
+ 96 385 95 15
+ 96 393 385 15
+ 391 396 375 15
+ 396 391 104 15
+ 33 397 3 15
+ 77 397 377 15
+ 397 77 3 15
+ 397 33 377 15
+ 105 396 104 15
+ 105 382 396 15
+ 396 376 375 15
+ 382 376 396 15
+ 379 92 91 15
+ 91 395 379 15
+ 379 395 381 15
+ 370 398 393 15
+ 398 370 392 15
+ 398 386 368 15
+ 392 386 398 15
+ 385 398 368 15
+ 385 393 398 15
+ 103 391 389 15
+ 382 105 106 15
+ 92 401 18 15
+ 401 106 18 15
+ 101 102 400 15
+ 374 400 389 15
+ 400 374 372 15
+ 102 389 400 15
+ 106 401 382 15
+ 401 379 382 15
+ 379 401 92 15
+ 389 384 374 15
+ 391 375 384 15
+ 375 390 384 15
+ 391 384 389 15
+ 372 402 400 15
+ 403 86 374 15
+ 403 384 87 15
+ 384 403 374 15
+ 86 403 87 15
+ 101 402 100 15
+ 101 400 402 15
+ 399 402 372 15
+ 85 374 86 15
+ 82 405 83 15
+ 404 98 99 15
+ 99 100 404 15
+ 399 404 402 15
+ 404 399 373 15
+ 100 402 404 15
+ 405 82 387 15
+ 371 405 387 15
+ 373 405 371 15
+ 98 404 388 15
+ 404 371 388 15
+ 404 373 371 15
+ 83 406 84 15
+ 406 399 372 15
+ 406 373 399 15
+ 406 83 405 15
+ 405 373 406 15
+ 85 407 374 15
+ 372 407 406 15
+ 407 372 374 15
+ 84 407 85 15
+ 84 406 407 15
+ 22 421 417 18
+ 27 416 420 18
+ 409 417 421 18
+ 410 420 416 18
+ 408 441 415 18
+ 408 415 440 18
+ 408 440 417 18
+ 408 416 441 18
+ 108 109 413 18
+ 113 114 414 18
+ 24 415 25 18
+ 408 419 418 18
+ 409 413 430 18
+ 410 431 414 18
+ 409 421 413 18
+ 410 414 420 18
+ 109 430 413 18
+ 113 414 431 18
+ 26 416 27 18
+ 22 417 23 18
+ 2 32 428 18
+ 3 429 33 18
+ 111 112 418 18
+ 108 413 432 18
+ 114 433 414 18
+ 112 431 418 18
+ 408 434 419 18
+ 111 418 419 18
+ 410 418 431 18
+ 25 415 441 18
+ 24 440 415 18
+ 110 111 419 18
+ 107 432 427 18
+ 115 426 433 18
+ 9 34 426 18
+ 9 426 115 18
+ 8 427 31 18
+ 8 107 427 18
+ 408 417 434 18
+ 408 435 416 18
+ 107 108 432 18
+ 114 115 433 18
+ 27 420 28 18
+ 21 421 22 18
+ 29 429 30 18
+ 19 428 20 18
+ 409 430 419 18
+ 25 441 26 18
+ 23 440 24 18
+ 26 441 416 18
+ 23 417 440 18
+ 32 422 428 18
+ 33 429 423 18
+ 110 419 430 18
+ 410 435 418 18
+ 411 432 425 18
+ 412 424 433 18
+ 413 425 432 18
+ 414 433 424 18
+ 408 418 435 18
+ 410 416 435 18
+ 409 434 417 18
+ 411 427 432 18
+ 412 433 426 18
+ 409 419 434 18
+ 2 428 19 18
+ 3 30 429 18
+ 28 420 424 18
+ 21 425 421 18
+ 109 110 430 18
+ 112 113 431 18
+ 411 439 422 18
+ 412 423 438 18
+ 413 421 425 18
+ 414 424 420 18
+ 20 428 422 18
+ 29 423 429 18
+ 28 438 29 18
+ 20 439 21 18
+ 33 437 34 18
+ 31 436 32 18
+ 411 422 436 18
+ 412 437 423 18
+ 20 422 439 18
+ 29 438 423 18
+ 411 425 439 18
+ 412 438 424 18
+ 32 436 422 18
+ 33 423 437 18
+ 411 436 427 18
+ 412 426 437 18
+ 28 424 438 18
+ 21 439 425 18
+ 31 427 436 18
+ 34 437 426 18
+ End
=== added file 'examples/conveyor/conveyor.py'
--- examples/conveyor/conveyor.py 1970-01-01 00:00:00 +0000
+++ examples/conveyor/conveyor.py 2014-05-15 14:47:33 +0000
@@ -0,0 +1,55 @@
+#!/usr/bin/python
+# -*- coding: utf-8 -*-
+# This example shows, how one can simulate the conveyor of
+# complex form, using mask-parameter in NewtonIntegrator.
+# The elements of conveyor are getting the velocity, but
+# are blocked from motion.
+# Conveyor element have a groupMask=5 which is after bitwise AND
+# operator with mask=2 in NewtonIntegrator gives 0 and prevents motion.
+#
+# So the interacting particles are getting motion from interaction
+# with conveyor
+
+## PhysicalParameters
+Density=1000
+frictionAngle=0.4
+tc = 0.001
+en = 0.3
+es = 0.3
+
+
+## Import wall's geometry
+mat=O.materials.append(ViscElMat(density=Density,frictionAngle=frictionAngle,tc=tc,en=en,et=es))
+
+sp=pack.SpherePack()
+sp.makeCloud((-0.3,0.05,0.05),(0.3,0.7,0.5),rMean=0.03, rRelFuzz=0.001)
+particles=O.bodies.append([sphere(c,r,mask=3) for c,r in sp])
+
+from yade import ymport
+fctIds= O.bodies.append(ymport.gmsh('conveyor.mesh',scale=0.001,color=(1,0,0)))
+voxIds= O.bodies.append(utils.geom.facetBunker(center=[0,1.5,-0.7],dBunker=1.1, dOutput=0.2,hBunker=0.2,hOutput=0.2,hPipe=0.1, mask=5))
+
+for i in fctIds:
+ O.bodies[i].state.vel=Vector3(0,0.2,0) # Set conveyor velocity
+
+## Timestep
+O.dt=.2*tc
+
+## Engines
+O.engines=[
+ ForceResetter(),
+ InsertionSortCollider([Bo1_Sphere_Aabb(),Bo1_Facet_Aabb()]),
+ InteractionLoop(
+ [Ig2_Sphere_Sphere_ScGeom(), Ig2_Facet_Sphere_ScGeom()],
+ [Ip2_ViscElMat_ViscElMat_ViscElPhys()],
+ [Law2_ScGeom_ViscElPhys_Basic()],
+ ),
+ NewtonIntegrator(damping=0,gravity=[0,0,-9.81], mask=2),
+ DomainLimiter(lo=(-0.6,0.0,-1.0),hi=(0.6,2.0,1.0),iterPeriod=200),
+]
+
+from yade import qt
+qt.View()
+#O.saveTmp()
+#O.run()
+
=== modified file 'examples/packs/packs.py'
--- examples/packs/packs.py 2014-01-06 13:59:54 +0000
+++ examples/packs/packs.py 2014-05-15 14:47:34 +0000
@@ -43,7 +43,7 @@
pack.regularHexa (pack.inCylinder((+1,1,-2.5),(0,3,-5),1),radius=rad,gap=gap,color=(0,1,1),**kw), # right leg
pack.regularHexa (pack.inHyperboloid((+2,0,1),(+6,0,0),1,.5),radius=rad,gap=gap,color=(0,0,1),**kw), # right hand
pack.regularOrtho(pack.inCylinder((-2,0,2),(-5,0,4),1),radius=rad,gap=gap,color=(0,0,1),**kw) # left hand
- ]: O.bodies.appendClumped(part,integrateInertia=False)
+ ]: O.bodies.appendClumped(part)
# Example of geom.facetBox usage
=== removed directory 'extra'
=== removed directory 'extra/floating_point_utilities_v3'
=== removed file 'extra/floating_point_utilities_v3/README'
--- extra/floating_point_utilities_v3/README 2010-04-19 10:18:42 +0000
+++ extra/floating_point_utilities_v3/README 1970-01-01 00:00:00 +0000
@@ -1,7 +0,0 @@
-Graceful handling of nan and inf in iostream
-
-Proposed for boost::math
-
-Downloaded from: http://www.boostpro.com/vault/index.php?action=downloadfile&filename=floating_point_utilities_v3.zip&directory=Math%20-%20Numerics&
-
-stripped of documentation
=== removed directory 'extra/floating_point_utilities_v3/boost'
=== removed directory 'extra/floating_point_utilities_v3/boost/math'
=== removed directory 'extra/floating_point_utilities_v3/boost/math/detail'
=== removed file 'extra/floating_point_utilities_v3/boost/math/detail/fp_traits.hpp'
--- extra/floating_point_utilities_v3/boost/math/detail/fp_traits.hpp 2010-04-19 10:18:42 +0000
+++ extra/floating_point_utilities_v3/boost/math/detail/fp_traits.hpp 1970-01-01 00:00:00 +0000
@@ -1,576 +0,0 @@
-// fp_traits.hpp
-
-#ifndef BOOST_MATH_FP_TRAITS_HPP
-#define BOOST_MATH_FP_TRAITS_HPP
-
-// Copyright (c) 2006 Johan Rade
-
-// Distributed under the Boost Software License, Version 1.0.
-// (See accompanying file LICENSE_1_0.txt
-// or copy at http://www.boost.org/LICENSE_1_0.txt)
-
-#if defined(__vms) && defined(__DECCXX) && !__IEEE_FLOAT
-# error The VAX floating point mode on VMS is not supported.
-#endif
-
-#include <cstring>
-
-#include <boost/assert.hpp>
-#include <boost/cstdint.hpp>
-#include <boost/detail/endian.hpp>
-#include <boost/static_assert.hpp>
-#include <boost/type_traits/is_floating_point.hpp>
-
-//------------------------------------------------------------------------------
-
-namespace boost {
-namespace math {
-namespace detail {
-
-//------------------------------------------------------------------------------
-
-/*
-Most processors support three different floating point precisions:
-single precision (32 bits), double precision (64 bits)
-and extended double precision (>64 bits)
-
-Note that the C++ type long double can be implemented
-both as double precision and extended double precision.
-*/
-
-struct single_precision_tag {};
-struct double_precision_tag {};
-struct extended_double_precision_tag {};
-
-//------------------------------------------------------------------------------
-
-/*
-template<class T, class U> struct fp_traits_impl;
-
- This is traits class that describes the binary structure of floating
- point numbers of C++ type T and precision U
-
-Requirements:
-
- T = float, double or long double
- U = single_precision_tag, double_precision_tag
- or extended_double_precision_tag
-
-Typedef members:
-
- bits -- the target type when copying the leading bytes of a floating
- point number. It is a typedef for uint32_t or uint64_t.
-
- coverage -- tells us whether all bytes are copied or not.
- It is a typedef for all_bits or not_all_bits.
-
-Static data members:
-
- sign, exponent, flag, mantissa -- bit masks that give the meaning of the bits
- in the leading bytes.
-
-Static function members:
-
- init() -- initializes the static data members, if needed.
- (Is a no-op in the specialized versions of the template.)
-
- get_bits(), set_bits() -- provide access to the leading bytes.
-*/
-
-struct all_bits {};
-struct not_all_bits {};
-
-// Generic version -------------------------------------------------------------
-
-// The generic version uses run time initialization to determine the floating
-// point format. It is capable of handling most formats,
-// but not the Motorola 68K extended double precision format.
-
-// Currently the generic version is used only for extended double precision
-// on Itanium. In all other cases there are specializations of the template
-// that use compile time initialization.
-
-template<class T> struct uint32_t_coverage
-{
- typedef not_all_bits type;
-};
-
-template<> struct uint32_t_coverage<single_precision_tag>
-{
- typedef all_bits type;
-};
-
-template<class T, class U> struct fp_traits_impl
-{
- typedef uint32_t bits;
- typedef BOOST_DEDUCED_TYPENAME uint32_t_coverage<U>::type coverage;
-
- BOOST_STATIC_CONSTANT(uint32_t, sign = 0x80000000);
- static uint32_t exponent;
- static uint32_t flag;
- static uint32_t mantissa;
-
- static void init()
- {
- if(is_init_) return;
- do_init_();
- is_init_ = true;
- }
-
- static void get_bits(T x, uint32_t& a)
- {
- memcpy(&a, reinterpret_cast<const unsigned char*>(&x) + offset_, 4);
- }
-
- static void set_bits(T& x, uint32_t a)
- {
- memcpy(reinterpret_cast<unsigned char*>(&x) + offset_, &a, 4);
- }
-
-private:
- static size_t offset_;
- static bool is_init_;
- static void do_init_();
-};
-
-//..............................................................................
-
-template<class T, class U> uint32_t fp_traits_impl<T,U>::exponent;
-template<class T, class U> uint32_t fp_traits_impl<T,U>::flag;
-template<class T, class U> uint32_t fp_traits_impl<T,U>::mantissa;
-template<class T, class U> size_t fp_traits_impl<T,U>::offset_;
-template<class T, class U> bool fp_traits_impl<T,U>::is_init_;
-
-// In a single-threaded program, do_init will be called exactly once.
-// In a multi-threaded program, do_init may be called simultaneously
-// by more then one thread. That should not be a problem.
-
-//..............................................................................
-
-template<class T, class U> void fp_traits_impl<T,U>::do_init_()
-{
- T x = static_cast<T>(3) / static_cast<T>(4);
- // sign bit = 0
- // exponent: first and last bit = 0, all other bits = 1
- // flag bit (if present) = 1
- // mantissa: first bit = 1, all other bits = 0
-
- uint32_t a;
-
- for(size_t k = 0; k <= sizeof(T) - 4; ++k) {
-
- memcpy(&a, reinterpret_cast<unsigned char*>(&x) + k, 4);
-
- switch(a) {
-
- case 0x3f400000: // IEEE single precision format
-
- offset_ = k;
- exponent = 0x7f800000;
- flag = 0x00000000;
- mantissa = 0x007fffff;
- return;
-
- case 0x3fe80000: // IEEE double precision format
- // and PowerPC extended double precision format
- offset_ = k;
- exponent = 0x7ff00000;
- flag = 0x00000000;
- mantissa = 0x000fffff;
- return;
-
- case 0x3ffe0000: // Motorola extended double precision format
-
- // Must not get here. Must be handled by specialization.
- // To get accurate cutoff between normals and subnormals
- // we must use the flag bit that is in the 5th byte.
- // Otherwise this cutoff will be off by a factor 2.
- // If we do get here, then we have failed to detect the Motorola
- // processor at compile time.
-
- BOOST_ASSERT(false);
- return;
-
- case 0x3ffe8000: // IEEE extended double precision format
- // with 15 exponent bits
- offset_ = k;
- exponent = 0x7fff0000;
- flag = 0x00000000;
- mantissa = 0x0000ffff;
- return;
-
- case 0x3ffec000: // Intel extended double precision format
-
- offset_ = k;
- exponent = 0x7fff0000;
- flag = 0x00008000;
- mantissa = 0x00007fff;
- return;
-
- default:
- continue;
- }
- }
-
- BOOST_ASSERT(false);
-
- // Unknown format.
-}
-
-
-// float (32 bits) -------------------------------------------------------------
-
-template<> struct fp_traits_impl<float, single_precision_tag>
-{
- typedef uint32_t bits;
- typedef all_bits coverage;
-
- BOOST_STATIC_CONSTANT(uint32_t, sign = 0x80000000);
- BOOST_STATIC_CONSTANT(uint32_t, exponent = 0x7f800000);
- BOOST_STATIC_CONSTANT(uint32_t, flag = 0x00000000);
- BOOST_STATIC_CONSTANT(uint32_t, mantissa = 0x007fffff);
-
- static void init() {}
- static void get_bits(float x, uint32_t& a) { memcpy(&a, &x, 4); }
- static void set_bits(float& x, uint32_t a) { memcpy(&x, &a, 4); }
-};
-
-
-// double (64 bits) ------------------------------------------------------------
-
-#if defined(BOOST_NO_INT64_T) || defined(BOOST_NO_INCLASS_MEMBER_INITIALIZATION)
-
-template<> struct fp_traits_impl<double, double_precision_tag>
-{
- typedef uint32_t bits;
- typedef not_all_bits coverage;
-
- BOOST_STATIC_CONSTANT(uint32_t, sign = 0x80000000);
- BOOST_STATIC_CONSTANT(uint32_t, exponent = 0x7ff00000);
- BOOST_STATIC_CONSTANT(uint32_t, flag = 0);
- BOOST_STATIC_CONSTANT(uint32_t, mantissa = 0x000fffff);
-
- static void init() {}
-
- static void get_bits(double x, uint32_t& a)
- {
- memcpy(&a, reinterpret_cast<const unsigned char*>(&x) + offset_, 4);
- }
-
- static void set_bits(double& x, uint32_t a)
- {
- memcpy(reinterpret_cast<unsigned char*>(&x) + offset_, &a, 4);
- }
-
-private:
-
-#if defined(BOOST_BIG_ENDIAN)
- BOOST_STATIC_CONSTANT(int, offset_ = 0);
-#elif defined(BOOST_LITTLE_ENDIAN)
- BOOST_STATIC_CONSTANT(int, offset_ = 4);
-#else
- BOOST_STATIC_ASSERT(false);
-#endif
-};
-
-//..............................................................................
-
-#else
-
-template<> struct fp_traits_impl<double, double_precision_tag>
-{
- typedef uint64_t bits;
- typedef all_bits coverage;
-
- static const uint64_t sign = (uint64_t)0x80000000 << 32;
- static const uint64_t exponent = (uint64_t)0x7ff00000 << 32;
- static const uint64_t flag = 0;
- static const uint64_t mantissa
- = ((uint64_t)0x000fffff << 32) + (uint64_t)0xffffffff;
-
- static void init() {}
- static void get_bits(double x, uint64_t& a) { memcpy(&a, &x, 8); }
- static void set_bits(double& x, uint64_t a) { memcpy(&x, &a, 8); }
-};
-
-#endif
-
-
-// long double (64 bits) -------------------------------------------------------
-
-#if defined(BOOST_NO_INT64_T) || defined(BOOST_NO_INCLASS_MEMBER_INITIALIZATION)
-
-template<> struct fp_traits_impl<long double, double_precision_tag>
-{
- typedef uint32_t bits;
- typedef not_all_bits coverage;
-
- BOOST_STATIC_CONSTANT(uint32_t, sign = 0x80000000);
- BOOST_STATIC_CONSTANT(uint32_t, exponent = 0x7ff00000);
- BOOST_STATIC_CONSTANT(uint32_t, flag = 0);
- BOOST_STATIC_CONSTANT(uint32_t, mantissa = 0x000fffff);
-
- static void init() {}
-
- static void get_bits(long double x, uint32_t& a)
- {
- memcpy(&a, reinterpret_cast<const unsigned char*>(&x) + offset_, 4);
- }
-
- static void set_bits(long double& x, uint32_t a)
- {
- memcpy(reinterpret_cast<unsigned char*>(&x) + offset_, &a, 4);
- }
-
-private:
-
-#if defined(BOOST_BIG_ENDIAN)
- BOOST_STATIC_CONSTANT(int, offset_ = 0);
-#elif defined(BOOST_LITTLE_ENDIAN)
- BOOST_STATIC_CONSTANT(int, offset_ = 4);
-#else
- BOOST_STATIC_ASSERT(false);
-#endif
-};
-
-//..............................................................................
-
-#else
-
-template<> struct fp_traits_impl<long double, double_precision_tag>
-{
- typedef uint64_t bits;
- typedef all_bits coverage;
-
- static const uint64_t sign = (uint64_t)0x80000000 << 32;
- static const uint64_t exponent = (uint64_t)0x7ff00000 << 32;
- static const uint64_t flag = 0;
- static const uint64_t mantissa
- = ((uint64_t)0x000fffff << 32) + (uint64_t)0xffffffff;
-
- static void init() {}
- static void get_bits(long double x, uint64_t& a) { memcpy(&a, &x, 8); }
- static void set_bits(long double& x, uint64_t a) { memcpy(&x, &a, 8); }
-};
-
-#endif
-
-
-// long double (>64 bits), x86 and x64 -----------------------------------------
-
-#if defined(__i386) || defined(__i386__) || defined(_M_IX86) \
- || defined(__amd64) || defined(__amd64__) || defined(_M_AMD64) \
- || defined(__x86_64) || defined(__x86_64__) || defined(_M_X64)
-
-// Intel extended double precision format (80 bits)
-
-template<> struct fp_traits_impl<long double, extended_double_precision_tag>
-{
- typedef uint32_t bits;
- typedef not_all_bits coverage;
-
- BOOST_STATIC_CONSTANT(uint32_t, sign = 0x80000000);
- BOOST_STATIC_CONSTANT(uint32_t, exponent = 0x7fff0000);
- BOOST_STATIC_CONSTANT(uint32_t, flag = 0x00008000);
- BOOST_STATIC_CONSTANT(uint32_t, mantissa = 0x00007fff);
-
- static void init() {}
-
- static void get_bits(long double x, uint32_t& a)
- {
- memcpy(&a, reinterpret_cast<const unsigned char*>(&x) + 6, 4);
- }
-
- static void set_bits(long double& x, uint32_t a)
- {
- memcpy(reinterpret_cast<unsigned char*>(&x) + 6, &a, 4);
- }
-};
-
-
-// long double (>64 bits), Itanium ---------------------------------------------
-
-#elif defined(__ia64) || defined(__ia64__) || defined(_M_IA64)
-
-// The floating point format is unknown at compile time
-// No template specialization is provided.
-// The generic definition is used.
-
-// The Itanium supports both
-// the Intel extended double precision format (80 bits) and
-// the IEEE extended double precision format with 15 exponent bits (128 bits).
-
-
-// long double (>64 bits), PowerPC ---------------------------------------------
-
-#elif defined(__powerpc) || defined(__powerpc__) || defined(__POWERPC__) \
- || defined(__ppc) || defined(__ppc__) || defined(__PPC__)
-
-// PowerPC extended double precision format (128 bits)
-
-template<> struct fp_traits_impl<long double, extended_double_precision_tag>
-{
- typedef uint32_t bits;
- typedef not_all_bits coverage;
-
- BOOST_STATIC_CONSTANT(uint32_t, sign = 0x80000000);
- BOOST_STATIC_CONSTANT(uint32_t, exponent = 0x7ff00000);
- BOOST_STATIC_CONSTANT(uint32_t, flag = 0x00000000);
- BOOST_STATIC_CONSTANT(uint32_t, mantissa = 0x000fffff);
-
- static void init() {}
-
- static void get_bits(long double x, uint32_t& a)
- {
- memcpy(&a, reinterpret_cast<const unsigned char*>(&x) + offset_, 4);
- }
-
- static void set_bits(long double& x, uint32_t a)
- {
- memcpy(reinterpret_cast<unsigned char*>(&x) + offset_, &a, 4);
- }
-
-private:
-
-#if defined(BOOST_BIG_ENDIAN)
- BOOST_STATIC_CONSTANT(int, offset_ = 0);
-#elif defined(BOOST_LITTLE_ENDIAN)
- BOOST_STATIC_CONSTANT(int, offset_ = 12);
-#else
- BOOST_STATIC_ASSERT(false);
-#endif
-};
-
-
-// long double (>64 bits), Motorola 68K ----------------------------------------
-
-#elif defined(__m68k) || defined(__m68k__) \
- || defined(__mc68000) || defined(__mc68000__) \
-
-// Motorola extended double precision format (96 bits)
-
-// It is the same format as the Intel extended double precision format,
-// except that 1) it is big-endian, 2) the 3rd and 4th byte are padding, and
-// 3) the flag bit is not set for infinity
-
-template<> struct fp_traits_impl<long double, extended_double_precision_tag>
-{
- typedef uint32_t bits;
- typedef not_all_bits coverage;
-
- BOOST_STATIC_CONSTANT(uint32_t, sign = 0x80000000);
- BOOST_STATIC_CONSTANT(uint32_t, exponent = 0x7fff0000);
- BOOST_STATIC_CONSTANT(uint32_t, flag = 0x00008000);
- BOOST_STATIC_CONSTANT(uint32_t, mantissa = 0x00007fff);
-
- static void init() {}
-
- // copy 1st, 2nd, 5th and 6th byte. 3rd and 4th byte are padding.
-
- static void get_bits(long double x, uint32_t& a)
- {
- memcpy(&a, &x, 2);
- memcpy(reinterpret_cast<unsigned char*>(&a) + 2,
- reinterpret_cast<const unsigned char*>(&x) + 4, 2);
- }
-
- static void set_bits(long double& x, uint32_t a)
- {
- memcpy(&x, &a, 2);
- memcpy(reinterpret_cast<unsigned char*>(&x) + 4,
- reinterpret_cast<const unsigned char*>(&a) + 2, 2);
- }
-};
-
-
-// long double (>64 bits), All other processors --------------------------------
-
-#else
-
-// IEEE extended double precision format with 15 exponent bits (128 bits)
-
-template<> struct fp_traits_impl<long double, extended_double_precision_tag>
-{
- typedef uint32_t bits;
- typedef not_all_bits coverage;
-
- BOOST_STATIC_CONSTANT(uint32_t, sign = 0x80000000);
- BOOST_STATIC_CONSTANT(uint32_t, exponent = 0x7fff0000);
- BOOST_STATIC_CONSTANT(uint32_t, flag = 0x00000000);
- BOOST_STATIC_CONSTANT(uint32_t, mantissa = 0x0000ffff);
-
- static void init() {}
-
- static void get_bits(long double x, uint32_t& a)
- {
- memcpy(&a, reinterpret_cast<const unsigned char*>(&x) + offset_, 4);
- }
-
- static void set_bits(long double& x, uint32_t a)
- {
- memcpy(reinterpret_cast<unsigned char*>(&x) + offset_, &a, 4);
- }
-
-private:
-
-#if defined(BOOST_BIG_ENDIAN)
- BOOST_STATIC_CONSTANT(int, offset_ = 0);
-#elif defined(BOOST_LITTLE_ENDIAN)
- BOOST_STATIC_CONSTANT(int, offset_ = 12);
-#else
- BOOST_STATIC_ASSERT(false);
-#endif
-};
-
-#endif
-
-
-//------------------------------------------------------------------------------
-
-// size_to_precision is a type switch for converting a C++ floating point type
-// to the corresponding precision type.
-
-template<int n> struct size_to_precision;
-
-template<> struct size_to_precision<4>
-{
- typedef single_precision_tag type;
-};
-
-template<> struct size_to_precision<8>
-{
- typedef double_precision_tag type;
-};
-
-template<> struct size_to_precision<10>
-{
- typedef extended_double_precision_tag type;
-};
-
-template<> struct size_to_precision<12>
-{
- typedef extended_double_precision_tag type;
-};
-
-template<> struct size_to_precision<16>
-{
- typedef extended_double_precision_tag type;
-};
-
-// fp_traits is a type switch that selects the right fp_traits_impl
-
-template<class T> struct fp_traits
-{
- BOOST_STATIC_ASSERT(boost::is_floating_point<T>::value);
- typedef BOOST_DEDUCED_TYPENAME size_to_precision<sizeof(T)>::type precision;
- typedef fp_traits_impl<T, precision> type;
-};
-
-
-//------------------------------------------------------------------------------
-
-} // namespace detail
-} // namespace math
-} // namespace boost
-
-#endif
=== removed file 'extra/floating_point_utilities_v3/boost/math/fpclassify.hpp'
--- extra/floating_point_utilities_v3/boost/math/fpclassify.hpp 2010-04-19 10:18:42 +0000
+++ extra/floating_point_utilities_v3/boost/math/fpclassify.hpp 1970-01-01 00:00:00 +0000
@@ -1,229 +0,0 @@
-// fpclassify.hpp
-
-#ifndef BOOST_MATH_FPCLASSIFY_HPP
-#define BOOST_MATH_FPCLASSIFY_HPP
-
-// Copyright (c) 2006 Johan Rade
-
-// Distributed under the Boost Software License, Version 1.0.
-// (See accompanying file LICENSE_1_0.txt
-// or copy at http://www.boost.org/LICENSE_1_0.txt)
-
-/*
-The following algorithm is used:
-
- If all exponent bits, the flag bit (if there is one),
- and all mantissa bits are 0, then the number is zero.
-
- If all exponent bits and the flag bit (if there is one) are 0,
- and at least one mantissa bit is 1, then the number is subnormal.
-
- If all exponent bits are 1 and all mantissa bits are 0,
- then the number is infinity.
-
- If all exponent bits are 1 and at least one mantissa bit is 1,
- then the number is a not-a-number.
-
- Otherwise the number is normal.
-
-(Note that the binary representation of infinity
-has flag bit 0 for Motorola 68K extended double precision,
-and flag bit 1 for Intel extended double precision.)
-
-To get the bits, the four or eight most significant bytes are copied
-into an uint32_t or uint64_t and bit masks are applied.
-This covers all the exponent bits and the flag bit (if there is one),
-but not always all the mantissa bits.
-Some of the functions below have two implementations,
-depending on whether all the mantissa bits are copied or not.
-*/
-
-#include <cmath>
-
-#ifndef FP_INFINITE
-# define FP_INFINITE 0
-# define FP_NAN 1
-# define FP_NORMAL 2
-# define FP_SUBNORMAL 3
-# define FP_ZERO 4
-#endif
-
-#include "detail/fp_traits.hpp"
-
-namespace boost {
-namespace math {
-
-//------------------------------------------------------------------------------
-
-template<class T> bool (isfinite)(T x)
-{
- typedef BOOST_DEDUCED_TYPENAME detail::fp_traits<T>::type traits;
- traits::init();
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a &= traits::exponent;
- return a != traits::exponent;
-}
-
-//------------------------------------------------------------------------------
-
-template<class T> bool (isnormal)(T x)
-{
- typedef BOOST_DEDUCED_TYPENAME detail::fp_traits<T>::type traits;
- traits::init();
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a &= traits::exponent | traits::flag;
- return (a != 0) && (a < traits::exponent);
-}
-
-//------------------------------------------------------------------------------
-
-namespace detail {
-
- template<class T> bool isinf_impl(T x, all_bits)
- {
- typedef BOOST_DEDUCED_TYPENAME fp_traits<T>::type traits;
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a &= traits::exponent | traits::mantissa;
- return a == traits::exponent;
- }
-
- template<class T> bool isinf_impl(T x, not_all_bits)
- {
- typedef BOOST_DEDUCED_TYPENAME fp_traits<T>::type traits;
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a &= traits::exponent | traits::mantissa;
- if(a != traits::exponent)
- return false;
-
- traits::set_bits(x,0);
- return x == 0;
- }
-
-} // namespace detail
-
-template<class T> bool (isinf)(T x)
-{
- typedef BOOST_DEDUCED_TYPENAME detail::fp_traits<T>::type traits;
- traits::init();
- return detail::isinf_impl(x, BOOST_DEDUCED_TYPENAME traits::coverage());
-}
-
-//------------------------------------------------------------------------------
-
-namespace detail {
-
- template<class T> bool isnan_impl(T x, all_bits)
- {
- typedef BOOST_DEDUCED_TYPENAME fp_traits<T>::type traits;
- traits::init();
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a &= traits::exponent | traits::mantissa;
- return a > traits::exponent;
- }
-
- template<class T> bool isnan_impl(T x, not_all_bits)
- {
- typedef BOOST_DEDUCED_TYPENAME fp_traits<T>::type traits;
- traits::init();
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
-
- a &= traits::exponent | traits::mantissa;
- if(a < traits::exponent)
- return false;
-
- a &= traits::mantissa;
- traits::set_bits(x,a);
- return x != 0;
- }
-
-} // namespace detail
-
-template<class T> bool (isnan)(T x)
-{
- typedef BOOST_DEDUCED_TYPENAME detail::fp_traits<T>::type traits;
- traits::init();
- return detail::isnan_impl(x, BOOST_DEDUCED_TYPENAME traits::coverage());
-}
-
-//------------------------------------------------------------------------------
-
-namespace detail {
-
- template<class T> int fpclassify_impl(T x, all_bits)
- {
- typedef BOOST_DEDUCED_TYPENAME fp_traits<T>::type traits;
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a &= traits::exponent | traits::flag | traits::mantissa;
-
- if(a <= traits::mantissa) {
- if(a == 0)
- return FP_ZERO;
- else
- return FP_SUBNORMAL;
- }
-
- if(a < traits::exponent)
- return FP_NORMAL;
-
- a &= traits::mantissa;
- if(a == 0)
- return FP_INFINITE;
-
- return FP_NAN;
- }
-
- template<class T> int fpclassify_impl(T x, not_all_bits)
- {
- typedef BOOST_DEDUCED_TYPENAME fp_traits<T>::type traits;
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a &= traits::exponent | traits::flag | traits::mantissa;
-
- if(a <= traits::mantissa) {
- if(x == 0)
- return FP_ZERO;
- else
- return FP_SUBNORMAL;
- }
-
- if(a < traits::exponent)
- return FP_NORMAL;
-
- a &= traits::mantissa;
- traits::set_bits(x,a);
- if(x == 0)
- return FP_INFINITE;
-
- return FP_NAN;
- }
-
-} // namespace detail
-
-template<class T> int (fpclassify)(T x)
-{
- typedef BOOST_DEDUCED_TYPENAME detail::fp_traits<T>::type traits;
- traits::init();
- return detail::fpclassify_impl(x, BOOST_DEDUCED_TYPENAME traits::coverage());
-}
-
-//------------------------------------------------------------------------------
-
-} // namespace math
-} // namespace boost
-
-#endif
=== removed file 'extra/floating_point_utilities_v3/boost/math/nonfinite_num_facets.hpp'
--- extra/floating_point_utilities_v3/boost/math/nonfinite_num_facets.hpp 2010-04-19 10:18:42 +0000
+++ extra/floating_point_utilities_v3/boost/math/nonfinite_num_facets.hpp 1970-01-01 00:00:00 +0000
@@ -1,475 +0,0 @@
-#ifndef BOOST_MATH_NONFINITE_NUM_FACETS_HPP
-#define BOOST_MATH_NONFINITE_NUM_FACETS_HPP
-
-// Copyright (c) 2006 Johan Rade
-
-// Distributed under the Boost Software License, Version 1.0.
-// (See accompanying file LICENSE_1_0.txt
-// or copy at http://www.boost.org/LICENSE_1_0.txt)
-
-#include <cstring>
-#include <ios>
-#include <limits>
-#include <locale>
-#include "fpclassify.hpp"
-#include "signbit.hpp"
-
-#ifdef _MSC_VER
-# pragma warning(push)
-# pragma warning(disable : 4127 4511 4512 4706)
-#endif
-
-namespace boost {
-namespace math {
-
-
-// flags -----------------------------------------------------------------------
-
-const int legacy = 0x1;
-const int signed_zero = 0x2;
-const int trap_infinity = 0x4;
-const int trap_nan = 0x8;
-
-
-// class nonfinite_num_put -----------------------------------------------------
-
-template<
- class CharType,
- class OutputIterator = std::ostreambuf_iterator<CharType>
->
-class nonfinite_num_put : public std::num_put<CharType, OutputIterator> {
-public:
- explicit nonfinite_num_put(int flags = 0) : flags_(flags) {}
-
-protected:
- virtual OutputIterator do_put(
- OutputIterator it, std::ios_base& iosb,
- CharType fill, double val) const
- {
- put_and_reset_width(it, iosb, fill, val);
- return it;
- }
-
- virtual OutputIterator do_put(
- OutputIterator it, std::ios_base& iosb,
- CharType fill, long double val) const
- {
- put_and_reset_width(it, iosb, fill, val);
- return it;
- }
-
-private:
- template<class ValType> void put_and_reset_width(
- OutputIterator& it, std::ios_base& iosb,
- CharType fill, ValType val) const
- {
- put_impl(it, iosb, fill, val);
- iosb.width(0);
- }
-
- template<class ValType> void put_impl(
- OutputIterator& it, std::ios_base& iosb,
- CharType fill, ValType val) const
- {
- switch((boost::math::fpclassify)(val)) {
-
- case FP_INFINITE:
- if(flags_ & trap_infinity)
- throw std::ios_base::failure("Infinity");
- else if((boost::math::signbit)(val))
- put_num_and_fill(it, iosb, "-", "inf", fill);
- else if(iosb.flags() & std::ios_base::showpos)
- put_num_and_fill(it, iosb, "+", "inf", fill);
- else
- put_num_and_fill(it, iosb, "", "inf", fill);
- break;
-
- case FP_NAN:
- if(flags_ & trap_nan)
- throw std::ios_base::failure("NaN");
- else if((boost::math::signbit)(val))
- put_num_and_fill(it, iosb, "-", "nan", fill);
- else if(iosb.flags() & std::ios_base::showpos)
- put_num_and_fill(it, iosb, "+", "nan", fill);
- else
- put_num_and_fill(it, iosb, "", "nan", fill);
- break;
-
- case FP_ZERO:
- if(flags_ & signed_zero) {
- if((boost::math::signbit)(val))
- put_num_and_fill(it, iosb, "-", "0", fill);
- else if(iosb.flags() & std::ios_base::showpos)
- put_num_and_fill(it, iosb, "+", "0", fill);
- else
- put_num_and_fill(it, iosb, "", "0", fill);
- }
- else
- put_num_and_fill(it, iosb, "", "0", fill);
- break;
-
- default:
- it = std::num_put<CharType, OutputIterator>::do_put(
- it, iosb, fill, val);
- break;
- }
- }
-
- void put_num_and_fill(
- OutputIterator& it, std::ios_base& iosb, const char* prefix,
- const char* body, CharType fill) const
- {
- int width = (int)strlen(prefix) + (int)strlen(body);
- std::ios_base::fmtflags adjust
- = iosb.flags() & std::ios_base::adjustfield;
- const std::ctype<CharType>& ct
- = std::use_facet<std::ctype<CharType> >(iosb.getloc());
-
- if(adjust != std::ios_base::internal && adjust != std::ios_base::left)
- put_fill(it, iosb, fill, width);
-
- while(*prefix)
- *it = ct.widen(*(prefix++));
-
- if(adjust == std::ios_base::internal)
- put_fill(it, iosb, fill, width);
-
- if(iosb.flags() & std::ios_base::uppercase) {
- while(*body)
- *it = ct.toupper(ct.widen(*(body++)));
- }
- else {
- while(*body)
- *it = ct.widen(*(body++));
- }
-
- if(adjust == std::ios_base::left)
- put_fill(it, iosb, fill, width);
- }
-
- void put_fill(
- OutputIterator& it, std::ios_base& iosb,
- CharType fill, int width) const
- {
- for(int i = iosb.width() - width; i > 0; --i)
- *it = fill;
- }
-
-private:
- const int flags_;
-};
-
-
-// class nonfinite_num_get ------------------------------------------------------
-
-template<
- class CharType,
- class InputIterator = std::istreambuf_iterator<CharType>
->
-class nonfinite_num_get : public std::num_get<CharType, InputIterator> {
-public:
- explicit nonfinite_num_get(int flags = 0) : flags_(flags) {}
-
-protected:
- virtual InputIterator do_get(
- InputIterator it, InputIterator end, std::ios_base& iosb,
- std::ios_base::iostate& state, float& val) const
- {
- get_and_check_eof(it, end, iosb, state, val);
- return it;
- }
-
- virtual InputIterator do_get(
- InputIterator it, InputIterator end, std::ios_base& iosb,
- std::ios_base::iostate& state, double& val) const
- {
- get_and_check_eof(it, end, iosb, state, val);
- return it;
- }
-
- virtual InputIterator do_get(
- InputIterator it, InputIterator end, std::ios_base& iosb,
- std::ios_base::iostate& state, long double& val) const
- {
- get_and_check_eof(it, end, iosb, state, val);
- return it;
- }
-
-//..............................................................................
-
-private:
- template<class ValType> static ValType positive_nan()
- {
- // on some platforms quiet_NaN() is negative
- return (boost::math::copysign)(
- std::numeric_limits<ValType>::quiet_NaN(), 1);
- }
-
- template<class ValType> void get_and_check_eof(
- InputIterator& it, InputIterator end, std::ios_base& iosb,
- std::ios_base::iostate& state, ValType& val) const
- {
- get_signed(it, end, iosb, state, val);
- if(it == end)
- state |= std::ios_base::eofbit;
- }
-
- template<class ValType> void get_signed(
- InputIterator& it, InputIterator end, std::ios_base& iosb,
- std::ios_base::iostate& state, ValType& val) const
- {
- const std::ctype<CharType>& ct
- = std::use_facet<std::ctype<CharType> >(iosb.getloc());
-
- char c = peek_char(it, end, ct);
-
- bool negative = (c == '-');
-
- if(negative || c == '+') {
- ++it;
- c = peek_char(it, end, ct);
- if(c == '-' || c == '+') {
- // without this check, "++5" etc would be accepted
- state |= std::ios_base::failbit;
- return;
- }
- }
-
- get_unsigned(it, end, iosb, ct, state, val);
-
- if(negative)
- val = (boost::math::changesign)(val);
- }
-
- template<class ValType> void get_unsigned(
- InputIterator& it, InputIterator end, std::ios_base& iosb,
- const std::ctype<CharType>& ct,
- std::ios_base::iostate& state, ValType& val) const
- {
- switch(peek_char(it, end, ct)) {
-
- case 'i':
- get_i(it, end, ct, state, val);
- break;
-
- case 'n':
- get_n(it, end, ct, state, val);
- break;
-
- case 'q':
- case 's':
- get_q(it, end, ct, state, val);
- break;
-
- default:
- it = std::num_get<CharType, InputIterator>::do_get(
- it, end, iosb, state, val);
- if((flags_ & legacy) && val == static_cast<ValType>(1)
- && peek_char(it, end, ct) == '#')
- get_one_hash(it, end, ct, state, val);
- break;
- }
- }
-
- //..........................................................................
-
- template<class ValType> void get_i(
- InputIterator& it, InputIterator end, const std::ctype<CharType>& ct,
- std::ios_base::iostate& state, ValType& val) const
- {
- if(!std::numeric_limits<ValType>::has_infinity
- || (flags_ & trap_infinity)) {
- state |= std::ios_base::failbit;
- return;
- }
-
- ++it;
-
- if(!match_string(it, end, ct, "nf")) {
- state |= std::ios_base::failbit;
- return;
- }
-
- if(peek_char(it, end, ct) != 'i') {
- val = std::numeric_limits<ValType>::infinity(); // "inf"
- return;
- }
-
- ++it;
-
- if(!match_string(it, end, ct, "nity")) {
- state |= std::ios_base::failbit;
- return;
- }
-
- val = std::numeric_limits<ValType>::infinity(); // "infinity"
- }
-
- template<class ValType> void get_n(
- InputIterator& it, InputIterator end, const std::ctype<CharType>& ct,
- std::ios_base::iostate& state, ValType& val) const
- {
- if(!std::numeric_limits<ValType>::has_quiet_NaN
- || (flags_ & trap_nan)) {
- state |= std::ios_base::failbit;
- return;
- }
-
- ++it;
-
- if(!match_string(it, end, ct, "an")) {
- state |= std::ios_base::failbit;
- return;
- }
-
- switch(peek_char(it, end, ct)) {
- case 'q':
- case 's':
- if(flags_ && legacy)
- ++it;
- break; // "nanq", "nans"
-
- case '(':
- {
- ++it;
- char c;
- while((c = peek_char(it, end, ct))
- && c != ')' && c != ' ' && c != '\n' && c != '\t')
- ++it;
- if(c != ')') {
- state |= std::ios_base::failbit;
- return;
- }
- ++it;
- break; // "nan(...)"
- }
-
- default:
- break; // "nan"
- }
-
- val = positive_nan<ValType>();
- }
-
- template<class ValType> void get_q(
- InputIterator& it, InputIterator end, const std::ctype<CharType>& ct,
- std::ios_base::iostate& state, ValType& val) const
- {
- if(!std::numeric_limits<ValType>::has_quiet_NaN
- || (flags_ & trap_nan) || !(flags_ & legacy)) {
- state |= std::ios_base::failbit;
- return;
- }
-
- ++it;
-
- if(!match_string(it, end, ct, "nan")) {
- state |= std::ios_base::failbit;
- return;
- }
-
- val = positive_nan<ValType>(); // qnan, snan
- }
-
- template<class ValType> void get_one_hash(
- InputIterator& it, InputIterator end, const std::ctype<CharType>& ct,
- std::ios_base::iostate& state, ValType& val) const
- {
- ++it;
-
- switch(peek_char(it, end, ct)) {
- case 'i':
- get_one_hash_i(it, end, ct, state, val);
- return;
-
- case 'q':
- case 's':
- if(std::numeric_limits<ValType>::has_quiet_NaN
- && !(flags_ & trap_nan)) {
- ++it;
- if(match_string(it, end, ct, "nan")) {
- // "1.#QNAN", "1.#SNAN"
- ++it;
- val = positive_nan<ValType>();
- return;
- }
- }
- break;
-
- default:
- break;
- }
-
- state |= std::ios_base::failbit;
- }
-
- template<class ValType> void get_one_hash_i(
- InputIterator& it, InputIterator end, const std::ctype<CharType>& ct,
- std::ios_base::iostate& state, ValType& val) const
- {
- ++it;
-
- if(peek_char(it, end, ct) == 'n') {
- ++it;
- switch(peek_char(it, end, ct)) {
- case 'f': // "1.#INF"
- if(std::numeric_limits<ValType>::has_infinity
- && !(flags_ & trap_infinity)) {
- ++it;
- val = std::numeric_limits<ValType>::infinity();
- return;
- }
- break;
-
- case 'd': // 1.#IND"
- if(std::numeric_limits<ValType>::has_quiet_NaN
- && !(flags_ & trap_nan)) {
- ++it;
- val = positive_nan<ValType>();
- return;
- }
- break;
-
- default:
- break;
- }
- }
-
- state |= std::ios_base::failbit;
- }
-
- //..........................................................................
-
- char peek_char(
- InputIterator& it, InputIterator end,
- const std::ctype<CharType>& ct) const
- {
- if(it == end) return 0;
- return ct.narrow(ct.tolower(*it), 0);
- }
-
- bool match_string(
- InputIterator& it, InputIterator end,
- const std::ctype<CharType>& ct, const char* s) const
- {
- while(it != end && *s && *s == ct.narrow(ct.tolower(*it), 0)) {
- ++s;
- ++it;
- }
- return !*s;
- }
-
-private:
- const int flags_;
-};
-
-//------------------------------------------------------------------------------
-
-} // namespace serialization
-} // namespace boost
-
-#ifdef _MSC_VER
-# pragma warning(pop)
-#endif
-
-#endif
=== removed file 'extra/floating_point_utilities_v3/boost/math/signbit.hpp'
--- extra/floating_point_utilities_v3/boost/math/signbit.hpp 2010-04-19 10:18:42 +0000
+++ extra/floating_point_utilities_v3/boost/math/signbit.hpp 1970-01-01 00:00:00 +0000
@@ -1,86 +0,0 @@
-// signbit.hpp
-
-#ifndef BOOST_MATH_SIGNBIT_HPP
-#define BOOST_MATH_SIGNBIT_HPP
-
-// Copyright (c) 2006 Johan Rade
-
-// Distributed under the Boost Software License, Version 1.0.
-// (See accompanying file LICENSE_1_0.txt
-// or copy at http://www.boost.org/LICENSE_1_0.txt)
-
-#include "detail/fp_traits.hpp"
-
-namespace boost {
-namespace math {
-
-//------------------------------------------------------------------------------
-
-template<class T> bool (signbit)(T x)
-{
- typedef BOOST_DEDUCED_TYPENAME detail::fp_traits<T>::type traits;
- traits::init();
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a &= traits::sign;
- return a != 0;
-}
-
-//------------------------------------------------------------------------------
-
-namespace detail {
-
- template<class T> T copysign_impl(T x, T y)
- {
- typedef BOOST_DEDUCED_TYPENAME fp_traits<T>::type traits;
- traits::init();
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a &= ~traits::sign;
-
- BOOST_DEDUCED_TYPENAME traits::bits b;
- traits::get_bits(y,b);
- b &= traits::sign;
-
- traits::set_bits(x,a|b);
- return x;
- }
-}
-
-inline float (copysign)(float x, float y) // magnitude of x and sign of y
-{
- return detail::copysign_impl(x,y);
-}
-
-inline double (copysign)(double x, double y)
-{
- return detail::copysign_impl(x,y);
-}
-
-inline long double (copysign)(long double x, long double y)
-{
- return detail::copysign_impl(x,y);
-}
-
-//------------------------------------------------------------------------------
-
-template<class T> T (changesign)(T x)
-{
- typedef BOOST_DEDUCED_TYPENAME detail::fp_traits<T>::type traits;
- traits::init();
-
- BOOST_DEDUCED_TYPENAME traits::bits a;
- traits::get_bits(x,a);
- a ^= traits::sign;
- traits::set_bits(x,a);
- return x;
-}
-
-//------------------------------------------------------------------------------
-
-} // namespace math
-} // namespace boost
-
-#endif
=== modified file 'gui/qt4/GLViewer.cpp'
--- gui/qt4/GLViewer.cpp 2014-05-06 14:24:07 +0000
+++ gui/qt4/GLViewer.cpp 2014-05-23 13:05:19 +0000
@@ -27,8 +27,6 @@
#include<yade/lib/pyutil/gil.hpp>
#include<QtGui/qevent.h>
-using namespace boost;
-
#ifdef YADE_GL2PS
#include<gl2ps.h>
#endif
@@ -64,7 +62,7 @@
resize(550,550);
last=-1;
if(viewId==0) setWindowTitle("Primary view");
- else setWindowTitle(("Secondary view #"+lexical_cast<string>(viewId)).c_str());
+ else setWindowTitle(("Secondary view #"+boost::lexical_cast<string>(viewId)).c_str());
show();
@@ -134,7 +132,7 @@
const Se3r se3(renderer->clipPlaneSe3[planeNo]);
manipulatedFrame()->setPositionAndOrientation(qglviewer::Vec(se3.position[0],se3.position[1],se3.position[2]),qglviewer::Quaternion(se3.orientation.x(),se3.orientation.y(),se3.orientation.z(),se3.orientation.w()));
string grp=strBoundGroup();
- displayMessage("Manipulating clip plane #"+lexical_cast<string>(planeNo+1)+(grp.empty()?grp:" (bound planes:"+grp+")"));
+ displayMessage("Manipulating clip plane #"+boost::lexical_cast<string>(planeNo+1)+(grp.empty()?grp:" (bound planes:"+grp+")"));
}
string GLViewer::getState(){
@@ -171,7 +169,7 @@
else { resetManipulation(); displayMessage("Manipulating scene."); }
}
else if(e->key()==Qt::Key_Space){
- if(manipulatedClipPlane>=0) {displayMessage("Clip plane #"+lexical_cast<string>(manipulatedClipPlane+1)+(renderer->clipPlaneActive[manipulatedClipPlane]?" de":" ")+"activated"); renderer->clipPlaneActive[manipulatedClipPlane]=!renderer->clipPlaneActive[manipulatedClipPlane]; }
+ if(manipulatedClipPlane>=0) {displayMessage("Clip plane #"+boost::lexical_cast<string>(manipulatedClipPlane+1)+(renderer->clipPlaneActive[manipulatedClipPlane]?" de":" ")+"activated"); renderer->clipPlaneActive[manipulatedClipPlane]=!renderer->clipPlaneActive[manipulatedClipPlane]; }
else{ centerMedianQuartile(); }
}
/* function keys */
@@ -186,8 +184,8 @@
int n=0; if(e->key()==Qt::Key_1) n=1; else if(e->key()==Qt::Key_2) n=2; else if(e->key()==Qt::Key_3) n=3; assert(n>0); int planeId=n-1;
if(planeId>=renderer->numClipPlanes) return; // no such clipping plane
if(e->modifiers() & Qt::AltModifier){
- if(boundClipPlanes.count(planeId)==0) {boundClipPlanes.insert(planeId); displayMessage("Added plane #"+lexical_cast<string>(planeId+1)+" to the bound group: "+strBoundGroup());}
- else {boundClipPlanes.erase(planeId); displayMessage("Removed plane #"+lexical_cast<string>(planeId+1)+" from the bound group: "+strBoundGroup());}
+ if(boundClipPlanes.count(planeId)==0) {boundClipPlanes.insert(planeId); displayMessage("Added plane #"+boost::lexical_cast<string>(planeId+1)+" to the bound group: "+strBoundGroup());}
+ else {boundClipPlanes.erase(planeId); displayMessage("Removed plane #"+boost::lexical_cast<string>(planeId+1)+" from the bound group: "+strBoundGroup());}
}
else if(manipulatedClipPlane>=0 && manipulatedClipPlane!=planeId) {
const Quaternionr& o=renderer->clipPlaneSe3[planeId].orientation;
@@ -234,7 +232,7 @@
Quaternionr& ori=renderer->clipPlaneSe3[manipulatedClipPlane].orientation;
ori=Quaternionr(AngleAxisr(Mathr::PI,Vector3r(0,1,0)))*ori;
manipulatedFrame()->setOrientation(qglviewer::Quaternion(qglviewer::Vec(0,1,0),Mathr::PI)*manipulatedFrame()->orientation());
- displayMessage("Plane #"+lexical_cast<string>(manipulatedClipPlane+1)+" reversed.");
+ displayMessage("Plane #"+boost::lexical_cast<string>(manipulatedClipPlane+1)+" reversed.");
}
else {
camera()->setRevolveAroundPoint(sceneCenter());
@@ -279,17 +277,17 @@
else if( e->key()==Qt::Key_Plus ){
cut_plane = std::min(1.0, cut_plane + std::pow(10.0,(double)cut_plane_delta));
static_cast<YadeCamera*>(camera())->setCuttingDistance(cut_plane);
- displayMessage("Cut plane: "+lexical_cast<std::string>(cut_plane));
+ displayMessage("Cut plane: "+boost::lexical_cast<std::string>(cut_plane));
}else if( e->key()==Qt::Key_Minus ){
cut_plane = std::max(0.0, cut_plane - std::pow(10.0,(double)cut_plane_delta));
static_cast<YadeCamera*>(camera())->setCuttingDistance(cut_plane);
- displayMessage("Cut plane: "+lexical_cast<std::string>(cut_plane));
+ displayMessage("Cut plane: "+boost::lexical_cast<std::string>(cut_plane));
}else if( e->key()==Qt::Key_Slash ){
cut_plane_delta -= 1;
- displayMessage("Cut plane increment: 1e"+(cut_plane_delta>0?std::string("+"):std::string(""))+lexical_cast<std::string>(cut_plane_delta));
+ displayMessage("Cut plane increment: 1e"+(cut_plane_delta>0?std::string("+"):std::string(""))+boost::lexical_cast<std::string>(cut_plane_delta));
}else if( e->key()==Qt::Key_Asterisk ){
cut_plane_delta = std::min(1+cut_plane_delta,-1);
- displayMessage("Cut plane increment: 1e"+(cut_plane_delta>0?std::string("+"):std::string(""))+lexical_cast<std::string>(cut_plane_delta));
+ displayMessage("Cut plane increment: 1e"+(cut_plane_delta>0?std::string("+"):std::string(""))+boost::lexical_cast<std::string>(cut_plane_delta));
}
#endif
@@ -346,29 +344,26 @@
Scene* rb=Omega::instance().getScene().get();
if (!rb) return;
if(rb->isPeriodic){ centerPeriodic(); return; }
-
LOG_INFO("Select with shift, press 'm' to move.");
Vector3r min,max;
- if(rb->bound){
- min=rb->bound->min; max=rb->bound->max;
- bool hasNan=(isnan(min[0])||isnan(min[1])||isnan(min[2])||isnan(max[0])||isnan(max[1])||isnan(max[2]));
- Real minDim=std::min(max[0]-min[0],std::min(max[1]-min[1],max[2]-min[2]));
- if(minDim<=0 || hasNan){
- // Aabb is not yet calculated...
- LOG_DEBUG("scene's bound not yet calculated or has zero or nan dimension(s), attempt get that from bodies' positions.");
- Real inf=std::numeric_limits<Real>::infinity();
- min=Vector3r(inf,inf,inf); max=Vector3r(-inf,-inf,-inf);
- FOREACH(const shared_ptr<Body>& b, *rb->bodies){
- if(!b) continue;
- max=max.cwiseMax(b->state->pos);
- min=min.cwiseMin(b->state->pos);
- }
- if(isinf(min[0])||isinf(min[1])||isinf(min[2])||isinf(max[0])||isinf(max[1])||isinf(max[2])){ LOG_DEBUG("No min/max computed from bodies either, setting cube (-1,-1,-1)×(1,1,1)"); min=-Vector3r::Ones(); max=Vector3r::Ones(); }
- } else {LOG_DEBUG("Using scene's Aabb");}
- } else {
- LOG_DEBUG("No scene's Aabb; setting scene in cube (-1,-1,-1)x(1,1,1)");
- min=Vector3r(-1,-1,-1); max=Vector3r(1,1,1);
- }
+ if(not(rb->bound)){ rb->updateBound();}
+
+ min=rb->bound->min; max=rb->bound->max;
+ bool hasNan=(isnan(min[0])||isnan(min[1])||isnan(min[2])||isnan(max[0])||isnan(max[1])||isnan(max[2]));
+ Real minDim=std::min(max[0]-min[0],std::min(max[1]-min[1],max[2]-min[2]));
+ if(minDim<=0 || hasNan){
+ // Aabb is not yet calculated...
+ LOG_DEBUG("scene's bound not yet calculated or has zero or nan dimension(s), attempt get that from bodies' positions.");
+ Real inf=std::numeric_limits<Real>::infinity();
+ min=Vector3r(inf,inf,inf); max=Vector3r(-inf,-inf,-inf);
+ FOREACH(const shared_ptr<Body>& b, *rb->bodies){
+ if(!b) continue;
+ max=max.cwiseMax(b->state->pos);
+ min=min.cwiseMin(b->state->pos);
+ }
+ if(isinf(min[0])||isinf(min[1])||isinf(min[2])||isinf(max[0])||isinf(max[1])||isinf(max[2])){ LOG_DEBUG("No min/max computed from bodies either, setting cube (-1,-1,-1)×(1,1,1)"); min=-Vector3r::Ones(); max=Vector3r::Ones(); }
+ } else {LOG_DEBUG("Using scene's Aabb");}
+
LOG_DEBUG("Got scene box min="<<min<<" and max="<<max);
Vector3r center = (max+min)*0.5;
Vector3r halfSize = (max-min)*0.5;
@@ -404,16 +399,16 @@
setSelectedName(selection);
LOG_DEBUG("New selection "<<selection);
- displayMessage("Selected body #"+lexical_cast<string>(selection)+(Body::byId(selection)->isClump()?" (clump)":""));
+ displayMessage("Selected body #"+boost::lexical_cast<string>(selection)+(Body::byId(selection)->isClump()?" (clump)":""));
Omega::instance().getScene()->selectedBody = selection;
PyGILState_STATE gstate;
gstate = PyGILState_Ensure();
- python::object main=python::import("__main__");
- python::object global=main.attr("__dict__");
+ boost::python::object main=boost::python::import("__main__");
+ boost::python::object global=main.attr("__dict__");
// the try/catch block must be properly nested inside PyGILState_Ensure and PyGILState_Release
try{
- python::eval(string("onBodySelect("+lexical_cast<string>(selection)+")").c_str(),global,global);
- } catch (python::error_already_set const &) {
+ boost::python::eval(string("onBodySelect("+boost::lexical_cast<string>(selection)+")").c_str(),global,global);
+ } catch (boost::python::error_already_set const &) {
LOG_DEBUG("unable to call onBodySelect. Not defined?");
}
PyGILState_Release(gstate);
=== modified file 'gui/qt4/GLViewer.hpp'
--- gui/qt4/GLViewer.hpp 2014-03-08 21:19:02 +0000
+++ gui/qt4/GLViewer.hpp 2014-05-23 13:05:19 +0000
@@ -54,7 +54,7 @@
int manipulatedClipPlane;
set<int> boundClipPlanes;
shared_ptr<qglviewer::LocalConstraint> xyPlaneConstraint;
- string strBoundGroup(){string ret;FOREACH(int i, boundClipPlanes) ret+=" "+lexical_cast<string>(i+1);return ret;}
+ string strBoundGroup(){string ret;FOREACH(int i, boundClipPlanes) ret+=" "+boost::lexical_cast<string>(i+1);return ret;}
boost::posix_time::ptime last_user_event;
public:
=== modified file 'gui/qt4/GLViewerDisplay.cpp'
--- gui/qt4/GLViewerDisplay.cpp 2014-02-16 14:03:41 +0000
+++ gui/qt4/GLViewerDisplay.cpp 2014-05-23 13:05:19 +0000
@@ -29,8 +29,6 @@
#include<QtGui/qevent.h>
-using namespace boost;
-
#ifdef YADE_GL2PS
#include<gl2ps.h>
#endif
@@ -40,14 +38,14 @@
void GLViewer::useDisplayParameters(size_t n){
LOG_DEBUG("Loading display parameters from #"<<n);
vector<shared_ptr<DisplayParameters> >& dispParams=Omega::instance().getScene()->dispParams;
- if(dispParams.size()<=(size_t)n){ throw std::invalid_argument(("Display parameters #"+lexical_cast<string>(n)+" don't exist (number of entries "+lexical_cast<string>(dispParams.size())+")").c_str());; return;}
+ if(dispParams.size()<=(size_t)n){ throw std::invalid_argument(("Display parameters #"+boost::lexical_cast<string>(n)+" don't exist (number of entries "+boost::lexical_cast<string>(dispParams.size())+")").c_str());; return;}
const shared_ptr<DisplayParameters>& dp=dispParams[n];
string val;
if(dp->getValue("OpenGLRenderer",val)){ istringstream oglre(val);
yade::ObjectIO::load<typeof(renderer),boost::archive::xml_iarchive>(oglre,"renderer",renderer);
}
else { LOG_WARN("OpenGLRenderer configuration not found in display parameters, skipped.");}
- if(dp->getValue("GLViewer",val)){ GLViewer::setState(val); displayMessage("Loaded view configuration #"+lexical_cast<string>(n)); }
+ if(dp->getValue("GLViewer",val)){ GLViewer::setState(val); displayMessage("Loaded view configuration #"+boost::lexical_cast<string>(n)); }
else { LOG_WARN("GLViewer configuration not found in display parameters, skipped."); }
}
@@ -60,7 +58,7 @@
yade::ObjectIO::save<typeof(renderer),boost::archive::xml_oarchive>(oglre,"renderer",renderer);
dp->setValue("OpenGLRenderer",oglre.str());
dp->setValue("GLViewer",GLViewer::getState());
- displayMessage("Saved view configuration ot #"+lexical_cast<string>(n));
+ displayMessage("Saved view configuration ot #"+boost::lexical_cast<string>(n));
}
void GLViewer::draw()
=== modified file 'gui/qt4/GLViewerMouse.cpp'
--- gui/qt4/GLViewerMouse.cpp 2014-05-06 16:53:02 +0000
+++ gui/qt4/GLViewerMouse.cpp 2014-05-23 13:03:50 +0000
@@ -29,8 +29,6 @@
#include<QtGui/qevent.h>
-using namespace boost;
-
#ifdef YADE_GL2PS
#include<gl2ps.h>
#endif
=== added file 'gui/qt4/XYZ.xpm'
--- gui/qt4/XYZ.xpm 1970-01-01 00:00:00 +0000
+++ gui/qt4/XYZ.xpm 2014-05-15 14:47:33 +0000
@@ -0,0 +1,45 @@
+/* XPM */
+static char * XYZ_xpm[] = {
+"40 40 2 1",
+" c None",
+". c #000000",
+" .. .. ",
+" . . ",
+" .... ",
+" .... ",
+" .. ",
+" .. ",
+" .. ",
+" .. ",
+" ",
+" . ",
+" . ",
+" ... ",
+" ... ",
+" ... ",
+" ..... ",
+" ..... ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" ........... ",
+" . . ",
+" . ...... . .. .. ",
+" . .. . .. . . ",
+" . .. . ..... .... ",
+" . .. .................... .. ",
+" . . . ..... .. ",
+" . .. . ... .... ",
+" . .. . . . ",
+" . ...... . .. .. ",
+" . . ",
+" ........... ",
+" ",
+" "};
=== added file 'gui/qt4/YZX.xpm'
--- gui/qt4/YZX.xpm 1970-01-01 00:00:00 +0000
+++ gui/qt4/YZX.xpm 2014-05-15 14:47:33 +0000
@@ -0,0 +1,45 @@
+/* XPM */
+static char * YZX_xpm[] = {
+"40 40 2 1",
+" c None",
+". c #000000",
+" ...... ",
+" .. ",
+" .. ",
+" .. ",
+" . ",
+" .. ",
+" .. ",
+" ...... ",
+" ",
+" . ",
+" . ",
+" ... ",
+" ... ",
+" ... ",
+" ..... ",
+" ..... ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" ........... ",
+" . . ",
+" . .. .. . .. .. ",
+" . . . . .. . . ",
+" . .... . ..... .... ",
+" . .. .................... .... ",
+" . .. . ..... .. ",
+" . .... . ... .. ",
+" . . . . .. ",
+" . .. .. . .. ",
+" . . ",
+" ........... ",
+" ",
+" "};
=== added file 'gui/qt4/ZXY.xpm'
--- gui/qt4/ZXY.xpm 1970-01-01 00:00:00 +0000
+++ gui/qt4/ZXY.xpm 2014-05-15 14:47:33 +0000
@@ -0,0 +1,45 @@
+/* XPM */
+static char * ZXY_xpm[] = {
+"40 40 2 1",
+" c None",
+". c #000000",
+" .. .. ",
+" . . ",
+" .... ",
+" .. ",
+" .. ",
+" .... ",
+" . . ",
+" .. .. ",
+" ",
+" . ",
+" . ",
+" ... ",
+" ... ",
+" ... ",
+" ..... ",
+" ..... ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" . ",
+" ........... ",
+" . . ",
+" . .. .. . ...... ",
+" . . . . .. .. ",
+" . .... . ..... .. ",
+" . .... .................... .. ",
+" . .. . ..... . ",
+" . .. . ... .. ",
+" . .. . .. ",
+" . .. . ...... ",
+" . . ",
+" ........... ",
+" ",
+" "};
=== modified file 'gui/qt4/_GLViewer.cpp'
--- gui/qt4/_GLViewer.cpp 2012-11-01 21:42:22 +0000
+++ gui/qt4/_GLViewer.cpp 2014-05-23 13:05:19 +0000
@@ -9,13 +9,13 @@
namespace py=boost::python;
-qglviewer::Vec tuple2vec(py::tuple t){ qglviewer::Vec ret; for(int i=0;i<3;i++){py::extract<Real> e(t[i]); if(!e.check()) throw invalid_argument("Element #"+lexical_cast<string>(i)+" is not a number"); ret[i]=e();} return ret;};
+qglviewer::Vec tuple2vec(py::tuple t){ qglviewer::Vec ret; for(int i=0;i<3;i++){py::extract<Real> e(t[i]); if(!e.check()) throw invalid_argument("Element #"+boost::lexical_cast<string>(i)+" is not a number"); ret[i]=e();} return ret;};
py::tuple vec2tuple(qglviewer::Vec v){return py::make_tuple(v[0],v[1],v[2]);};
class pyGLViewer{
const size_t viewNo;
public:
- #define GLV if((OpenGLManager::self->views.size()<=viewNo) || !(OpenGLManager::self->views[viewNo])) throw runtime_error("No view #"+lexical_cast<string>(viewNo)); GLViewer* glv=OpenGLManager::self->views[viewNo].get();
+ #define GLV if((OpenGLManager::self->views.size()<=viewNo) || !(OpenGLManager::self->views[viewNo])) throw runtime_error("No view #"+boost::lexical_cast<string>(viewNo)); GLViewer* glv=OpenGLManager::self->views[viewNo].get();
pyGLViewer(size_t _viewNo=0): viewNo(_viewNo){}
void close(){ GLV; QCloseEvent* e(new QCloseEvent); QApplication::postEvent(glv,e); }
py::tuple get_grid(){GLV; return py::make_tuple(bool(glv->drawGrid & 1),bool(glv->drawGrid & 2),bool(glv->drawGrid & 4));}
@@ -40,7 +40,7 @@
void center(bool median){GLV; if(median)glv->centerMedianQuartile(); else glv->centerScene();}
Vector2i get_screenSize(){GLV; return Vector2i(glv->width(),glv->height());}
void set_screenSize(Vector2i t){ /*GLV;*/ OpenGLManager::self->emitResizeView(viewNo,t[0],t[1]);}
- string pyStr(){return string("<GLViewer for view #")+lexical_cast<string>(viewNo)+">";}
+ string pyStr(){return string("<GLViewer for view #")+boost::lexical_cast<string>(viewNo)+">";}
void saveDisplayParameters(size_t n){GLV; glv->saveDisplayParameters(n);}
void useDisplayParameters(size_t n){GLV; glv->useDisplayParameters(n);}
string get_timeDisp(){GLV; const int& m(glv->timeDispMask); string ret; if(m&GLViewer::TIME_REAL) ret+='r'; if(m&GLViewer::TIME_VIRT) ret+="v"; if(m&GLViewer::TIME_ITER) ret+="i"; return ret;}
=== modified file 'gui/qt4/controller.ui'
--- gui/qt4/controller.ui 2010-12-26 15:42:43 +0000
+++ gui/qt4/controller.ui 2014-05-15 14:47:33 +0000
@@ -21,7 +21,7 @@
</property>
<property name="windowIcon">
<iconset resource="img.qrc">
- <normaloff>:/img/yade-favicon.png</normaloff>:/img/yade-favicon.png</iconset>
+ <normaloff>:/img/yade-favicon.xpm</normaloff>:/img/yade-favicon.xpm</iconset>
</property>
<layout class="QGridLayout" name="gridLayout_3">
<property name="margin">
@@ -460,7 +460,7 @@
</property>
<property name="icon">
<iconset resource="img.qrc">
- <normaloff>:/img/XYZ.png</normaloff>:/img/XYZ.png</iconset>
+ <normaloff>:/img/XYZ.xpm</normaloff>:/img/XYZ.xpm</iconset>
</property>
<property name="iconSize">
<size>
@@ -483,7 +483,7 @@
</property>
<property name="icon">
<iconset resource="img.qrc">
- <normaloff>:/img/YZX.png</normaloff>:/img/YZX.png</iconset>
+ <normaloff>:/img/YZX.xpm</normaloff>:/img/YZX.xpm</iconset>
</property>
<property name="iconSize">
<size>
@@ -506,7 +506,7 @@
</property>
<property name="icon">
<iconset resource="img.qrc">
- <normaloff>:/img/ZXY.png</normaloff>:/img/ZXY.png</iconset>
+ <normaloff>:/img/ZXY.xpm</normaloff>:/img/ZXY.xpm</iconset>
</property>
<property name="iconSize">
<size>
=== modified file 'gui/qt4/img.qrc'
--- gui/qt4/img.qrc 2010-12-26 15:42:43 +0000
+++ gui/qt4/img.qrc 2014-05-15 14:47:33 +0000
@@ -1,8 +1,8 @@
<RCC>
<qresource prefix="img">
- <file>yade-favicon.png</file>
- <file>XYZ.png</file>
- <file>YZX.png</file>
- <file>ZXY.png</file>
+ <file>yade-favicon.xpm</file>
+ <file>XYZ.xpm</file>
+ <file>YZX.xpm</file>
+ <file>ZXY.xpm</file>
</qresource>
</RCC>
=== added file 'gui/qt4/yade-favicon.xpm'
--- gui/qt4/yade-favicon.xpm 1970-01-01 00:00:00 +0000
+++ gui/qt4/yade-favicon.xpm 2014-05-15 14:47:33 +0000
@@ -0,0 +1,229 @@
+/* XPM */
+static char * yade_favicon_xpm[] = {
+"16 16 210 2",
+" c None",
+". c #F47372",
+"+ c #F1B4B5",
+"@ c #909092",
+"# c #EA5A5A",
+"$ c #8E4D3C",
+"% c #746C35",
+"& c #616233",
+"* c #4B4B0E",
+"= c #939191",
+"- c #8A8A8A",
+"; c #808380",
+"> c #6F6E6D",
+", c #4F4D2B",
+"' c #646427",
+") c #383827",
+"! c #EB9D9E",
+"~ c #7F6B5D",
+"{ c #828500",
+"] c #A2A200",
+"^ c #838500",
+"/ c #404031",
+"( c #AEAEAE",
+"_ c #8C8C8C",
+": c #ABAAAF",
+"< c #444319",
+"[ c #9E9C01",
+"} c #B4B106",
+"| c #908E0C",
+"1 c #4C4C4F",
+"2 c #D0BBBB",
+"3 c #B07E83",
+"4 c #706137",
+"5 c #B9B704",
+"6 c #C8C901",
+"7 c #686800",
+"8 c #4C4C51",
+"9 c #A3A1A3",
+"0 c #ABA9AC",
+"a c #45444A",
+"b c #8F8E00",
+"c c #A3A005",
+"d c #AAA809",
+"e c #25241B",
+"f c #D79090",
+"g c #E25E5E",
+"h c #FCBEC9",
+"i c #E6AF6F",
+"j c #D6B700",
+"k c #ACAA00",
+"l c #3F4000",
+"m c #53525D",
+"n c #666472",
+"o c #6A6A02",
+"p c #B7B509",
+"q c #A3A407",
+"r c #3F4008",
+"s c #E07B7A",
+"t c #E35151",
+"u c #DC6565",
+"v c #C76B67",
+"w c #D79E42",
+"x c #ABA10D",
+"y c #99A400",
+"z c #393C21",
+"A c #40401D",
+"B c #9A9A01",
+"C c #B6B406",
+"D c #737100",
+"E c #545157",
+"F c #DCA8A8",
+"G c #DAA5A7",
+"H c #D86261",
+"I c #D85D5D",
+"J c #DEC7D1",
+"K c #E1BE91",
+"L c #B5C100",
+"M c #848D04",
+"N c #818103",
+"O c #8C8C08",
+"P c #7A7A02",
+"Q c #504F33",
+"R c #827F8D",
+"S c #C85757",
+"T c #CC6666",
+"U c #D65757",
+"V c #DB5353",
+"W c #E59596",
+"X c #E58A82",
+"Y c #BFB500",
+"Z c #B4BD05",
+"` c #BBBA0B",
+" . c #A4A306",
+".. c #5E5D13",
+"+. c #565463",
+"@. c #B47070",
+"#. c #C69392",
+"$. c #D57E7E",
+"%. c #DA2929",
+"&. c #ED393A",
+"*. c #8B3537",
+"=. c #949700",
+"-. c #9AA706",
+";. c #ABB10A",
+">. c #747502",
+",. c #2C2B35",
+"'. c #B2AFBB",
+"). c #B86363",
+"!. c #C8BEBE",
+"~. c #DBCFCF",
+"{. c #DF7373",
+"]. c #F16466",
+"^. c #E79DA6",
+"/. c #5A5408",
+"(. c #EEAC06",
+"_. c #EBBA08",
+":. c #312E0B",
+"<. c #7D7B8A",
+"[. c #8C899A",
+"}. c #858394",
+"|. c #777588",
+"1. c #B75E5E",
+"2. c #C38181",
+"3. c #D58383",
+"4. c #AB5B5A",
+"5. c #DF484A",
+"6. c #F28088",
+"7. c #5F4507",
+"8. c #FD8D08",
+"9. c #FFBD0C",
+"0. c #3D330C",
+"a. c #B8B5C6",
+"b. c #858297",
+"c. c #BD6464",
+"d. c #C24748",
+"e. c #CD5E5F",
+"f. c #D2ADAE",
+"g. c #DA8E91",
+"h. c #E73643",
+"i. c #5B3206",
+"j. c #EF8308",
+"k. c #EF7510",
+"l. c #3C2A0F",
+"m. c #ADAEC2",
+"n. c #8F8DA3",
+"o. c #8A88A1",
+"p. c #9490AB",
+"q. c #69687B",
+"r. c #C30C0C",
+"s. c #BD3C3F",
+"t. c #C6777A",
+"u. c #D6B7BA",
+"v. c #D9A2A7",
+"w. c #D9848C",
+"x. c #DBC5C3",
+"y. c #E49A37",
+"z. c #F59212",
+"A. c #482E17",
+"B. c #D5ABBA",
+"C. c #817A95",
+"D. c #A491A9",
+"E. c #8986A2",
+"F. c #8E89A7",
+"G. c #7B7795",
+"H. c #C55252",
+"I. c #C37072",
+"J. c #BE4951",
+"K. c #CA6A72",
+"L. c #CF4E5A",
+"M. c #D49098",
+"N. c #DDD2D6",
+"O. c #E6A489",
+"P. c #EB7313",
+"Q. c #452716",
+"R. c #FEC1CD",
+"S. c #E76B80",
+"T. c #F7BBC5",
+"U. c #CBACBA",
+"V. c #9292AD",
+"W. c #837FA0",
+"X. c #C62F2F",
+"Y. c #C73E3F",
+"Z. c #C53F4A",
+"`. c #B93344",
+" + c #CD3C4D",
+".+ c #D75767",
+"++ c #E17484",
+"@+ c #C46559",
+"#+ c #DA743E",
+"$+ c #53241E",
+"%+ c #ED546E",
+"&+ c #E66E82",
+"*+ c #F3BCC6",
+"=+ c #E19FAF",
+"-+ c #B81415",
+";+ c #BA4D4F",
+">+ c #AD7782",
+",+ c #AC4B5D",
+"'+ c #C09FA9",
+")+ c #BB3A52",
+"!+ c #C14F67",
+"~+ c #CD5858",
+"{+ c #E1AEAC",
+"]+ c #D9D0D0",
+"^+ c #D25169",
+"/+ c #DC7C8F",
+"(+ c #F0C9D1",
+"_+ c #E6A3B2",
+":+ c #A27791",
+"<+ c #AA98B1",
+". + @ ",
+"# $ % & * = - ; > , ' ) ",
+"! ~ { ] ^ / ( _ : < [ } | 1 ",
+"2 3 4 5 6 7 8 9 0 a b c d e ",
+"f g h i j k l m n o p q r ",
+"s t u v w x y z A B C D E ",
+"F G H I J K L M N O P Q R ",
+"S T U V W X Y Z ` ...+. ",
+"@.#.$.%.&.*.=.-.;.>.,. '. ",
+").!.~.{.].^./.(._.:.<.[.}.|. ",
+"1.2.3.4.5.6.7.8.9.0.a. b. ",
+"c.d.e.f.g.h.i.j.k.l.m.n.o. p.q.",
+"r.s.t.u.v.w.x.y.z.A.B.C.D.E.F.G.",
+"H.I.J.K.L.M.N.O.P.Q.R.S.T.U.V.W.",
+"X.Y.Z.`. +.+++@+#+$+%+&+*+=+ ",
+"-+;+>+,+'+)+!+~+{+]+^+/+(+_+:+<+"};
=== modified file 'lib/factory/DynLibManager.cpp'
--- lib/factory/DynLibManager.cpp 2009-11-29 15:46:19 +0000
+++ lib/factory/DynLibManager.cpp 2014-05-23 13:03:50 +0000
@@ -20,7 +20,6 @@
//using namespace std;
-using namespace boost;
CREATE_LOGGER(DynLibManager);
=== modified file 'lib/multimethods/DynLibDispatcher.hpp'
--- lib/multimethods/DynLibDispatcher.hpp 2010-11-07 11:46:20 +0000
+++ lib/multimethods/DynLibDispatcher.hpp 2014-05-23 13:05:19 +0000
@@ -37,8 +37,6 @@
using namespace std;
-using namespace boost;
-
struct DynLibDispatcher_Item2D{ int ix1, ix2; std::string functorName; DynLibDispatcher_Item2D(int a, int b, std::string c):ix1(a),ix2(b),functorName(c){}; };
struct DynLibDispatcher_Item1D{ int ix1 ; std::string functorName; DynLibDispatcher_Item1D(int a, std::string c):ix1(a), functorName(c){}; };
@@ -184,13 +182,13 @@
shared_ptr<Executor> getExecutor(shared_ptr<BaseClass1>& arg1){
int ix1;
- if(arg1->getClassIndex()<0) throw runtime_error("No functor for type "+arg1->getClassName()+" (index "+lexical_cast<string>(arg1->getClassIndex())+"), since the index is invalid (negative).");
+ if(arg1->getClassIndex()<0) throw runtime_error("No functor for type "+arg1->getClassName()+" (index "+boost::lexical_cast<string>(arg1->getClassIndex())+"), since the index is invalid (negative).");
if(locateMultivirtualFunctor1D(ix1,arg1)) return callBacks[ix1];
return shared_ptr<Executor>();
}
shared_ptr<Executor> getExecutor(shared_ptr<BaseClass1>& arg1, shared_ptr<BaseClass2>& arg2){
- if(arg1->getClassIndex()<0 || arg2->getClassIndex()<0) throw runtime_error("No functor for types "+arg1->getClassName()+" (index "+lexical_cast<string>(arg1->getClassIndex())+") + "+arg2->getClassName()+" (index "+lexical_cast<string>(arg2->getClassIndex())+"), since some of the indices is invalid (negative).");
+ if(arg1->getClassIndex()<0 || arg2->getClassIndex()<0) throw runtime_error("No functor for types "+arg1->getClassName()+" (index "+boost::lexical_cast<string>(arg1->getClassIndex())+") + "+arg2->getClassName()+" (index "+boost::lexical_cast<string>(arg2->getClassIndex())+"), since some of the indices is invalid (negative).");
int ix1,ix2;
if(locateMultivirtualFunctor2D(ix1,ix2,arg1,arg2)) return callBacks[ix1][ix2];
return shared_ptr<Executor>();
=== modified file 'lib/serialization/ObjectIO.hpp'
--- lib/serialization/ObjectIO.hpp 2011-12-19 17:02:15 +0000
+++ lib/serialization/ObjectIO.hpp 2014-05-23 13:03:50 +0000
@@ -52,9 +52,9 @@
template<class T>
static void save(const string fileName, const string& objectTag, T& object){
boost::iostreams::filtering_ostream out;
- if(boost::algorithm::ends_with(fileName,".bz2")) out.push(iostreams::bzip2_compressor());
- if(boost::algorithm::ends_with(fileName,".gz")) out.push(iostreams::gzip_compressor());
- out.push(iostreams::file_sink(fileName));
+ if(boost::algorithm::ends_with(fileName,".bz2")) out.push(boost::iostreams::bzip2_compressor());
+ if(boost::algorithm::ends_with(fileName,".gz")) out.push(boost::iostreams::gzip_compressor());
+ out.push(boost::iostreams::file_sink(fileName));
if(!out.good()) throw std::runtime_error("Error opening file "+fileName+" for writing.");
if(isXmlFilename(fileName)) save<T,boost::archive::xml_oarchive>(out,objectTag,object);
else save<T,boost::archive::binary_oarchive>(out,objectTag,object);
@@ -63,9 +63,9 @@
template<class T>
static void load(const string& fileName, const string& objectTag, T& object){
boost::iostreams::filtering_istream in;
- if(boost::algorithm::ends_with(fileName,".bz2")) in.push(iostreams::bzip2_decompressor());
- if(boost::algorithm::ends_with(fileName,".gz")) in.push(iostreams::gzip_decompressor());
- in.push(iostreams::file_source(fileName));
+ if(boost::algorithm::ends_with(fileName,".bz2")) in.push(boost::iostreams::bzip2_decompressor());
+ if(boost::algorithm::ends_with(fileName,".gz")) in.push(boost::iostreams::gzip_decompressor());
+ in.push(boost::iostreams::file_source(fileName));
if(!in.good()) throw std::runtime_error("Error opening file "+fileName+" for reading.");
if(isXmlFilename(fileName)) load<T,boost::archive::xml_iarchive>(in,objectTag,object);
else load<T,boost::archive::binary_iarchive>(in,objectTag,object);
=== modified file 'lib/serialization/Serializable.cpp'
--- lib/serialization/Serializable.cpp 2010-08-24 12:54:14 +0000
+++ lib/serialization/Serializable.cpp 2014-05-23 13:03:50 +0000
@@ -14,7 +14,7 @@
void Serializable::pyRegisterClass(boost::python::object _scope) {
checkPyClassRegistersItself("Serializable");
boost::python::scope thisScope(_scope);
- python::class_<Serializable, shared_ptr<Serializable>, noncopyable >("Serializable")
+ boost::python::class_<Serializable, shared_ptr<Serializable>, boost::noncopyable >("Serializable")
.def("__str__",&Serializable::pyStr).def("__repr__",&Serializable::pyStr)
.def("dict",&Serializable::pyDict,"Return dictionary of attributes.")
.def("updateAttrs",&Serializable::pyUpdateAttrs,"Update object attributes from given dictionary")
@@ -25,7 +25,7 @@
.add_property("__getstate_manages_dict__",&Serializable::getClassName,"just define the attr, return some bogus data")
#endif
// constructor with dictionary of attributes
- .def("__init__",python::raw_constructor(Serializable_ctor_kwAttrs<Serializable>))
+ .def("__init__",boost::python::raw_constructor(Serializable_ctor_kwAttrs<Serializable>))
// comparison operators
.def(boost::python::self == boost::python::self)
.def(boost::python::self != boost::python::self)
@@ -36,26 +36,13 @@
if(getClassName()!=thisClassName) throw std::logic_error(("Class "+getClassName()+" does not register with YADE_CLASS_BASE_DOC_ATTR*, would not be accessible from python.").c_str());
}
-#if 1
- void Serializable::pyUpdateAttrs(const python::dict& d){
- python::list l=d.items(); size_t ll=python::len(l); if(ll==0) return;
- for(size_t i=0; i<ll; i++){
- python::tuple t=python::extract<python::tuple>(l[i]);
- string key=python::extract<string>(t[0]);
- pySetAttr(key,t[1]);
- }
- callPostLoad();
- }
-#else
- void Serializable::pyUpdateAttrs(const shared_ptr<Serializable>& instance, const python::dict& d){
- python::list l=d.items(); size_t ll=python::len(l); if(ll==0) return;
- python::object self(instance);
- for(size_t i=0; i<ll; i++){
- python::tuple t=python::extract<python::tuple>(l[i]);
- string key=python::extract<string>(t[0]);
- self.attr(key.c_str())=t[1];
- }
- }
-#endif
-
-
+
+void Serializable::pyUpdateAttrs(const boost::python::dict& d){
+ boost::python::list l=d.items(); size_t ll=boost::python::len(l); if(ll==0) return;
+ for(size_t i=0; i<ll; i++){
+ boost::python::tuple t=boost::python::extract<boost::python::tuple>(l[i]);
+ string key=boost::python::extract<string>(t[0]);
+ pySetAttr(key,t[1]);
+ }
+ callPostLoad();
+}
=== modified file 'lib/serialization/Serializable.hpp'
--- lib/serialization/Serializable.hpp 2014-04-01 13:18:38 +0000
+++ lib/serialization/Serializable.hpp 2014-05-23 13:03:50 +0000
@@ -36,10 +36,7 @@
#include<yade/lib/base/Math.hpp>
-using namespace boost;
using namespace std;
-
-
// empty functions for ADL
//namespace{
template<typename T> void preLoad(T&){}; template<typename T> void postLoad(T& obj){ /* cerr<<"Generic no-op postLoad("<<typeid(T).name()<<"&) called for "<<obj.getClassName()<<std::endl; */ }
@@ -185,7 +182,7 @@
_REGISTER_ATTRIBUTES_DEPREC(thisClass,baseClass,attrs,deprec) \
REGISTER_CLASS_AND_BASE(thisClass,baseClass) \
/* accessors for deprecated attributes, with warnings */ BOOST_PP_SEQ_FOR_EACH(_ACCESS_DEPREC,thisClass,deprec) \
- /* python class registration */ virtual void pyRegisterClass(python::object _scope) { checkPyClassRegistersItself(#thisClass); boost::python::scope thisScope(_scope); YADE_SET_DOCSTRING_OPTS; boost::python::class_<thisClass,shared_ptr<thisClass>,boost::python::bases<baseClass>,boost::noncopyable> _classObj(#thisClass,docString); _classObj.def("__init__",python::raw_constructor(Serializable_ctor_kwAttrs<thisClass>)); BOOST_PP_SEQ_FOR_EACH(_PYATTR_DEF,thisClass,attrs); (void) _classObj BOOST_PP_SEQ_FOR_EACH(_PYATTR_DEPREC_DEF,thisClass,deprec); (void) _classObj extras ; }
+ /* python class registration */ virtual void pyRegisterClass(boost::python::object _scope) { checkPyClassRegistersItself(#thisClass); boost::python::scope thisScope(_scope); YADE_SET_DOCSTRING_OPTS; boost::python::class_<thisClass,shared_ptr<thisClass>,boost::python::bases<baseClass>,boost::noncopyable> _classObj(#thisClass,docString); _classObj.def("__init__",boost::python::raw_constructor(Serializable_ctor_kwAttrs<thisClass>)); BOOST_PP_SEQ_FOR_EACH(_PYATTR_DEF,thisClass,attrs); (void) _classObj BOOST_PP_SEQ_FOR_EACH(_PYATTR_DEPREC_DEF,thisClass,deprec); (void) _classObj extras ; }
// use later: void must_use_both_YADE_CLASS_BASE_DOC_ATTRS_and_YADE_PLUGIN();
// #define YADE_CLASS_BASE_DOC_ATTRS_PY(thisClass,baseClass,docString,attrs,extras) YADE_CLASS_BASE_DOC_ATTRS_DEPREC_PY(thisClass,baseClass,docString,attrs,,extras)
@@ -208,8 +205,8 @@
#define _STATCLASS_PY_REGISTER_CLASS(thisClass,baseClass,docString,attrs)\
- virtual void pyRegisterClass(python::object _scope) { checkPyClassRegistersItself(#thisClass); initSetStaticAttributesValue(); boost::python::scope thisScope(_scope); YADE_SET_DOCSTRING_OPTS; \
- boost::python::class_<thisClass,shared_ptr<thisClass>,boost::python::bases<baseClass>,boost::noncopyable> _classObj(#thisClass,docString "\n\n" BOOST_PP_SEQ_FOR_EACH(_STATATTR_MAKE_DOC,thisClass,attrs) ); _classObj.def("__init__",python::raw_constructor(Serializable_ctor_kwAttrs<thisClass>)); \
+ virtual void pyRegisterClass(boost::python::object _scope) { checkPyClassRegistersItself(#thisClass); initSetStaticAttributesValue(); boost::python::scope thisScope(_scope); YADE_SET_DOCSTRING_OPTS; \
+ boost::python::class_<thisClass,shared_ptr<thisClass>,boost::python::bases<baseClass>,boost::noncopyable> _classObj(#thisClass,docString "\n\n" BOOST_PP_SEQ_FOR_EACH(_STATATTR_MAKE_DOC,thisClass,attrs) ); _classObj.def("__init__",boost::python::raw_constructor(Serializable_ctor_kwAttrs<thisClass>)); \
BOOST_PP_SEQ_FOR_EACH(_STATATTR_PY,thisClass,attrs); \
}
@@ -217,7 +214,7 @@
_REGISTER_ATTRIBUTES_DEPREC(thisClass,baseClass,attrs,deprec) \
REGISTER_CLASS_AND_BASE(pyClassName,baseClass) \
/* accessors for deprecated attributes, with warnings */ BOOST_PP_SEQ_FOR_EACH(_ACCESS_DEPREC,thisClass,deprec) \
- /* python class registration */ virtual void pyRegisterClass(python::object _scope) { checkPyClassRegistersItself(#pyClassName); boost::python::scope thisScope(_scope); YADE_SET_DOCSTRING_OPTS; boost::python::class_<thisClass,shared_ptr<thisClass>,boost::python::bases<baseClass>,boost::noncopyable> _classObj(#pyClassName,docString); _classObj.def("__init__",python::raw_constructor(Serializable_ctor_kwAttrs<thisClass>)); BOOST_PP_SEQ_FOR_EACH(_PYATTR_DEF,thisClass,attrs); (void) _classObj BOOST_PP_SEQ_FOR_EACH(_PYATTR_DEPREC_DEF,thisClass,deprec); (void) _classObj extras ; }
+ /* python class registration */ virtual void pyRegisterClass(boost::python::object _scope) { checkPyClassRegistersItself(#pyClassName); boost::python::scope thisScope(_scope); YADE_SET_DOCSTRING_OPTS; boost::python::class_<thisClass,shared_ptr<thisClass>,boost::python::bases<baseClass>,boost::noncopyable> _classObj(#pyClassName,docString); _classObj.def("__init__",boost::python::raw_constructor(Serializable_ctor_kwAttrs<thisClass>)); BOOST_PP_SEQ_FOR_EACH(_PYATTR_DEF,thisClass,attrs); (void) _classObj BOOST_PP_SEQ_FOR_EACH(_PYATTR_DEPREC_DEF,thisClass,deprec); (void) _classObj extras ; }
/********************** USER MACROS START HERE ********************/
@@ -293,7 +290,7 @@
virtual void pyHandleCustomCtorArgs(boost::python::tuple& args, boost::python::dict& kw){ return; }
//! string representation of this object
- std::string pyStr() { return "<"+getClassName()+" instance at "+lexical_cast<string>(this)+">"; }
+ std::string pyStr() { return "<"+getClassName()+" instance at "+boost::lexical_cast<string>(this)+">"; }
REGISTER_CLASS_NAME(Serializable);
REGISTER_BASE_CLASS_NAME(Factorable);
@@ -302,11 +299,11 @@
// helper functions
template <typename T>
-shared_ptr<T> Serializable_ctor_kwAttrs(python::tuple& t, python::dict& d){
+shared_ptr<T> Serializable_ctor_kwAttrs(boost::python::tuple& t, boost::python::dict& d){
shared_ptr<T> instance;
instance=shared_ptr<T>(new T);
instance->pyHandleCustomCtorArgs(t,d); // can change t and d in-place
- if(python::len(t)>0) throw runtime_error("Zero (not "+lexical_cast<string>(python::len(t))+") non-keyword constructor arguments required [in Serializable_ctor_kwAttrs; Serializable::pyHandleCustomCtorArgs might had changed it after your call].");
- if(python::len(d)>0){ instance->pyUpdateAttrs(d); instance->callPostLoad(); }
+ if(boost::python::len(t)>0) throw runtime_error("Zero (not "+boost::lexical_cast<string>(boost::python::len(t))+") non-keyword constructor arguments required [in Serializable_ctor_kwAttrs; Serializable::pyHandleCustomCtorArgs might had changed it after your call].");
+ if(boost::python::len(d)>0){ instance->pyUpdateAttrs(d); instance->callPostLoad(); }
return instance;
}
=== modified file 'lib/smoothing/WeightedAverage2d.hpp'
--- lib/smoothing/WeightedAverage2d.hpp 2013-03-07 18:28:16 +0000
+++ lib/smoothing/WeightedAverage2d.hpp 2014-05-23 13:03:50 +0000
@@ -16,12 +16,18 @@
#include<boost/version.hpp>
#include<boost/math/distributions/normal.hpp>
+#ifndef __GXX_EXPERIMENTAL_CXX0X__
+# include<boost/shared_ptr.hpp>
+ using boost::shared_ptr;
+#else
+# include<memory>
+ using std::shared_ptr;
+#endif
#ifndef FOREACH
#define FOREACH BOOST_FOREACH
#endif
using namespace std;
-using namespace boost;
#include<yade/lib/base/Math.hpp>
@@ -46,7 +52,7 @@
Vector2i xy2cell(Vector2r xy, bool* inGrid=NULL) const {
Vector2i ret((int)(floor((xy[0]-lo[0])/cellSizes[0])),(int)(floor((xy[1]-lo[1])/cellSizes[1])));
if(ret[0]<0 || ret[0]>=nCells[0] || ret[1]<0 || ret[1]>=nCells[1]){
- if(inGrid) *inGrid=false; else throw std::invalid_argument("Cell coordinates outside grid (xy="+lexical_cast<string>(xy[0])+","+lexical_cast<string>(xy[1])+", computed cell coordinates "+lexical_cast<string>(ret[0])+","+lexical_cast<string>(ret[1])+").");
+ if(inGrid) *inGrid=false; else throw std::invalid_argument("Cell coordinates outside grid (xy="+boost::lexical_cast<string>(xy[0])+","+boost::lexical_cast<string>(xy[1])+", computed cell coordinates "+boost::lexical_cast<string>(ret[0])+","+boost::lexical_cast<string>(ret[1])+").");
} else {if(inGrid) *inGrid=true;}
return ret;
}
@@ -170,13 +176,13 @@
* */
class pyGaussAverage{
//struct Scalar2d{Vector2r pos; Real val;};
- Vector2r tuple2vec2r(const python::tuple& t){return Vector2r(python::extract<Real>(t[0])(),python::extract<Real>(t[1])());}
- Vector2i tuple2vec2i(const python::tuple& t){return Vector2i(python::extract<int>(t[0])(),python::extract<int>(t[1])());}
+ Vector2r tuple2vec2r(const boost::python::tuple& t){return Vector2r(boost::python::extract<Real>(t[0])(),boost::python::extract<Real>(t[1])());}
+ Vector2i tuple2vec2i(const boost::python::tuple& t){return Vector2i(boost::python::extract<int>(t[0])(),boost::python::extract<int>(t[1])());}
shared_ptr<SGDA_Scalar2d> sgda;
struct Poly2d{vector<Vector2r> vertices; bool inclusive;};
vector<Poly2d> clips;
public:
- pyGaussAverage(python::tuple lo, python::tuple hi, python::tuple nCells, Real stDev, Real relThreshold=3.){
+ pyGaussAverage(boost::python::tuple lo, boost::python::tuple hi, boost::python::tuple nCells, Real stDev, Real relThreshold=3.){
shared_ptr<GridContainer<Scalar2d> > g(new GridContainer<Scalar2d>(tuple2vec2r(lo),tuple2vec2r(hi),tuple2vec2i(nCells)));
sgda=shared_ptr<SGDA_Scalar2d>(new SGDA_Scalar2d(g,stDev));
sgda->relThreshold=relThreshold;
@@ -189,36 +195,36 @@
}
return false;
}
- bool addPt(Real val, python::tuple pos){Scalar2d d; d.pos=tuple2vec2r(pos); if(ptIsClipped(d.pos)) return false; d.val=val; sgda->grid->add(d,d.pos); return true; }
+ bool addPt(Real val, boost::python::tuple pos){Scalar2d d; d.pos=tuple2vec2r(pos); if(ptIsClipped(d.pos)) return false; d.val=val; sgda->grid->add(d,d.pos); return true; }
Real avg(Vector2r pt){ if(ptIsClipped(pt)) return std::numeric_limits<Real>::quiet_NaN(); return sgda->computeAverage(pt);}
Real avgPerUnitArea(Vector2r pt){ if(ptIsClipped(pt)) return std::numeric_limits<Real>::quiet_NaN(); return sgda->computeAvgPerUnitArea(pt); }
Real stDev_get(){return sgda->stDev;} void stDev_set(Real s){sgda->stDev=s;}
Real relThreshold_get(){return sgda->relThreshold;} void relThreshold_set(Real rt){sgda->relThreshold=rt;}
- python::tuple aabb_get(){return python::make_tuple(sgda->grid->getLo(),sgda->grid->getHi());}
- python::list clips_get(){
- python::list ret;
+ boost::python::tuple aabb_get(){return boost::python::make_tuple(sgda->grid->getLo(),sgda->grid->getHi());}
+ boost::python::list clips_get(){
+ boost::python::list ret;
FOREACH(const Poly2d& poly, clips){
- python::list vertices;
- FOREACH(const Vector2r& v, poly.vertices) vertices.append(python::make_tuple(v[0],v[1]));
- ret.append(python::make_tuple(vertices,poly.inclusive));
+ boost::python::list vertices;
+ FOREACH(const Vector2r& v, poly.vertices) vertices.append(boost::python::make_tuple(v[0],v[1]));
+ ret.append(boost::python::make_tuple(vertices,poly.inclusive));
}
return ret;
}
- void clips_set(python::list l){
+ void clips_set(boost::python::list l){
/* [ ( [(x1,y1),(x2,y2),…], true), … ] */
clips.clear();
- for(int i=0; i<python::len(l); i++){
- python::tuple polyDesc=python::extract<python::tuple>(l[i])();
- python::list coords=python::extract<python::list>(polyDesc[0]);
- Poly2d poly; poly.inclusive=python::extract<bool>(polyDesc[1]);
- for(int j=0; j<python::len(coords); j++){
- poly.vertices.push_back(tuple2vec2r(python::extract<python::tuple>(coords[j])));
+ for(int i=0; i<boost::python::len(l); i++){
+ boost::python::tuple polyDesc=boost::python::extract<boost::python::tuple>(l[i])();
+ boost::python::list coords=boost::python::extract<boost::python::list>(polyDesc[0]);
+ Poly2d poly; poly.inclusive=boost::python::extract<bool>(polyDesc[1]);
+ for(int j=0; j<boost::python::len(coords); j++){
+ poly.vertices.push_back(tuple2vec2r(boost::python::extract<boost::python::tuple>(coords[j])));
}
clips.push_back(poly);
}
}
- python::tuple data_get(){
- python::list x,y,val;
+ boost::python::tuple data_get(){
+ boost::python::list x,y,val;
const Vector2i& dim=sgda->grid->getSize();
for(int i=0; i<dim[0]; i++){
for(int j=0; j<dim[1]; j++){
@@ -227,7 +233,7 @@
}
}
}
- return python::make_tuple(x,y,val);
+ return boost::python::make_tuple(x,y,val);
}
Vector2i nCells_get(){ return sgda->grid->getSize(); }
int cellNum(const Vector2i& cell){ return sgda->grid->grid[cell[0]][cell[1]].size(); }
=== modified file 'lib/triangulation/Network.ipp'
--- lib/triangulation/Network.ipp 2014-05-23 14:03:16 +0000
+++ lib/triangulation/Network.ipp 2014-05-23 14:06:21 +0000
@@ -16,7 +16,6 @@
using namespace std;
-// using namespace boost;
namespace CGT {
// template<class Tesselation> const double Network<Tesselation>::FAR = 50000;
=== modified file 'pkg/common/Collider.cpp'
--- pkg/common/Collider.cpp 2012-11-08 13:03:30 +0000
+++ pkg/common/Collider.cpp 2014-05-23 13:05:19 +0000
@@ -26,19 +26,19 @@
;
}
-void Collider::pyHandleCustomCtorArgs(python::tuple& t, python::dict& d){
- if(python::len(t)==0) return; // nothing to do
- if(python::len(t)!=1) throw invalid_argument(("Collider optionally takes exactly one list of BoundFunctor's as non-keyword argument for constructor ("+lexical_cast<string>(python::len(t))+" non-keyword ards given instead)").c_str());
+void Collider::pyHandleCustomCtorArgs(boost::python::tuple& t, boost::python::dict& d){
+ if(boost::python::len(t)==0) return; // nothing to do
+ if(boost::python::len(t)!=1) throw invalid_argument(("Collider optionally takes exactly one list of BoundFunctor's as non-keyword argument for constructor ("+boost::lexical_cast<string>(boost::python::len(t))+" non-keyword ards given instead)").c_str());
typedef std::vector<shared_ptr<BoundFunctor> > vecBound;
- vecBound vb=python::extract<vecBound>(t[0])();
+ vecBound vb=boost::python::extract<vecBound>(t[0])();
FOREACH(shared_ptr<BoundFunctor> bf, vb) this->boundDispatcher->add(bf);
- t=python::tuple(); // empty the args
+ t=boost::python::tuple(); // empty the args
}
void Collider::findBoundDispatcherInEnginesIfNoFunctorsAndWarn(){
if(boundDispatcher->functors.size()>0) return;
shared_ptr<BoundDispatcher> bd;
- FOREACH(shared_ptr<Engine>& e, scene->engines){ bd=dynamic_pointer_cast<BoundDispatcher>(e); if(bd) break; }
+ FOREACH(shared_ptr<Engine>& e, scene->engines){ bd=boost::dynamic_pointer_cast<BoundDispatcher>(e); if(bd) break; }
if(!bd) return;
LOG_WARN("Collider.boundDispatcher had no functors defined, while there was a BoundDispatcher found in O.engines. Since version 0.60 (r2396), Collider has boundDispatcher integrated in itself; separate BoundDispatcher should not be used anymore. For now, I will fix it for you, but change your script! Where it reads e.g.\n\n\tO.engines=[...,\n\t\tBoundDispatcher([Bo1_Sphere_Aabb(),Bo1_Facet_Aabb()]),\n\t\t"<<getClassName()<<"(),\n\t\t...\n\t]\n\nit should become\n\n\tO.engines=[...,\n\t\t"<<getClassName()<<"([Bo1_Sphere_Aabb(),Bo1_Facet_Aabb()]),\n\t\t...\n\t]\n\ninstead.")
boundDispatcher=bd;
=== modified file 'pkg/common/Collider.hpp'
--- pkg/common/Collider.hpp 2012-11-08 13:03:30 +0000
+++ pkg/common/Collider.hpp 2014-05-23 13:05:19 +0000
@@ -32,7 +32,7 @@
virtual void invalidatePersistentData(){}
// ctor with functors for the integrated BoundDispatcher
- virtual void pyHandleCustomCtorArgs(python::tuple& t, python::dict& d);
+ virtual void pyHandleCustomCtorArgs(boost::python::tuple& t, boost::python::dict& d);
// backwards-compatility func, can be removed later
void findBoundDispatcherInEnginesIfNoFunctorsAndWarn();
@@ -48,4 +48,4 @@
);
};
-REGISTER_SERIALIZABLE(Collider);
\ No newline at end of file
+REGISTER_SERIALIZABLE(Collider);
=== modified file 'pkg/common/Cylinder.hpp'
--- pkg/common/Cylinder.hpp 2014-05-06 15:32:52 +0000
+++ pkg/common/Cylinder.hpp 2014-05-23 13:05:19 +0000
@@ -91,7 +91,7 @@
/*py*/
// .def_readwrite("chains",&ChainedState::chains,"documentation")
.def_readwrite("currentChain",&ChainedState::currentChain,"Current active chain (where newly created chained bodies will be appended).")
- .def("addToChain",&ChainedState::addToChain,(python::arg("bodyId")),"Add body to current active chain")
+ .def("addToChain",&ChainedState::addToChain,(boost::python::arg("bodyId")),"Add body to current active chain")
);
REGISTER_CLASS_INDEX(ChainedState,State);
};
=== modified file 'pkg/common/Facet.cpp'
--- pkg/common/Facet.cpp 2013-09-08 11:12:42 +0000
+++ pkg/common/Facet.cpp 2014-05-23 13:05:19 +0000
@@ -19,7 +19,7 @@
// if this fails, it means someone did vertices push_back, but they are resized to 3 at Facet initialization already
// in the future, a fixed-size array should be used instead of vector<Vector3r> for vertices
// this is prevented by yade::serialization now IIRC
- if(vertices.size()!=3){ throw runtime_error(("Facet must have exactly 3 vertices (not "+lexical_cast<string>(vertices.size())+")").c_str()); }
+ if(vertices.size()!=3){ throw runtime_error(("Facet must have exactly 3 vertices (not "+boost::lexical_cast<string>(vertices.size())+")").c_str()); }
if(isnan(vertices[0][0])) return; // not initialized, nothing to do
Vector3r e[3] = {vertices[1]-vertices[0] ,vertices[2]-vertices[1] ,vertices[0]-vertices[2]};
#define CHECK_EDGE(i) if(e[i].squaredNorm()==0){LOG_FATAL("Facet has coincident vertices "<<i<<" ("<<vertices[i]<<") and "<<(i+1)%3<<" ("<<vertices[(i+1)%3]<<")!");}
=== modified file 'pkg/common/Gl1_NormPhys.cpp'
--- pkg/common/Gl1_NormPhys.cpp 2013-08-23 15:21:20 +0000
+++ pkg/common/Gl1_NormPhys.cpp 2014-05-22 15:26:55 +0000
@@ -67,7 +67,7 @@
Real dist=relPos.norm();
#else
// get endpoints from geom
- // max(r,0) handles r<0 which is the case for "radius" of the facet in Dem3DofGeom_FacetSphere
+ // max(r,0) handles r<0 which is the case for "radius" of the facet
Vector3r cp=scene->isPeriodic? scene->cell->wrapShearedPt(geom->contactPoint) : geom->contactPoint;
Vector3r p1=cp-max(geom->refR1,(Real)0.)*geom->normal;
Vector3r p2=cp+max(geom->refR2,(Real)0.)*geom->normal;
=== modified file 'pkg/common/GravityEngines.cpp'
--- pkg/common/GravityEngines.cpp 2013-03-06 17:30:45 +0000
+++ pkg/common/GravityEngines.cpp 2014-05-23 13:05:19 +0000
@@ -66,7 +66,7 @@
boost::cmatch matches;
if(!boost::regex_match(buf,matches,re)) throw std::runtime_error(("HdapsGravityEngine: error parsing data from "+name).c_str());
//cerr<<matches[1]<<","<<matches[2]<<endl;
- return Vector2i(lexical_cast<int>(matches[1]),lexical_cast<int>(matches[2]));
+ return Vector2i(boost::lexical_cast<int>(matches[1]),boost::lexical_cast<int>(matches[2]));
}
=== modified file 'pkg/common/Grid.hpp'
--- pkg/common/Grid.hpp 2013-06-03 15:28:41 +0000
+++ pkg/common/Grid.hpp 2014-05-23 13:05:19 +0000
@@ -63,7 +63,7 @@
/*ctor*/
createIndex();,
/*py*/
- .def("addConnection",&GridNode::addConnection,(python::arg("Body")),"Add a GridConnection to the GridNode.")
+ .def("addConnection",&GridNode::addConnection,(boost::python::arg("Body")),"Add a GridConnection to the GridNode.")
);
REGISTER_CLASS_INDEX(GridNode,Sphere);
};
=== modified file 'pkg/common/InsertionSortCollider.cpp'
--- pkg/common/InsertionSortCollider.cpp 2014-05-06 15:32:52 +0000
+++ pkg/common/InsertionSortCollider.cpp 2014-05-23 13:05:19 +0000
@@ -109,8 +109,9 @@
}
///In the second sort, the chunks are connected consistently.
- ///If sorting requires to move a bound past half-chunk, the algorithm is not thread safe, if it happens we error out.
- ///Better than computing with messed up interactions
+ ///If sorting requires to move a bound past half-chunk, the algorithm is not thread safe,
+ /// if it happens we roll-back and run the 1-thread sort + send warning
+ bool parallelFailed=false;
#pragma omp parallel for schedule(dynamic,1) num_threads(ompThreads>0 ? min(ompThreads,omp_get_max_threads()) : omp_get_max_threads())
for (unsigned k=1; k<nChunks;k++) {
@@ -130,12 +131,20 @@
j--;
}
v[j+1]=viInit;
- if (j<=long(chunks[k]-chunkSize*0.5)) LOG_ERROR("parallel sort not guaranteed to succeed; in chunk "<<k<<" of "<<nChunks<< ", bound descending past half-chunk. Consider turning ompThreads=1 for thread safety.");
+ if (j<=long(chunks[k]-chunkSize*0.5)) {
+ LOG_WARN("parallel sort not guaranteed to succeed; in chunk "<<k<<" of "<<nChunks<< ", bound descending past half-chunk. Parallel colliding aborted, starting again in single thread. Consider turning collider.ompThreads=1 for not wasting CPU time.");
+ parallelFailed=true;}
}
- if (i>=long(chunks[k]+chunkSize*0.5)) LOG_ERROR("parallel sort not guaranteed to succeed; in chunk "<<k+1<<" of "<<nChunks<< ", bound advancing past half-chunk. Consider turning ompThreads=1 for thread safety.")
+ if (i>=long(chunks[k]+chunkSize*0.5)) {
+ LOG_ERROR("parallel sort not guaranteed to succeed; in chunk "<<k+1<<" of "<<nChunks<< ", bound advancing past half-chunk. Consider turning collider.ompThreads=1 for not wasting CPU time.");
+ parallelFailed=true;}
}
/// Check again, just to be sure...
- for (unsigned k=1; k<nChunks;k++) if (v[chunks[k]]<v[chunks[k]-1]) LOG_ERROR("parallel sort failed, consider turning ompThreads=1");
+ for (unsigned k=1; k<nChunks;k++) if (v[chunks[k]]<v[chunks[k]-1]) {
+ LOG_ERROR("Parallel colliding failed, starting again in single thread. Consider turning collider.ompThreads=1 for not wasting CPU time.");
+ parallelFailed=true;}
+
+ if (parallelFailed) return insertionSort(v,interactions, scene, doCollide);
/// Now insert interactions sequentially
for (int n=0;n<ompThreads;n++) for (size_t k=0, kend=newInteractions[n].size();k<kend;k++) if (!interactions->found(newInteractions[n][k].first,newInteractions[n][k].second)) interactions->insert(shared_ptr<Interaction>(new Interaction(newInteractions[n][k].first,newInteractions[n][k].second)));
@@ -265,7 +274,7 @@
if(verletDist>0){
// get NewtonIntegrator, to ask for the maximum velocity value
if(!newton){
- FOREACH(shared_ptr<Engine>& e, scene->engines){ newton=dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) break; }
+ FOREACH(shared_ptr<Engine>& e, scene->engines){ newton=boost::dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) break; }
if(!newton){ throw runtime_error("InsertionSortCollider.verletDist>0, but unable to locate NewtonIntegrator within O.engines."); }
}
}
@@ -537,20 +546,20 @@
return true;
}
-python::tuple InsertionSortCollider::dumpBounds(){
- python::list bl[3]; // 3 bound lists, inserted into the tuple at the end
+boost::python::tuple InsertionSortCollider::dumpBounds(){
+ boost::python::list bl[3]; // 3 bound lists, inserted into the tuple at the end
for(int axis=0; axis<3; axis++){
VecBounds& V=BB[axis];
if(periodic){
for(long i=0; i<V.size; i++){
long ii=V.norm(i); // start from the period boundary
- bl[axis].append(python::make_tuple(V[ii].coord,(V[ii].flags.isMin?-1:1)*V[ii].id,V[ii].period));
+ bl[axis].append(boost::python::make_tuple(V[ii].coord,(V[ii].flags.isMin?-1:1)*V[ii].id,V[ii].period));
}
} else {
for(long i=0; i<V.size; i++){
- bl[axis].append(python::make_tuple(V[i].coord,(V[i].flags.isMin?-1:1)*V[i].id));
+ bl[axis].append(boost::python::make_tuple(V[i].coord,(V[i].flags.isMin?-1:1)*V[i].id));
}
}
}
- return python::make_tuple(bl[0],bl[1],bl[2]);
+ return boost::python::make_tuple(bl[0],bl[1],bl[2]);
}
=== modified file 'pkg/common/InsertionSortCollider.hpp'
--- pkg/common/InsertionSortCollider.hpp 2014-05-06 15:32:52 +0000
+++ pkg/common/InsertionSortCollider.hpp 2014-05-23 13:05:19 +0000
@@ -147,7 +147,7 @@
bool periodic;
// return python representation of the BB struct, as ([...],[...],[...]).
- python::tuple dumpBounds();
+ boost::python::tuple dumpBounds();
/*! sorting routine; insertion sort is very fast for strongly pre-sorted lists, which is our case
http://en.wikipedia.org/wiki/Insertion_sort has the algorithm and other details
=== modified file 'pkg/common/InteractionLoop.cpp'
--- pkg/common/InteractionLoop.cpp 2014-04-16 10:30:23 +0000
+++ pkg/common/InteractionLoop.cpp 2014-05-23 13:05:19 +0000
@@ -3,20 +3,20 @@
YADE_PLUGIN((InteractionLoop));
CREATE_LOGGER(InteractionLoop);
-void InteractionLoop::pyHandleCustomCtorArgs(python::tuple& t, python::dict& d){
- if(python::len(t)==0) return; // nothing to do
- if(python::len(t)!=3) throw invalid_argument("Exactly 3 lists of functors must be given");
+void InteractionLoop::pyHandleCustomCtorArgs(boost::python::tuple& t, boost::python::dict& d){
+ if(boost::python::len(t)==0) return; // nothing to do
+ if(boost::python::len(t)!=3) throw invalid_argument("Exactly 3 lists of functors must be given");
// parse custom arguments (3 lists) and do in-place modification of args
typedef std::vector<shared_ptr<IGeomFunctor> > vecGeom;
typedef std::vector<shared_ptr<IPhysFunctor> > vecPhys;
typedef std::vector<shared_ptr<LawFunctor> > vecLaw;
- vecGeom vg=python::extract<vecGeom>(t[0])();
- vecPhys vp=python::extract<vecPhys>(t[1])();
- vecLaw vl=python::extract<vecLaw>(t[2])();
+ vecGeom vg=boost::python::extract<vecGeom>(t[0])();
+ vecPhys vp=boost::python::extract<vecPhys>(t[1])();
+ vecLaw vl=boost::python::extract<vecLaw>(t[2])();
FOREACH(shared_ptr<IGeomFunctor> gf, vg) this->geomDispatcher->add(gf);
FOREACH(shared_ptr<IPhysFunctor> pf, vp) this->physDispatcher->add(pf);
FOREACH(shared_ptr<LawFunctor> cf, vl) this->lawDispatcher->add(cf);
- t=python::tuple(); // empty the args; not sure if this is OK, as there is some refcounting in raw_constructor code
+ t=boost::python::tuple(); // empty the args; not sure if this is OK, as there is some refcounting in raw_constructor code
}
=== modified file 'pkg/common/InteractionLoop.hpp'
--- pkg/common/InteractionLoop.hpp 2013-04-23 14:07:34 +0000
+++ pkg/common/InteractionLoop.hpp 2014-05-23 13:05:19 +0000
@@ -24,7 +24,7 @@
void eraseAfterLoop(Body::id_t id1,Body::id_t id2){ eraseAfterLoopIds.push_back(idPair(id1,id2)); }
#endif
public:
- virtual void pyHandleCustomCtorArgs(python::tuple& t, python::dict& d);
+ virtual void pyHandleCustomCtorArgs(boost::python::tuple& t, boost::python::dict& d);
virtual void action();
YADE_CLASS_BASE_DOC_ATTRS_CTOR_PY(InteractionLoop,GlobalEngine,"Unified dispatcher for handling interaction loop at every step, for parallel performance reasons.\n\n.. admonition:: Special constructor\n\n\tConstructs from 3 lists of :yref:`Ig2<IGeomFunctor>`, :yref:`Ip2<IPhysFunctor>`, :yref:`Law<LawFunctor>` functors respectively; they will be passed to interal dispatchers, which you might retrieve.",
((shared_ptr<IGeomDispatcher>,geomDispatcher,new IGeomDispatcher,Attr::readonly,":yref:`IGeomDispatcher` object that is used for dispatch."))
=== modified file 'pkg/common/MatchMaker.cpp'
--- pkg/common/MatchMaker.cpp 2010-12-06 20:05:12 +0000
+++ pkg/common/MatchMaker.cpp 2014-05-23 13:03:50 +0000
@@ -14,7 +14,7 @@
if(((int)m[0]==id1 && (int)m[1]==id2) || ((int)m[0]==id2 && (int)m[1]==id1)) return m[2];
}
// no match
- if(fbNeedsValues && (isnan(val1) || isnan(val2))) throw std::invalid_argument("MatchMaker: no match for ("+lexical_cast<string>(id1)+","+lexical_cast<string>(id2)+"), and values required for algo computation '"+algo+"' not specified.");
+ if(fbNeedsValues && (isnan(val1) || isnan(val2))) throw std::invalid_argument("MatchMaker: no match for ("+boost::lexical_cast<string>(id1)+","+boost::lexical_cast<string>(id2)+"), and values required for algo computation '"+algo+"' not specified.");
return computeFallback(val1,val2);
}
=== modified file 'pkg/common/OpenGLRenderer.cpp'
--- pkg/common/OpenGLRenderer.cpp 2014-04-16 19:53:59 +0000
+++ pkg/common/OpenGLRenderer.cpp 2014-05-23 13:05:19 +0000
@@ -55,7 +55,7 @@
// reported http://www.mail-archive.com/yade-users@xxxxxxxxxxxxxxxxxxx/msg01482.html
#if 0
int e=glGetError();
- if(e!=GL_NO_ERROR) throw runtime_error((string("OpenGLRenderer::init returned GL error ")+lexical_cast<string>(e)).c_str());
+ if(e!=GL_NO_ERROR) throw runtime_error((string("OpenGLRenderer::init returned GL error ")+boost::lexical_cast<string>(e)).c_str());
#endif
}
@@ -68,7 +68,7 @@
void OpenGLRenderer::initgl(){
LOG_DEBUG("(re)initializing GL for gldraw methods.\n");
- #define _SETUP_DISPATCHER(names,FunctorType,dispatcher) dispatcher.clearMatrix(); FOREACH(string& s,names) {shared_ptr<FunctorType> f(static_pointer_cast<FunctorType>(ClassFactory::instance().createShared(s))); f->initgl(); dispatcher.add(f);}
+ #define _SETUP_DISPATCHER(names,FunctorType,dispatcher) dispatcher.clearMatrix(); FOREACH(string& s,names) {shared_ptr<FunctorType> f(boost::static_pointer_cast<FunctorType>(ClassFactory::instance().createShared(s))); f->initgl(); dispatcher.add(f);}
// _SETUP_DISPATCHER(stateFunctorNames,GlStateFunctor,stateDispatcher);
_SETUP_DISPATCHER(boundFunctorNames,GlBoundFunctor,boundDispatcher);
_SETUP_DISPATCHER(shapeFunctorNames,GlShapeFunctor,shapeDispatcher);
=== modified file 'pkg/common/OpenGLRenderer.hpp'
--- pkg/common/OpenGLRenderer.hpp 2014-02-16 16:42:06 +0000
+++ pkg/common/OpenGLRenderer.hpp 2014-05-23 13:05:19 +0000
@@ -122,8 +122,8 @@
/*py*/
.def("setRefSe3",&OpenGLRenderer::setBodiesRefSe3,"Make current positions and orientation reference for scaleDisplacements and scaleRotations.")
.def("render",&OpenGLRenderer::pyRender,"Render the scene in the current OpenGL context.")
- .def("hideBody",&OpenGLRenderer::hide,(python::arg("id")),"Hide body from id (see :yref:`OpenGLRenderer::showBody`)")
- .def("showBody",&OpenGLRenderer::show,(python::arg("id")),"Make body visible (see :yref:`OpenGLRenderer::hideBody`)")
+ .def("hideBody",&OpenGLRenderer::hide,(boost::python::arg("id")),"Hide body from id (see :yref:`OpenGLRenderer::showBody`)")
+ .def("showBody",&OpenGLRenderer::show,(boost::python::arg("id")),"Make body visible (see :yref:`OpenGLRenderer::hideBody`)")
);
};
REGISTER_SERIALIZABLE(OpenGLRenderer);
=== modified file 'pkg/common/ParallelEngine.cpp'
--- pkg/common/ParallelEngine.cpp 2013-01-29 19:03:26 +0000
+++ pkg/common/ParallelEngine.cpp 2014-05-23 13:03:50 +0000
@@ -1,6 +1,6 @@
#include"ParallelEngine.hpp"
#include<boost/python.hpp>
-using namespace boost;
+
#ifdef YADE_OPENMP
#include<omp.h>
#endif
@@ -8,7 +8,7 @@
YADE_PLUGIN((ParallelEngine));
//! ParallelEngine's pseudo-ctor (factory), taking nested lists of slave engines (might be moved to real ctor perhaps)
-shared_ptr<ParallelEngine> ParallelEngine_ctor_list(const python::list& slaves){ shared_ptr<ParallelEngine> instance(new ParallelEngine); instance->slaves_set(slaves); return instance; }
+shared_ptr<ParallelEngine> ParallelEngine_ctor_list(const boost::python::list& slaves){ shared_ptr<ParallelEngine> instance(new ParallelEngine); instance->slaves_set(slaves); return instance; }
void ParallelEngine::action(){
// openMP warns if the iteration variable is unsigned...
@@ -29,24 +29,24 @@
}
}
-void ParallelEngine::slaves_set(const python::list& slaves2){
- int len=python::len(slaves2);
+void ParallelEngine::slaves_set(const boost::python::list& slaves2){
+ int len=boost::python::len(slaves2);
slaves.clear();
for(int i=0; i<len; i++){
- python::extract<std::vector<shared_ptr<Engine> > > serialGroup(slaves2[i]);
+ boost::python::extract<std::vector<shared_ptr<Engine> > > serialGroup(slaves2[i]);
if (serialGroup.check()){ slaves.push_back(serialGroup()); continue; }
- python::extract<shared_ptr<Engine> > serialAlone(slaves2[i]);
+ boost::python::extract<shared_ptr<Engine> > serialAlone(slaves2[i]);
if (serialAlone.check()){ vector<shared_ptr<Engine> > aloneWrap; aloneWrap.push_back(serialAlone()); slaves.push_back(aloneWrap); continue; }
PyErr_SetString(PyExc_TypeError,"List elements must be either\n (a) sequences of engines to be executed one after another\n(b) alone engines.");
- python::throw_error_already_set();
+ boost::python::throw_error_already_set();
}
}
-python::list ParallelEngine::slaves_get(){
- python::list ret;
+boost::python::list ParallelEngine::slaves_get(){
+ boost::python::list ret;
FOREACH(vector<shared_ptr<Engine > >& grp, slaves){
- if(grp.size()==1) ret.append(python::object(grp[0]));
- else ret.append(python::object(grp));
+ if(grp.size()==1) ret.append(boost::python::object(grp[0]));
+ else ret.append(boost::python::object(grp));
}
return ret;
}
=== modified file 'pkg/common/ParallelEngine.hpp'
--- pkg/common/ParallelEngine.hpp 2012-10-31 12:31:50 +0000
+++ pkg/common/ParallelEngine.hpp 2014-05-23 13:03:50 +0000
@@ -3,7 +3,7 @@
#include<boost/python.hpp>
class ParallelEngine;
-shared_ptr<ParallelEngine> ParallelEngine_ctor_list(const python::list& slaves);
+shared_ptr<ParallelEngine> ParallelEngine_ctor_list(const boost::python::list& slaves);
class ParallelEngine: public Engine {
public:
@@ -20,7 +20,7 @@
ompThreads=2;
,
/*py*/
- .def("__init__",python::make_constructor(ParallelEngine_ctor_list),"Construct from (possibly nested) list of slaves.")
+ .def("__init__",boost::python::make_constructor(ParallelEngine_ctor_list),"Construct from (possibly nested) list of slaves.")
.add_property("slaves",&ParallelEngine::slaves_get,&ParallelEngine::slaves_set,"List of lists of Engines; each top-level group will be run in parallel with other groups, while Engines inside each group will be run sequentially, in given order.");
);
};
=== modified file 'pkg/common/Recorder.cpp'
--- pkg/common/Recorder.cpp 2010-11-07 11:46:20 +0000
+++ pkg/common/Recorder.cpp 2014-05-23 13:05:19 +0000
@@ -7,7 +7,7 @@
assert(!out.is_open());
std::string fileTemp = file;
- if (addIterNum) fileTemp+="-" + lexical_cast<string>(scene->iter);
+ if (addIterNum) fileTemp+="-" + boost::lexical_cast<string>(scene->iter);
if(fileTemp.empty()) throw ios_base::failure(__FILE__ ": Empty filename.");
out.open(fileTemp.c_str(), truncate ? fstream::trunc : fstream::app);
=== modified file 'pkg/common/ZECollider.cpp'
--- pkg/common/ZECollider.cpp 2013-03-06 17:30:45 +0000
+++ pkg/common/ZECollider.cpp 2014-05-23 13:05:19 +0000
@@ -92,7 +92,7 @@
if(verletDist>0){
// get NewtonIntegrator, to ask for the maximum velocity value
if(!newton){
- FOREACH(shared_ptr<Engine>& e, scene->engines){ newton=dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) break; }
+ FOREACH(shared_ptr<Engine>& e, scene->engines){ newton=boost::dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) break; }
if(!newton){ throw runtime_error("ZECollider.verletDist>0, but unable to locate NewtonIntegrator within O.engines."); }
}
}
=== modified file 'pkg/dem/CapillaryStressRecorder.cpp'
--- pkg/dem/CapillaryStressRecorder.cpp 2013-08-20 11:13:01 +0000
+++ pkg/dem/CapillaryStressRecorder.cpp 2014-05-23 13:05:19 +0000
@@ -141,16 +141,16 @@
SIG_13_cap = sig13_cap/V;
SIG_23_cap = sig23_cap/V;
- out << lexical_cast<string> ( scene->iter ) << " "
- << lexical_cast<string>(SIG_11_cap) << " "
- << lexical_cast<string>(SIG_22_cap) << " "
- << lexical_cast<string>(SIG_33_cap) << " "
- << lexical_cast<string>(SIG_12_cap) << " "
- << lexical_cast<string>(SIG_13_cap)<< " "
- << lexical_cast<string>(SIG_23_cap)<< " "
- << lexical_cast<string>(capillaryPressure) << " "
- << lexical_cast<string>(Sr)<< " "
- << lexical_cast<string>(w)<< " "
+ out << boost::lexical_cast<string> ( scene->iter ) << " "
+ << boost::lexical_cast<string>(SIG_11_cap) << " "
+ << boost::lexical_cast<string>(SIG_22_cap) << " "
+ << boost::lexical_cast<string>(SIG_33_cap) << " "
+ << boost::lexical_cast<string>(SIG_12_cap) << " "
+ << boost::lexical_cast<string>(SIG_13_cap)<< " "
+ << boost::lexical_cast<string>(SIG_23_cap)<< " "
+ << boost::lexical_cast<string>(capillaryPressure) << " "
+ << boost::lexical_cast<string>(Sr)<< " "
+ << boost::lexical_cast<string>(w)<< " "
<< endl;
}
=== modified file 'pkg/dem/CapillaryTriaxialTest.cpp'
--- pkg/dem/CapillaryTriaxialTest.cpp 2013-05-30 20:17:45 +0000
+++ pkg/dem/CapillaryTriaxialTest.cpp 2014-05-23 13:20:43 +0000
@@ -53,12 +53,8 @@
#include <boost/random/variate_generator.hpp>
#include <boost/random/normal_distribution.hpp>
-
-
-using namespace boost;
using namespace std;
-
typedef pair<Vector3r, Real> BasicSphere;
//! generate a list of non-overlapping spheres
string GenerateCloud_water(vector<BasicSphere>& sphere_list, Vector3r lowerCorner, Vector3r upperCorner, long number, Real rad_std_dev, Real porosity);
@@ -180,11 +176,11 @@
//convert the original sphere vector (with clump info) to a BasicSphere vector.
vector<BasicSphere> sphere_list;
- typedef tuple<Vector3r,Real,int> tupleVector3rRealInt;
+ typedef boost::tuple<Vector3r,Real,int> tupleVector3rRealInt;
if(importFilename!=""){
- vector<tuple<Vector3r,Real,int> >sphereListClumpInfo = Shop::loadSpheresFromFile(importFilename,lowerCorner,upperCorner);
+ vector<boost::tuple<Vector3r,Real,int> >sphereListClumpInfo = Shop::loadSpheresFromFile(importFilename,lowerCorner,upperCorner);
FOREACH(tupleVector3rRealInt t, sphereListClumpInfo){
- sphere_list.push_back(make_pair(get<0>(t),get<1>(t)));
+ sphere_list.push_back(make_pair(boost::get<0>(t),boost::get<1>(t)));
};
}
else message+=GenerateCloud_water(sphere_list, lowerCorner, upperCorner, numberOfGrains, Rdispersion, 0.75);
@@ -201,12 +197,12 @@
return true;
// return "Generated a sample inside box of dimensions: ("
-// + lexical_cast<string>(lowerCorner[0]) + ","
-// + lexical_cast<string>(lowerCorner[1]) + ","
-// + lexical_cast<string>(lowerCorner[2]) + ") and ("
-// + lexical_cast<string>(upperCorner[0]) + ","
-// + lexical_cast<string>(upperCorner[1]) + ","
-// + lexical_cast<string>(upperCorner[2]) + ").";
+// + boost::lexical_cast<string>(lowerCorner[0]) + ","
+// + boost::lexical_cast<string>(lowerCorner[1]) + ","
+// + boost::lexical_cast<string>(lowerCorner[2]) + ") and ("
+// + boost::lexical_cast<string>(upperCorner[0]) + ","
+// + boost::lexical_cast<string>(upperCorner[1]) + ","
+// + boost::lexical_cast<string>(upperCorner[2]) + ").";
}
@@ -464,17 +460,17 @@
Rmax = std::max(Rmax,s.second);
break;}
}
- if (t==tries) return "More than " + lexical_cast<string>(tries) +
+ if (t==tries) return "More than " + boost::lexical_cast<string>(tries) +
" tries while generating sphere number " +
- lexical_cast<string>(i+1) + "/" + lexical_cast<string>(number) + ".";
+ boost::lexical_cast<string>(i+1) + "/" + boost::lexical_cast<string>(number) + ".";
}
- return "Generated a sample with " + lexical_cast<string>(number) + "spheres inside box of dimensions: ("
- + lexical_cast<string>(dimensions[0]) + ","
- + lexical_cast<string>(dimensions[1]) + ","
- + lexical_cast<string>(dimensions[2]) + ")."
- + " mean radius=" + lexical_cast<string>(mean_radius) +
- + " Rmin =" + lexical_cast<string>(Rmin) +
- + " Rmax =" + lexical_cast<string>(Rmax) + ".";
+ return "Generated a sample with " + boost::lexical_cast<string>(number) + "spheres inside box of dimensions: ("
+ + boost::lexical_cast<string>(dimensions[0]) + ","
+ + boost::lexical_cast<string>(dimensions[1]) + ","
+ + boost::lexical_cast<string>(dimensions[2]) + ")."
+ + " mean radius=" + boost::lexical_cast<string>(mean_radius) +
+ + " Rmin =" + boost::lexical_cast<string>(Rmin) +
+ + " Rmax =" + boost::lexical_cast<string>(Rmax) + ".";
}
=== modified file 'pkg/dem/CohFrictMat.hpp'
--- pkg/dem/CohFrictMat.hpp 2013-03-06 20:47:43 +0000
+++ pkg/dem/CohFrictMat.hpp 2014-05-19 15:00:11 +0000
@@ -21,11 +21,11 @@
/// Serialization
YADE_CLASS_BASE_DOC_ATTRS_CTOR(CohFrictMat,FrictMat,"",
((bool,isCohesive,true,,""))
- ((Real,alphaKr,2.0,,"Dimensionless coefficient used for the rolling stiffness."))
- ((Real,alphaKtw,2.0,,"Dimensionless coefficient used for the twist stiffness."))
- ((Real,etaRoll,-1.,,"Dimensionless coefficient used to calculate the plastic rolling moment (if negative, plasticity will not be applied)."))
- ((Real,normalCohesion,0,,""))
- ((Real,shearCohesion,0,,""))
+ ((Real,alphaKr,2.0,,"Dimensionless rolling stiffness."))
+ ((Real,alphaKtw,2.0,,"Dimensionless twist stiffness."))
+ ((Real,etaRoll,-1.,,"Dimensionless rolling (aka 'bending') strength. If negative, rolling will be elastic."))
+ ((Real,normalCohesion,0,,"Tensile strength, homogeneous to a pressure"))
+ ((Real,shearCohesion,0,,"Shear strength, homogeneous to a pressure"))
((bool,momentRotationLaw,false,,"Use bending/twisting moment at contact. The contact will have moments only if both bodies have this flag true. See :yref:`CohFrictPhys::cohesionDisablesFriction` for details."))
,
createIndex();
=== modified file 'pkg/dem/CohesiveTriaxialTest.cpp'
--- pkg/dem/CohesiveTriaxialTest.cpp 2013-01-07 15:19:31 +0000
+++ pkg/dem/CohesiveTriaxialTest.cpp 2014-05-23 13:05:19 +0000
@@ -49,9 +49,6 @@
#include <boost/random/variate_generator.hpp>
#include <boost/random/normal_distribution.hpp>
-
-
-using namespace boost;
using namespace std;
@@ -177,11 +174,11 @@
//convert the original sphere vector (with clump info) to a BasicSphere vector.
vector<BasicSphere> sphere_list;
- typedef tuple<Vector3r,Real,int> tupleVector3rRealInt;
+ typedef boost::tuple<Vector3r,Real,int> tupleVector3rRealInt;
if(importFilename!=""){
- vector<tuple<Vector3r,Real,int> >sphereListClumpInfo = Shop::loadSpheresFromFile(importFilename,lowerCorner,upperCorner);
+ vector<boost::tuple<Vector3r,Real,int> >sphereListClumpInfo = Shop::loadSpheresFromFile(importFilename,lowerCorner,upperCorner);
FOREACH(tupleVector3rRealInt t, sphereListClumpInfo){
- sphere_list.push_back(make_pair(get<0>(t),get<1>(t)));
+ sphere_list.push_back(make_pair(boost::get<0>(t),boost::get<1>(t)));
};
}
else message=GenerateCloud_cohesive(sphere_list, lowerCorner, upperCorner, numberOfGrains, radiusDeviation, 0.75);
@@ -391,14 +388,14 @@
break;
}
}
- if (t==tries) return "More than " + lexical_cast<string>(tries) +
+ if (t==tries) return "More than " + boost::lexical_cast<string>(tries) +
" tries while generating sphere number " +
- lexical_cast<string>(i+1) + "/" + lexical_cast<string>(number) + ".";
+ boost::lexical_cast<string>(i+1) + "/" + boost::lexical_cast<string>(number) + ".";
}
- return "Generated a sample with " + lexical_cast<string>(number) + "spheres inside box of dimensions: ("
- + lexical_cast<string>(dimensions[0]) + ","
- + lexical_cast<string>(dimensions[1]) + ","
- + lexical_cast<string>(dimensions[2]) + ").";
+ return "Generated a sample with " + boost::lexical_cast<string>(number) + "spheres inside box of dimensions: ("
+ + boost::lexical_cast<string>(dimensions[0]) + ","
+ + boost::lexical_cast<string>(dimensions[1]) + ","
+ + boost::lexical_cast<string>(dimensions[2]) + ").";
}
=== modified file 'pkg/dem/ConcretePM.cpp'
--- pkg/dem/ConcretePM.cpp 2013-10-04 12:03:13 +0000
+++ pkg/dem/ConcretePM.cpp 2014-05-23 13:05:19 +0000
@@ -465,7 +465,7 @@
void Gl1_CpmPhys::go(const shared_ptr<IPhys>& ip, const shared_ptr<Interaction>& i, const shared_ptr<Body>& b1, const shared_ptr<Body>& b2, bool wireFrame){
- const shared_ptr<CpmPhys>& phys = static_pointer_cast<CpmPhys>(ip);
+ const shared_ptr<CpmPhys>& phys = boost::static_pointer_cast<CpmPhys>(ip);
const shared_ptr<GenericSpheresContact>& geom = YADE_PTR_CAST<GenericSpheresContact>(i->geom);
// FIXME: get the scene for periodicity; ugly!
Scene* scene=Omega::instance().getScene().get();
@@ -518,7 +518,7 @@
glPopMatrix();
}
- Vector3r cp = static_pointer_cast<GenericSpheresContact>(i->geom)->contactPoint;
+ Vector3r cp = boost::static_pointer_cast<GenericSpheresContact>(i->geom)->contactPoint;
if (scene->isPeriodic) {cp = scene->cell->wrapShearedPt(cp);}
if (epsT) {
Real maxShear = (phys->undamagedCohesion-phys->sigmaN*phys->tanFrictionAngle)/phys->G;
@@ -564,7 +564,7 @@
FOREACH(const shared_ptr<Interaction>& I, *scene->interactions){
if (!I) continue;
if (!I->isReal()) continue;
- shared_ptr<CpmPhys> phys = dynamic_pointer_cast<CpmPhys>(I->phys);
+ shared_ptr<CpmPhys> phys = boost::dynamic_pointer_cast<CpmPhys>(I->phys);
if (!phys) continue;
const Body::id_t id1 = I->getId1(), id2 = I->getId2();
GenericSpheresContact* geom = YADE_CAST<GenericSpheresContact*>(I->geom.get());
=== modified file 'pkg/dem/Disp2DPropLoadEngine.cpp'
--- pkg/dem/Disp2DPropLoadEngine.cpp 2010-11-07 11:46:20 +0000
+++ pkg/dem/Disp2DPropLoadEngine.cpp 2014-05-23 13:05:19 +0000
@@ -77,7 +77,7 @@
else if ( (scene->iter-it_begin) == nbre_iter)
{
stopMovement();
- string fileName=Key + "DR"+lexical_cast<string> (nbre_iter)+"ItAtV_"+lexical_cast<string> (v)+"done.xml";
+ string fileName=Key + "DR"+boost::lexical_cast<string> (nbre_iter)+"ItAtV_"+boost::lexical_cast<string> (v)+"done.xml";
// Omega::instance().saveSimulation ( fileName );
saveData();
}
@@ -210,11 +210,11 @@
,d2W = dSigN * du + dTau * dgamma
;
- ofile << lexical_cast<string> (theta) << " "<< lexical_cast<string> (dTau) << " " << lexical_cast<string> (dSigN) << " "
- << lexical_cast<string> (dgamma)<<" " << lexical_cast<string> (du) << " " << lexical_cast<string> (Tau0) << " "
- << lexical_cast<string> (SigN0) << " " << lexical_cast<string> (d2W) << " "
- << lexical_cast<string> (coordSs0) << " " << lexical_cast<string> (coordTot0) << " "
- << lexical_cast<string> (coordSs) << " " << lexical_cast<string> (coordTot) <<endl;
+ ofile << boost::lexical_cast<string> (theta) << " "<< boost::lexical_cast<string> (dTau) << " " << boost::lexical_cast<string> (dSigN) << " "
+ << boost::lexical_cast<string> (dgamma)<<" " << boost::lexical_cast<string> (du) << " " << boost::lexical_cast<string> (Tau0) << " "
+ << boost::lexical_cast<string> (SigN0) << " " << boost::lexical_cast<string> (d2W) << " "
+ << boost::lexical_cast<string> (coordSs0) << " " << boost::lexical_cast<string> (coordTot0) << " "
+ << boost::lexical_cast<string> (coordSs) << " " << boost::lexical_cast<string> (coordTot) <<endl;
}
=== modified file 'pkg/dem/DomainLimiter.cpp'
--- pkg/dem/DomainLimiter.cpp 2013-10-15 05:01:48 +0000
+++ pkg/dem/DomainLimiter.cpp 2014-05-23 13:05:19 +0000
@@ -23,7 +23,7 @@
}
}
FOREACH(Body::id_t id, out){
- scene->bodies->erase(id);
+ scene->bodies->erase(id,false);
}
}
@@ -63,7 +63,7 @@
if(ids.size()!=2) throw std::invalid_argument("LawTester.ids: exactly two values must be given.");
LOG_DEBUG("=================== LawTester step "<<step<<" ========================");
const shared_ptr<Interaction> Inew=scene->interactions->find(ids[0],ids[1]);
- string strIds("##"+lexical_cast<string>(ids[0])+"+"+lexical_cast<string>(ids[1]));
+ string strIds("##"+boost::lexical_cast<string>(ids[0])+"+"+boost::lexical_cast<string>(ids[1]));
// interaction not found at initialization
if(!I && (!Inew || !Inew->isReal())){
LOG_WARN("Interaction "<<strIds<<" does not exist (yet?), no-op."); return;
@@ -87,7 +87,7 @@
bool hasRot=(l6Geom || scGeom6d);
//NormShearPhys* phys=dynamic_cast<NormShearPhys*>(I->phys.get()); //Disabled because of warning
if(!gsc) throw std::invalid_argument("LawTester: IGeom of "+strIds+" not a GenericSpheresContact.");
- if(!scGeom && !l3Geom) throw std::invalid_argument("LawTester: IGeom of "+strIds+" is neither ScGeom, nor Dem3DofGeom, nor L3Geom (or L6Geom).");
+ if(!scGeom && !l3Geom) throw std::invalid_argument("LawTester: IGeom of "+strIds+" is neither ScGeom, nor L3Geom (or L6Geom).");
assert(!((bool)scGeom && (bool)l3Geom)); // nonsense
// get body objects
State *state1=Body::byId(id1,scene)->state.get(), *state2=Body::byId(id2,scene)->state.get();
@@ -237,7 +237,7 @@
// scene object changed (after reload, for instance), for re-initialization
if(tester && tester->scene!=scene) tester=shared_ptr<LawTester>();
- if(!tester){ FOREACH(shared_ptr<Engine> e, scene->engines){ tester=dynamic_pointer_cast<LawTester>(e); if(tester) break; } }
+ if(!tester){ FOREACH(shared_ptr<Engine> e, scene->engines){ tester=boost::dynamic_pointer_cast<LawTester>(e); if(tester) break; } }
if(!tester){ LOG_ERROR("No LawTester in O.engines, killing myself."); dead=true; return; }
//if(tester->renderLength<=0) return;
=== modified file 'pkg/dem/FacetTopologyAnalyzer.cpp'
--- pkg/dem/FacetTopologyAnalyzer.cpp 2011-02-14 08:05:09 +0000
+++ pkg/dem/FacetTopologyAnalyzer.cpp 2014-05-23 13:05:19 +0000
@@ -17,7 +17,7 @@
// minimum facet edge length (tolerance scale)
Real minSqLen=numeric_limits<Real>::infinity();
FOREACH(const shared_ptr<Body>& b, *scene->bodies){
- shared_ptr<Facet> f=dynamic_pointer_cast<Facet>(b->shape);
+ shared_ptr<Facet> f=boost::dynamic_pointer_cast<Facet>(b->shape);
if(!f) continue;
const Vector3r& pos=b->state->pos;
for(size_t i=0; i<3; i++){
=== modified file 'pkg/dem/FlatGridCollider.cpp'
--- pkg/dem/FlatGridCollider.cpp 2014-02-03 11:21:42 +0000
+++ pkg/dem/FlatGridCollider.cpp 2014-05-23 13:05:19 +0000
@@ -21,7 +21,7 @@
void FlatGridCollider::action(){
if(!newton){
- FOREACH(const shared_ptr<Engine>& e, scene->engines){ newton=dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) break; }
+ FOREACH(const shared_ptr<Engine>& e, scene->engines){ newton=boost::dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) break; }
if(!newton){ throw runtime_error("FlatGridCollider: Unable to find NewtonIntegrator in engines."); }
}
fastestBodyMaxDist=0;
=== modified file 'pkg/dem/GeneralIntegratorInsertionSortCollider.cpp'
--- pkg/dem/GeneralIntegratorInsertionSortCollider.cpp 2014-02-17 14:31:35 +0000
+++ pkg/dem/GeneralIntegratorInsertionSortCollider.cpp 2014-05-23 13:05:19 +0000
@@ -111,7 +111,7 @@
if(verletDist>0){
// get the Integrator, to ask for the maximum velocity value
if(!integrator){
- FOREACH(shared_ptr<Engine>& e, scene->engines){ integrator=dynamic_pointer_cast<Integrator>(e); if(integrator) break; }
+ FOREACH(shared_ptr<Engine>& e, scene->engines){ integrator=boost::dynamic_pointer_cast<Integrator>(e); if(integrator) break; }
if(!integrator){ throw runtime_error("InsertionSortCollider.verletDist>0, but unable to locate any Integrator within O.engines."); }
}
}
=== modified file 'pkg/dem/GlobalStiffnessTimeStepper.cpp'
--- pkg/dem/GlobalStiffnessTimeStepper.cpp 2013-09-26 07:51:11 +0000
+++ pkg/dem/GlobalStiffnessTimeStepper.cpp 2014-05-23 13:05:19 +0000
@@ -132,7 +132,7 @@
else if (!computedOnce) scene->dt=defaultDt;
LOG_INFO("computed timestep " << newDt <<
(scene->dt==newDt ? string(", applied") :
- string(", BUT timestep is ")+lexical_cast<string>(scene->dt))<<".");
+ string(", BUT timestep is ")+boost::lexical_cast<string>(scene->dt))<<".");
}
void GlobalStiffnessTimeStepper::computeStiffnesses(Scene* rb){
=== modified file 'pkg/dem/Ig2_Sphere_Sphere_ScGeom.cpp'
--- pkg/dem/Ig2_Sphere_Sphere_ScGeom.cpp 2013-04-23 14:07:34 +0000
+++ pkg/dem/Ig2_Sphere_Sphere_ScGeom.cpp 2014-05-23 13:05:19 +0000
@@ -29,7 +29,7 @@
else { scm=shared_ptr<ScGeom>(new ScGeom()); c->geom=scm; }
Real norm=normal.norm(); normal/=norm; // normal is unit vector now
#ifdef YADE_DEBUG
- if(norm==0) throw runtime_error(("Zero distance between spheres #"+lexical_cast<string>(c->getId1())+" and #"+lexical_cast<string>(c->getId2())+".").c_str());
+ if(norm==0) throw runtime_error(("Zero distance between spheres #"+boost::lexical_cast<string>(c->getId1())+" and #"+boost::lexical_cast<string>(c->getId2())+".").c_str());
#endif
Real penetrationDepth=s1->radius+s2->radius-norm;
scm->contactPoint=se31.position+(s1->radius-0.5*penetrationDepth)*normal;//0.5*(pt1+pt2);
=== modified file 'pkg/dem/Integrator.cpp'
--- pkg/dem/Integrator.cpp 2014-02-17 14:31:35 +0000
+++ pkg/dem/Integrator.cpp 2014-05-23 13:03:50 +0000
@@ -2,7 +2,7 @@
#include<yade/core/Scene.hpp>
#include<yade/pkg/dem/Integrator.hpp>
#include<boost/python.hpp>
-using namespace boost;
+
#ifdef YADE_OPENMP
#include<omp.h>
#endif
@@ -106,8 +106,8 @@
b->shape->cast<Clump>().addForceTorqueFromMembers(b->state.get(),scene,force,moment);
#ifdef YADE_OPENMP
//it is safe here, since only one thread will read/write
- scene->forces.getTorqueUnsynced(id)+=moment;
- scene->forces.getForceUnsynced(id)+=force;
+ scene->forces.addTorqueUnsynced(id,moment);
+ scene->forces.addForceUnsynced(id,force);
#else
scene->forces.addTorque(id,moment);
scene->forces.addForce(id,force);
@@ -325,25 +325,25 @@
maxVelocitySq=max(maxVelocitySq,maxDisp);
}
-void Integrator::slaves_set(const python::list& slaves2){
+void Integrator::slaves_set(const boost::python::list& slaves2){
std::cout<<"Adding slaves";
- int len=python::len(slaves2);
+ int len=boost::python::len(slaves2);
slaves.clear();
for(int i=0; i<len; i++){
- python::extract<std::vector<shared_ptr<Engine> > > serialGroup(slaves2[i]);
+ boost::python::extract<std::vector<shared_ptr<Engine> > > serialGroup(slaves2[i]);
if (serialGroup.check()){ slaves.push_back(serialGroup()); continue; }
- python::extract<shared_ptr<Engine> > serialAlone(slaves2[i]);
+ boost::python::extract<shared_ptr<Engine> > serialAlone(slaves2[i]);
if (serialAlone.check()){ vector<shared_ptr<Engine> > aloneWrap; aloneWrap.push_back(serialAlone()); slaves.push_back(aloneWrap); continue; }
PyErr_SetString(PyExc_TypeError,"Engines that are given to Integrator should be in two cases (a) in an ordered group, (b) alone engines");
- python::throw_error_already_set();
+ boost::python::throw_error_already_set();
}
}
-python::list Integrator::slaves_get(){
- python::list ret;
+boost::python::list Integrator::slaves_get(){
+ boost::python::list ret;
FOREACH(vector<shared_ptr<Engine > >& grp, slaves){
- if(grp.size()==1) ret.append(python::object(grp[0]));
- else ret.append(python::object(grp));
+ if(grp.size()==1) ret.append(boost::python::object(grp[0]));
+ else ret.append(boost::python::object(grp));
}
return ret;
}
=== modified file 'pkg/dem/Ip2_CohFrictMat_CohFrictMat_CohFrictPhys.hpp'
--- pkg/dem/Ip2_CohFrictMat_CohFrictMat_CohFrictPhys.hpp 2013-01-14 21:22:11 +0000
+++ pkg/dem/Ip2_CohFrictMat_CohFrictMat_CohFrictPhys.hpp 2014-05-21 16:01:55 +0000
@@ -20,7 +20,7 @@
int cohesionDefinitionIteration;
YADE_CLASS_BASE_DOC_ATTRS_CTOR(Ip2_CohFrictMat_CohFrictMat_CohFrictPhys,IPhysFunctor,
- "Generates cohesive-frictional interactions with moments. Used in the contact law :yref:`Law2_ScGeom6D_CohFrictPhys_CohesionMoment`. The normal/shear stiffness and friction definitions are the same as in :yref:`Ip2_FrictMat_FrictMat_FrictPhys`, check the documentation there for details.",
+ "Generates cohesive-frictional interactions with moments, used in the contact law :yref:`Law2_ScGeom6D_CohFrictPhys_CohesionMoment`. The normal/shear stiffness and friction definitions are the same as in :yref:`Ip2_FrictMat_FrictMat_FrictPhys`, check the documentation there for details.\n\nAdhesions related to the normal and the shear components are calculated form :yref:`CohFrictMat::normalCohesion` ($C_n$) and :yref:`CohFrictMat::shearlCohesion` ($C_s$). For particles of size $R_1$,$R_2$ the adhesion will be $a_i=C_i min(R_1,R_2)^2$, $i=n\\,s$.\n\nTwist and rolling stiffnesses are proportional to the shear stiffness through dimensionless factors alphaKtw and alphaKr, such that the rotational stiffnesses are defined by $k_s \\alpha_i R_1 R_2$, $i=tw\\,r$",
((bool,setCohesionNow,false,,"If true, assign cohesion to all existing contacts in current time-step. The flag is turned false automatically, so that assignment is done in the current timestep only."))
((bool,setCohesionOnNewContacts,false,,"If true, assign cohesion at all new contacts. If false, only existing contacts can be cohesive (also see :yref:`Ip2_CohFrictMat_CohFrictMat_CohFrictPhys::setCohesionNow`), and new contacts are only frictional."))
,
=== modified file 'pkg/dem/JointedCohesiveFrictionalPM.cpp'
--- pkg/dem/JointedCohesiveFrictionalPM.cpp 2014-03-11 18:36:24 +0000
+++ pkg/dem/JointedCohesiveFrictionalPM.cpp 2014-05-23 13:05:19 +0000
@@ -70,7 +70,7 @@
if(file.tellp()==0){ file <<"i p0 p1 p2 t s norm0 norm1 norm2"<<endl; }
Vector3r crackNormal=Vector3r::Zero();
if ((smoothJoint) && (phys->isOnJoint)) { crackNormal=phys->jointNormal; } else {crackNormal=geom->normal;}
- file << lexical_cast<string> ( scene->iter )<<" "<< lexical_cast<string> ( geom->contactPoint[0] ) <<" "<< lexical_cast<string> ( geom->contactPoint[1] ) <<" "<< lexical_cast<string> ( geom->contactPoint[2] ) <<" "<< 0 <<" "<< lexical_cast<string> ( 0.5*(geom->radius1+geom->radius2) ) <<" "<< lexical_cast<string> ( crackNormal[0] ) <<" "<< lexical_cast<string> ( crackNormal[1] ) <<" "<< lexical_cast<string> ( crackNormal[2] ) << endl;
+ file << boost::lexical_cast<string> ( scene->iter )<<" "<< boost::lexical_cast<string> ( geom->contactPoint[0] ) <<" "<< boost::lexical_cast<string> ( geom->contactPoint[1] ) <<" "<< boost::lexical_cast<string> ( geom->contactPoint[2] ) <<" "<< 0 <<" "<< boost::lexical_cast<string> ( 0.5*(geom->radius1+geom->radius2) ) <<" "<< boost::lexical_cast<string> ( crackNormal[0] ) <<" "<< boost::lexical_cast<string> ( crackNormal[1] ) <<" "<< boost::lexical_cast<string> ( crackNormal[2] ) << endl;
}
cracksFileExist=true;
@@ -133,7 +133,7 @@
if(file.tellp()==0){ file <<"i p0 p1 p2 t s norm0 norm1 norm2"<<endl; }
Vector3r crackNormal=Vector3r::Zero();
if ((smoothJoint) && (phys->isOnJoint)) { crackNormal=phys->jointNormal; } else {crackNormal=geom->normal;}
- file << lexical_cast<string> ( scene->iter )<<" "<< lexical_cast<string> ( geom->contactPoint[0] ) <<" "<< lexical_cast<string> ( geom->contactPoint[1] ) <<" "<< lexical_cast<string> ( geom->contactPoint[2] ) <<" "<< 1 <<" "<< lexical_cast<string> ( 0.5*(geom->radius1+geom->radius2) ) <<" "<< lexical_cast<string> ( crackNormal[0] ) <<" "<< lexical_cast<string> ( crackNormal[1] ) <<" "<< lexical_cast<string> ( crackNormal[2] ) << endl;
+ file << boost::lexical_cast<string> ( scene->iter )<<" "<< boost::lexical_cast<string> ( geom->contactPoint[0] ) <<" "<< boost::lexical_cast<string> ( geom->contactPoint[1] ) <<" "<< boost::lexical_cast<string> ( geom->contactPoint[2] ) <<" "<< 1 <<" "<< boost::lexical_cast<string> ( 0.5*(geom->radius1+geom->radius2) ) <<" "<< boost::lexical_cast<string> ( crackNormal[0] ) <<" "<< boost::lexical_cast<string> ( crackNormal[1] ) <<" "<< boost::lexical_cast<string> ( crackNormal[2] ) << endl;
}
cracksFileExist=true;
=== modified file 'pkg/dem/KinemCNDEngine.cpp'
--- pkg/dem/KinemCNDEngine.cpp 2011-05-12 15:13:50 +0000
+++ pkg/dem/KinemCNDEngine.cpp 2014-05-23 13:05:19 +0000
@@ -38,7 +38,7 @@
if ( ( ( (shearSpeed>0)&&(gamma > gamma_save[j]) ) || ((shearSpeed<0)&&(gamma < gamma_save[j])) ) && (temoin_save[j]==0) )
{
stopMovement(); // reset of all the speeds before the save
- Omega::instance().saveSimulation(Key+"_"+lexical_cast<string> (floor(gamma*1000)) + "mmsheared.xml");
+ Omega::instance().saveSimulation(Key+"_"+boost::lexical_cast<string> (floor(gamma*1000)) + "mmsheared.xml");
temoin_save[j]=1;
}
}
=== modified file 'pkg/dem/KinemCNLEngine.cpp'
--- pkg/dem/KinemCNLEngine.cpp 2011-05-12 15:13:50 +0000
+++ pkg/dem/KinemCNLEngine.cpp 2014-05-23 13:05:19 +0000
@@ -16,7 +16,7 @@
if(LOG) cout << "debut applyCondi du CNCEngine !!" << endl;
KinemSimpleShearBox::getBoxes_Dt();
- if(LOG) cout << "gamma = " << lexical_cast<string>(gamma) << " et gammalim = " << lexical_cast<string>(gammalim) << endl;
+ if(LOG) cout << "gamma = " << boost::lexical_cast<string>(gamma) << " et gammalim = " << boost::lexical_cast<string>(gammalim) << endl;
if(gamma<=gammalim)
{
if(LOG) cout << "Je suis bien dans la partie gamma < gammalim" << endl;
@@ -41,7 +41,7 @@
}
else if (temoin==2 && (scene->iter==(it_stop+5000)) )
{
- Omega::instance().saveSimulation(Key + "endShear" +lexical_cast<string> ( scene->iter ) + ".xml");
+ Omega::instance().saveSimulation(Key + "endShear" +boost::lexical_cast<string> ( scene->iter ) + ".xml");
Omega::instance().pause();
}
@@ -50,7 +50,7 @@
if ((gamma > gamma_save[j]) && (temoin_save[j]==0))
{
stopMovement(); // reset of all the speeds before the save
- Omega::instance().saveSimulation(Key+"_"+lexical_cast<string> (floor(gamma*1000)) +"_" +lexical_cast<string> (floor(gamma*10000)-10*floor(gamma*1000))+ "mmsheared.xml");
+ Omega::instance().saveSimulation(Key+"_"+boost::lexical_cast<string> (floor(gamma*1000)) +"_" +boost::lexical_cast<string> (floor(gamma*10000)-10*floor(gamma*1000))+ "mmsheared.xml");
temoin_save[j]=1;
}
}
=== modified file 'pkg/dem/KinemCNSEngine.cpp'
--- pkg/dem/KinemCNSEngine.cpp 2011-05-12 15:13:50 +0000
+++ pkg/dem/KinemCNSEngine.cpp 2014-05-23 13:05:19 +0000
@@ -38,7 +38,7 @@
}
else if (temoin==2 && (scene->iter==(it_stop+5000)) )
{
- Omega::instance().saveSimulation(Key + "finCis" +lexical_cast<string> (scene->iter ) + ".xml");
+ Omega::instance().saveSimulation(Key + "finCis" +boost::lexical_cast<string> (scene->iter ) + ".xml");
Omega::instance().pause();
}
=== modified file 'pkg/dem/KinemCTDEngine.cpp'
--- pkg/dem/KinemCTDEngine.cpp 2011-05-12 15:13:50 +0000
+++ pkg/dem/KinemCTDEngine.cpp 2014-05-23 13:05:19 +0000
@@ -29,9 +29,9 @@
{
if(temoin!=0)
{
-// cout << "j'ai ici un temoin #0 visiblement. En effet temoin =" <<lexical_cast<string>(temoin) << endl;
+// cout << "j'ai ici un temoin #0 visiblement. En effet temoin =" <<boost::lexical_cast<string>(temoin) << endl;
temoin=0;
-// cout << "Maintenant (toujours dans le if temoin!=0), temoin =" <<lexical_cast<string>(temoin) << endl;
+// cout << "Maintenant (toujours dans le if temoin!=0), temoin =" <<boost::lexical_cast<string>(temoin) << endl;
}
letMove(0.0,-compSpeed*dt);
@@ -39,17 +39,17 @@
else if (temoin==0)
{
stopMovement();
-// cout << "Mouvement stoppe, temoin = " << lexical_cast<string>(temoin) << endl;
-// cout << " Dans le if, temoin =" << lexical_cast<string>(temoin) << endl;
+// cout << "Mouvement stoppe, temoin = " << boost::lexical_cast<string>(temoin) << endl;
+// cout << " Dans le if, temoin =" << boost::lexical_cast<string>(temoin) << endl;
string f;
if (compSpeed > 0)
f="Sigmax_";
else
f="Sigmin_";
- Omega::instance().saveSimulation(Key + f +lexical_cast<string> (floor(targetSigma)) + "kPaReached.xml");
+ Omega::instance().saveSimulation(Key + f +boost::lexical_cast<string> (floor(targetSigma)) + "kPaReached.xml");
temoin=1;
-// cout << " Fin du if, temoin =" << lexical_cast<string>(temoin) << endl << endl;
+// cout << " Fin du if, temoin =" << boost::lexical_cast<string>(temoin) << endl << endl;
}
@@ -58,11 +58,11 @@
if( ( ( (compSpeed>0)&&(current_sigma > sigma_save[j]) ) || ((compSpeed<0)&&(current_sigma < sigma_save[j])) ) && (temoin_save[j]==0))
{
stopMovement();
- Omega::instance().saveSimulation(Key + "SigInt_" +lexical_cast<string> (floor(current_sigma)) + "kPareached.xml");
+ Omega::instance().saveSimulation(Key + "SigInt_" +boost::lexical_cast<string> (floor(current_sigma)) + "kPareached.xml");
temoin_save[j]=1;
}
}
-// cout << "Fin de ApplyCondi, temoin = " << lexical_cast<string>(temoin) << endl;
+// cout << "Fin de ApplyCondi, temoin = " << boost::lexical_cast<string>(temoin) << endl;
}
=== modified file 'pkg/dem/NewtonIntegrator.cpp'
--- pkg/dem/NewtonIntegrator.cpp 2014-04-08 19:11:03 +0000
+++ pkg/dem/NewtonIntegrator.cpp 2014-05-23 13:05:19 +0000
@@ -142,14 +142,15 @@
// clump members are handled inside clumps
if(b->isClumpMember()) continue;
State* state=b->state.get(); const Body::id_t& id=b->getId();
- Vector3r f=Vector3r::Zero(), m=Vector3r::Zero();
+ Vector3r f=Vector3r::Zero();
+ Vector3r m=Vector3r::Zero();
// clumps forces
if(b->isClump()) {
b->shape->cast<Clump>().addForceTorqueFromMembers(state,scene,f,m);
#ifdef YADE_OPENMP
- //it is safe here, since only one thread will read/write
- scene->forces.getTorqueUnsynced(id)+=m;
- scene->forces.getForceUnsynced(id)+=f;
+ //it is safe here, since only one thread is adding forces/torques
+ scene->forces.addTorqueUnsynced(id,m);
+ scene->forces.addForceUnsynced(id,f);
#else
scene->forces.addTorque(id,m);
scene->forces.addForce(id,f);
@@ -158,10 +159,10 @@
//in most cases, the initial force on clumps will be zero and next line is not changing f and m, but make sure we don't miss something (e.g. user defined forces on clumps)
f=scene->forces.getForce(id); m=scene->forces.getTorque(id);
#ifdef YADE_DEBUG
- if(isnan(f[0])||isnan(f[1])||isnan(f[2])) throw runtime_error(("NewtonIntegrator: NaN force acting on #"+lexical_cast<string>(id)+".").c_str());
- if(isnan(m[0])||isnan(m[1])||isnan(m[2])) throw runtime_error(("NewtonIntegrator: NaN torque acting on #"+lexical_cast<string>(id)+".").c_str());
- if(state->mass<=0 && ((state->blockedDOFs & State::DOF_XYZ) != State::DOF_XYZ)) throw runtime_error(("NewtonIntegrator: #"+lexical_cast<string>(id)+" has some linear accelerations enabled, but State::mass is non-positive."));
- if(state->inertia.minCoeff()<=0 && ((state->blockedDOFs & State::DOF_RXRYRZ) != State::DOF_RXRYRZ)) throw runtime_error(("NewtonIntegrator: #"+lexical_cast<string>(id)+" has some angular accelerations enabled, but State::inertia contains non-positive terms."));
+ if(isnan(f[0])||isnan(f[1])||isnan(f[2])) throw runtime_error(("NewtonIntegrator: NaN force acting on #"+boost::lexical_cast<string>(id)+".").c_str());
+ if(isnan(m[0])||isnan(m[1])||isnan(m[2])) throw runtime_error(("NewtonIntegrator: NaN torque acting on #"+boost::lexical_cast<string>(id)+".").c_str());
+ if(state->mass<=0 && ((state->blockedDOFs & State::DOF_XYZ) != State::DOF_XYZ)) throw runtime_error(("NewtonIntegrator: #"+boost::lexical_cast<string>(id)+" has some linear accelerations enabled, but State::mass is non-positive."));
+ if(state->inertia.minCoeff()<=0 && ((state->blockedDOFs & State::DOF_RXRYRZ) != State::DOF_RXRYRZ)) throw runtime_error(("NewtonIntegrator: #"+boost::lexical_cast<string>(id)+" has some angular accelerations enabled, but State::inertia contains non-positive terms."));
#endif
// fluctuation velocity does not contain meanfield velocity in periodic boundaries
@@ -201,6 +202,7 @@
leapfrogTranslate(state,id,dt);
if(!useAspherical) leapfrogSphericalRotate(state,id,dt);
else leapfrogAsphericalRotate(state,id,dt,m);
+
saveMaximaDisplacement(b);
// move individual members of the clump, save maxima velocity (for collider stride)
if(b->isClump()) Clump::moveMembers(b,scene,this);
@@ -226,18 +228,22 @@
//NOTE : dVel defined without wraping the coordinates means bodies out of the (0,0,0) period can move realy fast. It has to be compensated properly in the definition of relative velocities (see Ig2 functors and contact laws).
//Reflect mean-field (periodic cell) acceleration in the velocity
if(scene->isPeriodic && homoDeform) {Vector3r dVel=dVelGrad*state->pos; state->vel+=dVel;}
- state->pos+=state->vel*dt;
+
+ if ( (mask<=0) or ((mask>0) and ((Body::byId(id)->groupMask & mask)!=0)) ) {
+ state->pos+=state->vel*dt;
+ }
}
void NewtonIntegrator::leapfrogSphericalRotate(State* state, const Body::id_t& id, const Real& dt )
{
Real angle2=state->angVel.squaredNorm();
- if (angle2!=0) {//If we have an angular velocity, we make a rotation
+ if (angle2!=0 and ( (mask<=0) or ((mask>0) and ((Body::byId(id)->groupMask & mask)!=0)) )) {//If we have an angular velocity, we make a rotation
Real angle=sqrt(angle2);
Quaternionr q(AngleAxisr(angle*dt,state->angVel/angle));
state->ori = q*state->ori;
}
- if(scene->forces.getMoveRotUsed() && scene->forces.getRot(id)!=Vector3r::Zero()) {
+ if(scene->forces.getMoveRotUsed() && scene->forces.getRot(id)!=Vector3r::Zero()
+ and ( (mask<=0) or ((mask>0) and ((Body::byId(id)->groupMask & mask)!=0)) )) {
Vector3r r(scene->forces.getRot(id));
Real norm=r.norm(); r/=norm;
Quaternionr q(AngleAxisr(norm,r));
=== modified file 'pkg/dem/NewtonIntegrator.hpp'
--- pkg/dem/NewtonIntegrator.hpp 2013-09-26 09:03:43 +0000
+++ pkg/dem/NewtonIntegrator.hpp 2014-05-15 14:47:33 +0000
@@ -76,6 +76,7 @@
((int,kinEnergyIx,-1,(Attr::hidden|Attr::noSave),"Index for kinetic energy in scene->energies."))
((int,kinEnergyTransIx,-1,(Attr::hidden|Attr::noSave),"Index for translational kinetic energy in scene->energies."))
((int,kinEnergyRotIx,-1,(Attr::hidden|Attr::noSave),"Index for rotational kinetic energy in scene->energies."))
+ ((int,mask,-1,,"If mask defined and the bitwise AND between mask and body`s groupMask gives 0, the body will not move/rotate. Velocities and accelerations will be calculated not paying attention to this parameter."))
,
/*ctor*/
densityScaling=false;
=== modified file 'pkg/dem/PeriIsoCompressor.cpp'
--- pkg/dem/PeriIsoCompressor.cpp 2013-07-09 12:42:00 +0000
+++ pkg/dem/PeriIsoCompressor.cpp 2014-05-22 15:26:55 +0000
@@ -111,7 +111,7 @@
NormShearPhys* nsi=YADE_CAST<NormShearPhys*> ( I->phys.get() );
GenericSpheresContact* gsc=YADE_CAST<GenericSpheresContact*> ( I->geom.get() );
//Contact force
- Vector3r f= ( useDem3Dof?1.:-1. ) * ( nsi->normalForce+nsi->shearForce );
+ Vector3r f= (-1.)*( nsi->normalForce+nsi->shearForce );
Vector3r branch=Body::byId(I->getId2(),scene)->state->pos + scene->cell->hSize*I->cellDist.cast<Real>() -Body::byId(I->getId1(),scene)->state->pos;
stressTensor+=f*branch.transpose();
if( !dynCell ){
=== modified file 'pkg/dem/PeriIsoCompressor.hpp'
--- pkg/dem/PeriIsoCompressor.hpp 2013-07-09 12:49:41 +0000
+++ pkg/dem/PeriIsoCompressor.hpp 2014-05-22 15:26:55 +0000
@@ -46,8 +46,7 @@
public:
virtual void action();
void strainStressStiffUpdate();
- YADE_CLASS_BASE_DOC_ATTRS_DEPREC_INIT_CTOR_PY(PeriTriaxController,BoundaryController,"Engine for independently controlling stress or strain in periodic simulations.\n\n``strainStress`` contains absolute values for the controlled quantity, and ``stressMask`` determines meaning of those values (0 for strain, 1 for stress): e.g. ``( 1<<0 | 1<<2 ) = 1 | 4 = 5`` means that ``strainStress[0]`` and ``strainStress[2]`` are stress values, and ``strainStress[1]`` is strain. \n\nSee scripts/test/periodic-triax.py for a simple example.",
- ((bool,useDem3Dof,false,,"For some constitutive laws (practicaly all laws based on Dem3Dof), normalForce and shearForce on interactions are in the reverse sense and this flag must be true. See this `message <https://lists.launchpad.net/yade-dev/msg07455.html>`_."))
+ YADE_CLASS_BASE_DOC_ATTRS_INIT_CTOR_PY(PeriTriaxController,BoundaryController,"Engine for independently controlling stress or strain in periodic simulations.\n\n``strainStress`` contains absolute values for the controlled quantity, and ``stressMask`` determines meaning of those values (0 for strain, 1 for stress): e.g. ``( 1<<0 | 1<<2 ) = 1 | 4 = 5`` means that ``strainStress[0]`` and ``strainStress[2]`` are stress values, and ``strainStress[1]`` is strain. \n\nSee scripts/test/periodic-triax.py for a simple example.",
((bool,dynCell,false,,"Imposed stress can be controlled using the packing stiffness or by applying the laws of dynamic (dynCell=true). Don't forget to assign a :yref:`mass<PeriTriaxController.mass>` to the cell."))
((Vector3r,goal,Vector3r::Zero(),,"Desired stress or strain values (depending on stressMask), strains defined as ``strain(i)=log(Fii)``.\n\n.. warning:: Strains are relative to the :yref:`O.cell.refSize<Cell.refSize>` (reference cell size), not the current one (e.g. at the moment when the new strain value is set)."))
((int,stressMask,((void)"all strains",0),,"mask determining strain/stress (0/1) meaning for goal components"))
@@ -69,8 +68,6 @@
((Real,mass,NaN,,"mass of the cell (user set); if not set and :yref:`dynCell<PeriTriaxController.dynCell>` is used, it will be computed as sum of masses of all particles."))
((Real,externalWork,0,,"Work input from boundary controller."))
((int,velGradWorkIx,-1,(Attr::hidden|Attr::noSave),"Index for work done by velocity gradient, if tracking energy"))
- ,//Deprecated
- ((reversedForces,useDem3Dof,"no need to reverse force any more, unless you are using Dem3Dof laws - in that case set the flag true. See this `message <https://lists.launchpad.net/yade-dev/msg07455.html>`_."))
,,,
);
DECLARE_LOGGER;
=== modified file 'pkg/dem/Polyhedra.cpp'
--- pkg/dem/Polyhedra.cpp 2013-10-17 11:59:10 +0000
+++ pkg/dem/Polyhedra.cpp 2014-05-23 13:05:19 +0000
@@ -16,7 +16,7 @@
YADE_PLUGIN(/* self-contained in hpp: */ (Polyhedra) (PolyhedraGeom) (Bo1_Polyhedra_Aabb) (PolyhedraPhys) (PolyhedraMat) (Ip2_PolyhedraMat_PolyhedraMat_PolyhedraPhys) (PolyhedraVolumetricLaw)
/* some code in cpp (this file): */
#ifdef YADE_OPENGL
- (Gl1_Polyhedra)
+ (Gl1_Polyhedra) (Gl1_PolyhedraGeom) (Gl1_PolyhedraPhys)
#endif
);
@@ -256,14 +256,15 @@
#ifdef YADE_OPENGL
#include<yade/lib/opengl/OpenGLWrapper.hpp>
- void Gl1_Polyhedra::go(const shared_ptr<Shape>& cm, const shared_ptr<State>&,bool,const GLViewInfo&)
+ bool Gl1_Polyhedra::wire;
+ void Gl1_Polyhedra::go(const shared_ptr<Shape>& cm, const shared_ptr<State>&,bool wire2,const GLViewInfo&)
{
glMaterialv(GL_FRONT,GL_AMBIENT_AND_DIFFUSE,Vector3r(cm->color[0],cm->color[1],cm->color[2]));
glColor3v(cm->color);
Polyhedra* t=static_cast<Polyhedra*>(cm.get());
vector<int> faceTri = t->GetSurfaceTriangulation();
- if (0) {
+ if (wire || wire2) {
glDisable(GL_LIGHTING);
glBegin(GL_LINES);
#define __ONEWIRE(a,b) glVertex3v(t->v[a]);glVertex3v(t->v[b])
@@ -283,6 +284,58 @@
glEnd();
}
}
+
+
+ void Gl1_PolyhedraGeom::go(const shared_ptr<IGeom>& ig, const shared_ptr<Interaction>&, const shared_ptr<Body>&, const shared_ptr<Body>&, bool){ draw(ig);}
+
+ void Gl1_PolyhedraGeom::draw(const shared_ptr<IGeom>& ig){
+ };
+
+ GLUquadric* Gl1_PolyhedraPhys::gluQuadric=NULL;
+ Real Gl1_PolyhedraPhys::maxFn;
+ Real Gl1_PolyhedraPhys::refRadius;
+ Real Gl1_PolyhedraPhys::maxRadius;
+ int Gl1_PolyhedraPhys::signFilter;
+ int Gl1_PolyhedraPhys::slices;
+ int Gl1_PolyhedraPhys::stacks;
+
+ void Gl1_PolyhedraPhys::go(const shared_ptr<IPhys>& ip, const shared_ptr<Interaction>& i, const shared_ptr<Body>& b1, const shared_ptr<Body>& b2, bool wireFrame){
+ if(!gluQuadric){ gluQuadric=gluNewQuadric(); if(!gluQuadric) throw runtime_error("Gl1_PolyhedraPhys::go unable to allocate new GLUquadric object (out of memory?)."); }
+ PolyhedraPhys* np=static_cast<PolyhedraPhys*>(ip.get());
+ shared_ptr<IGeom> ig(i->geom); if(!ig) return; // changed meanwhile?
+ PolyhedraGeom* geom=YADE_CAST<PolyhedraGeom*>(ig.get());
+ Real fnNorm=np->normalForce.dot(geom->normal);
+ if((signFilter>0 && fnNorm<0) || (signFilter<0 && fnNorm>0)) return;
+ int fnSign=fnNorm>0?1:-1;
+ fnNorm=abs(fnNorm);
+ Real radiusScale=1.;
+ maxFn=max(fnNorm,maxFn);
+ Real realMaxRadius;
+ if(maxRadius<0){
+ refRadius=min(0.03,refRadius);
+ realMaxRadius=refRadius;
+ }
+ else realMaxRadius=maxRadius;
+ Real radius=radiusScale*realMaxRadius*(fnNorm/maxFn);
+ if (radius<=0.) radius = 1E-8;
+ Vector3r color=Shop::scalarOnColorScale(fnNorm*fnSign,-maxFn,maxFn);
+
+ Vector3r p1=b1->state->pos, p2=b2->state->pos;
+ Vector3r relPos;
+ relPos=p2-p1;
+ Real dist=relPos.norm();
+
+ glDisable(GL_CULL_FACE);
+ glPushMatrix();
+ glTranslatef(p1[0],p1[1],p1[2]);
+ Quaternionr q(Quaternionr().setFromTwoVectors(Vector3r(0,0,1),relPos/dist /* normalized */));
+ // using Transform with OpenGL: http://eigen.tuxfamily.org/dox/TutorialGeometry.html
+ //glMultMatrixd(Eigen::Affine3d(q).data());
+ glMultMatrix(Eigen::Transform<Real,3,Eigen::Affine>(q).data());
+ glColor3v(color);
+ gluCylinder(gluQuadric,radius,radius,dist,slices,stacks);
+ glPopMatrix();
+ }
#endif
//**********************************************************************************
@@ -362,9 +415,9 @@
// Apply forces on polyhedrons in collision based on geometric configuration
void PolyhedraVolumetricLaw::go(shared_ptr<IGeom>& ig, shared_ptr<IPhys>& ip, Interaction* I){
- if (!I->geom) {I->phys=shared_ptr<IPhys>(); return;}
- const shared_ptr<PolyhedraGeom>& contactGeom(dynamic_pointer_cast<PolyhedraGeom>(I->geom));
- if(!contactGeom) {I->phys=shared_ptr<IPhys>(); return;}
+ if (!I->geom) {return;}
+ const shared_ptr<PolyhedraGeom>& contactGeom(boost::dynamic_pointer_cast<PolyhedraGeom>(I->geom));
+ if(!contactGeom) {return;}
const Body::id_t idA=I->getId1(), idB=I->getId2();
const shared_ptr<Body>& A=Body::byId(idA), B=Body::byId(idB);
@@ -373,11 +426,12 @@
//erase the interaction when aAbB shows separation, otherwise keep it to be able to store previous separating plane for fast detection of separation
if (A->bound->min[0] >= B->bound->max[0] || B->bound->min[0] >= A->bound->max[0] || A->bound->min[1] >= B->bound->max[1] || B->bound->min[1] >= A->bound->max[1] || A->bound->min[2] >= B->bound->max[2] || B->bound->min[2] >= A->bound->max[2]) {
scene->interactions->requestErase(I);
+ phys->normalForce = Vector3r(0.,0.,0.); phys->shearForce = Vector3r(0.,0.,0.);
return;
}
//zero penetration depth means no interaction force
- if(!(contactGeom->penetrationVolume > 0) ) {I->phys=shared_ptr<IPhys>(); return;}
+ if(!(contactGeom->equivalentPenetrationDepth > 1E-18) || !(contactGeom->penetrationVolume > 0)) {phys->normalForce = Vector3r(0.,0.,0.); phys->shearForce = Vector3r(0.,0.,0.); return;}
Vector3r normalForce=contactGeom->normal*contactGeom->penetrationVolume*phys->kn;
//shear force: in case the polyhdras are separated and come to contact again, one should not use the previous shear force
@@ -418,7 +472,22 @@
scene->forces.addForce (idB, -F);
scene->forces.addTorque(idA, -(A->state->pos-contactGeom->contactPoint).cross(F));
scene->forces.addTorque(idB, (B->state->pos-contactGeom->contactPoint).cross(F));
-
+
+ /*
+ FILE * fin = fopen("Forces.dat","a");
+ fprintf(fin,"************** IDS %d %d **************\n",idA, idB);
+ Vector3r T = (B->state->pos-contactGeom->contactPoint).cross(F);
+ fprintf(fin,"volume\t%e\n",contactGeom->penetrationVolume);
+ fprintf(fin,"normal_force\t%e\t%e\t%e\n",normalForce[0],normalForce[1],normalForce[2]);
+ fprintf(fin,"shear_force\t%e\t%e\t%e\n",shearForce[0],shearForce[1],shearForce[2]);
+ fprintf(fin,"total_force\t%e\t%e\t%e\n",F[0],F[1],F[2]);
+ fprintf(fin,"torsion\t%e\t%e\t%e\n",T[0],T[1],T[2]);
+ fprintf(fin,"A\t%e\t%e\t%e\n",A->state->pos[0],A->state->pos[1],A->state->pos[2]);
+ fprintf(fin,"B\t%e\t%e\t%e\n",B->state->pos[0],B->state->pos[1],B->state->pos[2]);
+ fprintf(fin,"centroid\t%e\t%e\t%e\n",contactGeom->contactPoint[0],contactGeom->contactPoint[1],contactGeom->contactPoint[2]);
+ fclose(fin);
+ */
+
//needed to be able to acces interaction forces in other parts of yade
phys->normalForce = normalForce;
phys->shearForce = shearForce;
=== modified file 'pkg/dem/Polyhedra.hpp'
--- pkg/dem/Polyhedra.hpp 2014-01-28 08:43:35 +0000
+++ pkg/dem/Polyhedra.hpp 2014-05-16 11:58:59 +0000
@@ -145,19 +145,6 @@
REGISTER_SERIALIZABLE(Bo1_Polyhedra_Aabb);
//***************************************************************************
-#ifdef YADE_OPENGL
- #include<yade/pkg/common/GLDrawFunctors.hpp>
- /*! Draw Polyhedra using OpenGL */
- class Gl1_Polyhedra: public GlShapeFunctor{
- public:
- virtual void go(const shared_ptr<Shape>&, const shared_ptr<State>&,bool,const GLViewInfo&);
- YADE_CLASS_BASE_DOC(Gl1_Polyhedra,GlShapeFunctor,"Renders :yref:`Polyhedra` object");
- RENDERS(Polyhedra);
- };
- REGISTER_SERIALIZABLE(Gl1_Polyhedra);
-#endif
-
-//***************************************************************************
/*! Elastic material */
class PolyhedraMat: public Material{
public:
@@ -193,6 +180,53 @@
REGISTER_SERIALIZABLE(PolyhedraPhys);
//***************************************************************************
+#ifdef YADE_OPENGL
+ #include<yade/pkg/common/GLDrawFunctors.hpp>
+ #include<yade/lib/opengl/OpenGLWrapper.hpp>
+ #include<yade/lib/opengl/GLUtils.hpp>
+ #include<GL/glu.h>
+ #include<yade/pkg/dem/Shop.hpp>
+
+ /*! Draw Polyhedra using OpenGL */
+ class Gl1_Polyhedra: public GlShapeFunctor{
+ public:
+ virtual void go(const shared_ptr<Shape>&, const shared_ptr<State>&,bool,const GLViewInfo&);
+ YADE_CLASS_BASE_DOC_STATICATTRS(Gl1_Polyhedra,GlShapeFunctor,"Renders :yref:`Polyhedra` object",
+ ((bool,wire,false,,"Only show wireframe"))
+ );
+ RENDERS(Polyhedra);
+ };
+ REGISTER_SERIALIZABLE(Gl1_Polyhedra);
+
+ struct Gl1_PolyhedraGeom: public GlIGeomFunctor{
+ RENDERS(PolyhedraGeom);
+ void go(const shared_ptr<IGeom>&, const shared_ptr<Interaction>&, const shared_ptr<Body>&, const shared_ptr<Body>&, bool);
+ void draw(const shared_ptr<IGeom>&);
+ YADE_CLASS_BASE_DOC_STATICATTRS(Gl1_PolyhedraGeom,GlIGeomFunctor,"Render :yref:`PolyhedraGeom` geometry.",
+ );
+ };
+ REGISTER_SERIALIZABLE(Gl1_PolyhedraGeom);
+
+ class Gl1_PolyhedraPhys: public GlIPhysFunctor{
+ static GLUquadric* gluQuadric; // needed for gluCylinder, initialized by ::go if no initialized yet
+ public:
+ virtual void go(const shared_ptr<IPhys>&,const shared_ptr<Interaction>&,const shared_ptr<Body>&,const shared_ptr<Body>&,bool wireFrame);
+ YADE_CLASS_BASE_DOC_STATICATTRS(Gl1_PolyhedraPhys,GlIPhysFunctor,"Renders :yref:`PolyhedraPhys` objects as cylinders of which diameter and color depends on :yref:`PolyhedraPhys::normForce` magnitude.",
+ ((Real,maxFn,0,,"Value of :yref:`NormPhys.normalForce` corresponding to :yref:`maxDiameter<Gl1_NormPhys.maxDiameter>`. This value will be increased (but *not decreased* ) automatically."))
+ ((Real,refRadius,std::numeric_limits<Real>::infinity(),,"Reference (minimum) particle radius"))
+ ((int,signFilter,0,,"If non-zero, only display contacts with negative (-1) or positive (+1) normal forces; if zero, all contacts will be displayed."))
+ ((Real,maxRadius,-1,,"Cylinder radius corresponding to the maximum normal force."))
+ ((int,slices,6,,"Number of sphere slices; (see `glutCylinder reference <http://www.opengl.org/sdk/docs/man/xhtml/gluCylinder.xml>`__)"))
+ ( (int,stacks,1,,"Number of sphere stacks; (see `glutCylinder reference <http://www.opengl.org/sdk/docs/man/xhtml/gluCylinder.xml>`__)"))
+ );
+ RENDERS(PolyhedraPhys);
+ };
+ REGISTER_SERIALIZABLE(Gl1_PolyhedraPhys);
+
+#endif
+
+
+//***************************************************************************
class Ip2_PolyhedraMat_PolyhedraMat_PolyhedraPhys: public IPhysFunctor{
public:
virtual void go(const shared_ptr<Material>& b1,
@@ -247,6 +281,8 @@
Polyhedron Polyhedron_Polyhedron_intersection(Polyhedron A, Polyhedron B, CGALpoint X, CGALpoint centroidA, CGALpoint centroidB, std::vector<int> &code);
//return intersection of plane & polyhedron
Polyhedron Polyhedron_Plane_intersection(Polyhedron A, Plane B, CGALpoint centroid, CGALpoint X);
+//Test if point is inside Polyhedron
+bool Is_inside_Polyhedron(Polyhedron P, CGALpoint inside);
//return approximate intersection of sphere & polyhedron
bool Sphere_Polyhedron_intersection(Polyhedron A, double r, CGALpoint C, CGALpoint centroid, double volume, CGALvector normal, double area);
//return volume and centroid of polyhedra
@@ -263,12 +299,13 @@
Polyhedron Simplify(Polyhedron P, double lim);
//list of facets and edges
void PrintPolyhedron(Polyhedron P);
+void PrintPolyhedron2File(Polyhedron P,FILE* X);
//normal by least square fitting of separating segments
Vector3r FindNormal(Polyhedron Int, Polyhedron PA, Polyhedron PB);
//calculate area of projection of polyhedron into the plane
double CalculateProjectionArea(Polyhedron Int, CGALvector CGALnormal);
//split polyhedron
-void SplitPolyhedra(const shared_ptr<Body>& body, Vector3r direction);
+shared_ptr<Body> SplitPolyhedra(const shared_ptr<Body>& body, Vector3r direction, Vector3r point);
//new polyhedra
shared_ptr<Body> NewPolyhedra(vector<Vector3r> v, shared_ptr<Material> mat);
=== modified file 'pkg/dem/Polyhedra_Ig2.cpp'
--- pkg/dem/Polyhedra_Ig2.cpp 2013-10-16 15:24:49 +0000
+++ pkg/dem/Polyhedra_Ig2.cpp 2014-05-16 11:58:59 +0000
@@ -29,6 +29,7 @@
Transformation t_rot_trans(rot_mat(0,0),rot_mat(0,1),rot_mat(0,2), trans_vec[0],rot_mat(1,0),rot_mat(1,1),rot_mat(1,2),trans_vec[1],rot_mat(2,0),rot_mat(2,1),rot_mat(2,2),trans_vec[2],1.);
Polyhedron PA = A->GetPolyhedron();
std::transform( PA.points_begin(), PA.points_end(), PA.points_begin(), t_rot_trans);
+ std::transform( PA.facets_begin(), PA.facets_end(), PA.planes_begin(),Plane_equation());
//move and rotate 2nd the CGAL structure Polyhedron
@@ -37,6 +38,7 @@
t_rot_trans = Transformation(rot_mat(0,0),rot_mat(0,1),rot_mat(0,2), trans_vec[0],rot_mat(1,0),rot_mat(1,1),rot_mat(1,2),trans_vec[1],rot_mat(2,0),rot_mat(2,1),rot_mat(2,2),trans_vec[2],1.);
Polyhedron PB = B->GetPolyhedron();
std::transform( PB.points_begin(), PB.points_end(), PB.points_begin(), t_rot_trans);
+ std::transform( PB.facets_begin(), PB.facets_end(), PB.planes_begin(),Plane_equation());
shared_ptr<PolyhedraGeom> bang;
if (isNew) {
@@ -62,6 +64,7 @@
Vector3r centroid;
P_volume_centroid(Int, &volume, ¢roid);
if(isnan(volume) || volume<=1E-25 || volume > min(A->GetVolume(),B->GetVolume())) {bang->equivalentPenetrationDepth=0; return true;}
+ if ( (!Is_inside_Polyhedron(PA, ToCGALPoint(centroid))) or (!Is_inside_Polyhedron(PB, ToCGALPoint(centroid)))) {bang->equivalentPenetrationDepth=0; return true;}
//find normal direction
Vector3r normal = FindNormal(Int, PA, PB);
@@ -80,6 +83,17 @@
bang->precompute(state1,state2,scene,interaction,normal,bang->isShearNew,shift2);
bang->normal=normal;
+ /*
+ FILE * fin = fopen("Interactions.dat","a");
+ fprintf(fin,"************** IDS %d %d **************\n",interaction->id1, interaction->id2);
+ fprintf(fin,"volume\t%e\n",volume);
+ fprintf(fin,"centroid\t%e\t%e\t%e\n",centroid[0],centroid[1],centroid[2]);
+ PrintPolyhedron2File(PA,fin);
+ PrintPolyhedron2File(PB,fin);
+ PrintPolyhedron2File(Int,fin);
+ fclose(fin);
+ */
+
return true;
}
@@ -131,6 +145,7 @@
Vector3r centroid;
P_volume_centroid(Int, &volume, ¢roid);
if(isnan(volume) || volume<=1E-25 || volume > B->GetVolume()) {bang->equivalentPenetrationDepth=0; return true;}
+ if (!Is_inside_Polyhedron(PB, ToCGALPoint(centroid))) {bang->equivalentPenetrationDepth=0; return true;}
//calculate area of projection of Intersection into the normal plane
double area = volume/1E-8;
@@ -167,6 +182,7 @@
Transformation t_rot_trans(rot_mat(0,0),rot_mat(0,1),rot_mat(0,2), trans_vec[0],rot_mat(1,0),rot_mat(1,1),rot_mat(1,2),trans_vec[1],rot_mat(2,0),rot_mat(2,1),rot_mat(2,2),trans_vec[2],1.);
Polyhedron PB = B->GetPolyhedron();
std::transform( PB.points_begin(), PB.points_end(), PB.points_begin(), t_rot_trans);
+ std::transform( PB.facets_begin(), PB.facets_end(), PB.planes_begin(),Plane_equation());
//move and rotate facet
vector<CGALpoint> v;
@@ -224,6 +240,7 @@
Vector3r centroid;
P_volume_centroid(Int, &volume, ¢roid);
if(isnan(volume) || volume<=1E-25 || volume > B->GetVolume()) {bang->equivalentPenetrationDepth=0; return true;}
+ if (!Is_inside_Polyhedron(PB, ToCGALPoint(centroid))) {bang->equivalentPenetrationDepth=0; return true;}
//find normal direction
Vector3r normal = FindNormal(Int, PA, PB);
=== modified file 'pkg/dem/Polyhedra_splitter.cpp'
--- pkg/dem/Polyhedra_splitter.cpp 2013-10-16 15:24:49 +0000
+++ pkg/dem/Polyhedra_splitter.cpp 2014-05-23 13:05:19 +0000
@@ -22,11 +22,9 @@
PolyhedraPhys* phys=YADE_CAST<PolyhedraPhys*>(I->phys.get());
if(!geom || !phys) continue;
Vector3r f=phys->normalForce+phys->shearForce;
- //Sum f_i*l_j for each contact of each particle
+ //Sum f_i*l_j for each contact of each particle
bStresses[I->getId1()] -=f*((geom->contactPoint-Body::byId(I->getId1(),scene)->state->pos).transpose());
bStresses[I->getId2()] +=f*((geom->contactPoint-Body::byId(I->getId2(),scene)->state->pos).transpose());
-
-
}
}
@@ -52,6 +50,20 @@
bStress(2,1) = bStress(1,2);
}
+//**********************************************************************************
+//split polyhedra
+void SplitPolyhedraDouble(const shared_ptr<Body>& body, Vector3r direction1, Vector3r direction2){
+
+ const Se3r& se3=body->state->se3;
+ Vector3r point = se3.position;
+
+ shared_ptr<Body> B2 = SplitPolyhedra(body, direction1, point);
+ shared_ptr<Body> B3 = SplitPolyhedra(B2, direction2, point);
+ shared_ptr<Body> B4 = SplitPolyhedra(body, direction2, point);
+
+}
+
+
//*********************************************************************************
/* Split if stress exceed strength */
@@ -61,7 +73,7 @@
shared_ptr<Scene> rb=(_rb?_rb:Omega::instance().getScene());
vector<shared_ptr<Body> > bodies;
- vector<Vector3r > directions;
+ vector<Vector3r > directions1, directions2;
vector<double > sigmas;
@@ -69,16 +81,14 @@
vector<Matrix3r> bStresses;
getStressForEachBody(bStresses);
- int i = -1;
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
- i++;
if(!b || !b->material || !b->shape) continue;
- shared_ptr<Polyhedra> p=dynamic_pointer_cast<Polyhedra>(b->shape);
- shared_ptr<PolyhedraMat> m=dynamic_pointer_cast<PolyhedraMat>(b->material);
+ shared_ptr<Polyhedra> p=boost::dynamic_pointer_cast<Polyhedra>(b->shape);
+ shared_ptr<PolyhedraMat> m=boost::dynamic_pointer_cast<PolyhedraMat>(b->material);
if(p && m->IsSplitable){
//not real strees, to get real one, it has to be divided by body volume
- Matrix3r stress = bStresses[i];
+ Matrix3r stress = bStresses[b->id];
//get eigenstresses
Symmetrize(stress);
@@ -93,16 +103,18 @@
//division of stress by volume
double comp_stress = I_valu(min_i,min_i)/p->GetVolume();
- double tens_stress = I_valu(max_i,max_i)/p->GetVolume();
+ double tens_stress = I_valu(max_i,max_i)/p->GetVolume();
Vector3r dirC = I_vect.col(max_i);
Vector3r dirT = I_vect.col(min_i);
- Vector3r dir = dirC.normalized() + dirT.normalized();;
- double sigma_t = -comp_stress/2.+ tens_stress;
- if (sigma_t > getStrength(p->GetVolume(),m->GetStrength())) {bodies.push_back(b); directions.push_back(dir); sigmas.push_back(sigma_t);};
+ Vector3r dir1 = dirC.normalized() + dirT.normalized();
+ Vector3r dir2 = dirC.normalized() - dirT.normalized();
+ //double sigma_t = -comp_stress/2.+ tens_stress;
+ double sigma_t = pow((pow(I_valu(0,0)-I_valu(1,1),2)+pow(I_valu(0,0)-I_valu(2,2),2)+pow(I_valu(1,1)-I_valu(2,2),2))/2.,0.5)/p->GetVolume();
+ if (sigma_t > getStrength(p->GetVolume(),m->GetStrength())) {bodies.push_back(b); directions1.push_back(dir1.normalized()); directions2.push_back(dir2.normalized()); sigmas.push_back(sigma_t);};
}
}
for(int i=0; i<int(bodies.size()); i++){
- SplitPolyhedra(bodies[i], directions[i]);
+ SplitPolyhedraDouble(bodies[i], directions1[i], directions2[i]);
}
}
=== modified file 'pkg/dem/Polyhedra_support.cpp'
--- pkg/dem/Polyhedra_support.cpp 2013-10-16 15:24:49 +0000
+++ pkg/dem/Polyhedra_support.cpp 2014-05-16 11:58:59 +0000
@@ -10,13 +10,15 @@
//EMPRIRICAL CONSTANTS - ADJUST IF SEGMENTATION FAULT OCCUR, IT IS A PROBLEM OF CGAL. THESE ARE USED TO CHECK CGAL IMPUTS
//DISTANCE_LIMIT controls numerical issues in calculating intersection. It should be small enough to neglect only extremely small overlaps, but large enough to prevent errors during computation of convex hull
-#define DISTANCE_LIMIT 1E-11 //-11
+#define DISTANCE_LIMIT 2E-11 //-11
//MERGE_PLANES_LIMIT - if two facets of two intersecting polyhedron differ less, then they are treated ose one only
#define MERGE_PLANES_LIMIT 1E-18 //18
//SIMPLIFY_LIMIT - if two facets of one polyhedron differ less, then they are joint into one facet
-#define SIMPLIFY_LIMIT 1E-20 //19
+#define SIMPLIFY_LIMIT 1E-19 //19
//FIND_NORMAL_LIMIT - to determine which facet of intersection belongs to which polyhedron
#define FIND_NORMAL_LIMIT 1E-40
+//SPLITTER_GAP - creates gap between splitted polyhedrons
+#define SPLITTER_GAP 1E-8
//**********************************************************************************
@@ -288,6 +290,30 @@
//**********************************************************************************
//list of facets + edges
+void PrintPolyhedron2File(Polyhedron P,FILE* X){
+ Vector3r A,B,C;
+ fprintf(X,"*** faces ***\n");
+ for (Polyhedron::Facet_iterator fIter = P.facets_begin(); fIter!=P.facets_end(); ++fIter){
+ Polyhedron::Halfedge_around_facet_circulator hfc0;
+ hfc0 = fIter->facet_begin();
+ int n = fIter->facet_degree();
+ A = FromCGALPoint(hfc0->vertex()->point());
+ C = FromCGALPoint(hfc0->next()->vertex()->point());
+ for (int i=2; i<n; i++){
+ ++hfc0;
+ B = C;
+ C = FromCGALPoint(hfc0->next()->vertex()->point());
+ fprintf(X,"%e\t%e\t%e\t%e\t%e\t%e\t%e\t%e\t%e\n",A[0],A[1],A[2],B[0],B[1],B[2],C[0],C[1],C[2]);
+ }
+ }
+ fprintf(X,"*** edges ***\n");
+ for (Polyhedron::Edge_iterator hei = P.edges_begin(); hei!=P.edges_end(); ++hei){
+ fprintf(X,"%e\t%e\t%e\t%e\t%e\t%e\n",hei->vertex()->point()[0],hei->vertex()->point()[1],hei->vertex()->point()[2], hei->opposite()->vertex()->point()[0], hei->opposite()->vertex()->point()[1], hei->opposite()->vertex()->point()[2]);
+ }
+}
+
+//**********************************************************************************
+//list of facets + edges
void PrintPolyhedron(Polyhedron P){
Vector3r A,B,C;
cout << "*** faces ***" << endl;
@@ -478,6 +504,7 @@
// test if do intersect, find some intersecting point
bool intersection_found = false;
double lim = pow(DISTANCE_LIMIT,2);
+ std::transform( A.facets_begin(), A.facets_end(), A.planes_begin(),Plane_equation());
// test centroid of previous intersection
if(Is_inside_Polyhedron(A,X,DISTANCE_LIMIT) && Oriented_squared_distance(B,X)<=-lim) {
intersection_found = true;
@@ -486,20 +513,24 @@
} else {
for(Polyhedron::Vertex_iterator vIter = A.vertices_begin(); vIter != A.vertices_end() && !intersection_found ; vIter++){
if(Oriented_squared_distance(B,vIter->point())<=-lim) {
- intersection_found = true;
- CGAL::Object result = CGAL::intersection(Line(vIter->point(),centroid), B);
- if (const CGALpoint *ipoint = CGAL::object_cast<CGALpoint>(&result)) {
- inside = vIter->point() + 0.5*CGALvector(vIter->point(),*ipoint);
+ if (Oriented_squared_distance(B,centroid)<lim/10.){
+ inside = vIter->point() + 0.5*CGALvector(vIter->point(),centroid);
}else{
- cerr << "Error in line-plane intersection" << endl;
+ CGAL::Object result = CGAL::intersection(Line(vIter->point(),centroid), B);
+ if (const CGALpoint *ipoint = CGAL::object_cast<CGALpoint>(&result)) {
+ inside = vIter->point() + 0.5*CGALvector(vIter->point(),*ipoint);
+ }else{
+ cerr << "Error in line-plane intersection" << endl;
+ }
}
+ if(Is_inside_Polyhedron(A,inside,DISTANCE_LIMIT) && Oriented_squared_distance(B,inside)<=-lim) intersection_found = true;
}
}
}
//no intersectiong point => no intersection polyhedron
if(!intersection_found) return Intersection;
-
+
//set the intersection point to origin
Transformation transl_back(CGAL::TRANSLATION, inside - CGALpoint(0.,0.,0.));
Transformation transl(CGAL::TRANSLATION, CGALpoint(0.,0.,0.)-inside);
@@ -520,7 +551,7 @@
//compute convex hull of it
Intersection = ConvexHull(dual_planes);
- if (Intersection.empty()) {cout << "0" << endl; cout.flush(); return Intersection;}
+ if (Intersection.empty()) return Intersection;
//simplify
std::transform( Intersection.facets_begin(), Intersection.facets_end(), Intersection.planes_begin(),Plane_equation());
@@ -542,7 +573,7 @@
}
//**********************************************************************************
-//returnes intersecting polyhedron of polyhedron & plane defined by diriction and point
+//returnes intersecting polyhedron of polyhedron & plane defined by direction and point
Polyhedron Polyhedron_Plane_intersection(Polyhedron A, Vector3r direction, Vector3r plane_point){
Plane B(ToCGALPoint(plane_point), ToCGALVector(direction));
CGALpoint X = ToCGALPoint(plane_point) - 1E-8*ToCGALVector(direction);
@@ -633,7 +664,7 @@
//compute convex hull of it
Intersection = ConvexHull(dual_planes);
- if (Intersection.empty()) {cout << "0" << endl; cout.flush(); return Intersection;};
+ if (Intersection.empty()) return Intersection;
//simplify
std::transform( Intersection.facets_begin(), Intersection.facets_end(), Intersection.planes_begin(),Plane_equation());
@@ -759,10 +790,11 @@
return body;
}
-
//**********************************************************************************
//split polyhedra
-void SplitPolyhedra(const shared_ptr<Body>& body, Vector3r direction){
+shared_ptr<Body> SplitPolyhedra(const shared_ptr<Body>& body, Vector3r direction, Vector3r point){
+
+ direction.normalize();
const Se3r& se3=body->state->se3;
Polyhedra* A = static_cast<Polyhedra*>(body->shape.get());
@@ -779,10 +811,14 @@
Polyhedron PA = A->GetPolyhedron();
std::transform( PA.points_begin(), PA.points_end(), PA.points_begin(), t_rot_trans);
- //calculate splitted polyhedrons
- Polyhedron S1 = Polyhedron_Plane_intersection(PA, direction, trans_vec);
- Polyhedron S2 = Polyhedron_Plane_intersection(PA, (-1)*direction, trans_vec);
-
+ //calculate first splitted polyhedrons
+ Plane B(ToCGALPoint(point-direction*SPLITTER_GAP), ToCGALVector(direction));
+ Polyhedron S1 = Polyhedron_Plane_intersection(PA, B, ToCGALPoint(se3.position), B.projection(ToCGALPoint(OrigPos)) - 1E-6*ToCGALVector(direction));
+ B = Plane(ToCGALPoint(point+direction*SPLITTER_GAP), ToCGALVector((-1.)*direction));
+ Polyhedron S2 = Polyhedron_Plane_intersection(PA, B, ToCGALPoint(se3.position), B.projection(ToCGALPoint(OrigPos)) + 1E-6*ToCGALVector(direction));
+ Scene* scene=Omega::instance().getScene().get();
+ //scene->bodies->erase(body->id);
+
//replace original polyhedron
A->Clear();
@@ -793,6 +829,8 @@
X->mass=body->material->density*A->GetVolume();
X->refPos[0] = X->refPos[0]+1.;
X->inertia =A->GetInertia()*body->material->density;
+ X->vel = OrigVel + OrigAngVel.cross(X->pos-OrigPos);
+ X->angVel = OrigAngVel;
//second polyhedron
vector<Vector3r> v2;
@@ -800,18 +838,12 @@
shared_ptr<Body> BP = NewPolyhedra(v2, body->material);
//BP->shape->color = body->shape->color;
BP->shape->color = Vector3r(double(rand())/RAND_MAX,double(rand())/RAND_MAX,double(rand())/RAND_MAX);
-
- //append to the rest
- Scene* scene=Omega::instance().getScene().get();
- //scene->bodies->erase(body->id);
scene->bodies->insert(BP);
-
//set proper state variables
- X->vel = OrigVel + OrigAngVel.cross(X->pos-OrigPos);
BP->state->vel = OrigVel + OrigAngVel.cross(BP->state->pos-OrigPos);
- X->angVel = OrigAngVel;
BP->state->angVel = OrigAngVel;
+ return BP;
}
#endif // YADE_CGAL
=== modified file 'pkg/dem/RungeKuttaCashKarp54Integrator.cpp'
--- pkg/dem/RungeKuttaCashKarp54Integrator.cpp 2014-02-18 12:02:35 +0000
+++ pkg/dem/RungeKuttaCashKarp54Integrator.cpp 2014-05-23 13:05:19 +0000
@@ -4,7 +4,7 @@
YADE_PLUGIN((RungeKuttaCashKarp54Integrator));
-shared_ptr<Integrator> RungeKuttaCashKarp54Integrator_ctor_list(const python::list& slaves){ shared_ptr<Integrator> instance(new RungeKuttaCashKarp54Integrator); instance->slaves_set(slaves); return instance; }
+shared_ptr<Integrator> RungeKuttaCashKarp54Integrator_ctor_list(const boost::python::list& slaves){ shared_ptr<Integrator> instance(new RungeKuttaCashKarp54Integrator); instance->slaves_set(slaves); return instance; }
void RungeKuttaCashKarp54Integrator::action()
{
=== modified file 'pkg/dem/RungeKuttaCashKarp54Integrator.hpp'
--- pkg/dem/RungeKuttaCashKarp54Integrator.hpp 2014-02-18 12:02:35 +0000
+++ pkg/dem/RungeKuttaCashKarp54Integrator.hpp 2014-05-23 13:05:19 +0000
@@ -12,7 +12,7 @@
typedef boost::numeric::odeint::default_error_checker< error_stepper_type::value_type,error_stepper_type::algebra_type ,error_stepper_type::operations_type > error_checker_type; //Error checker type that is redefined for initialization using different tolerance values
-shared_ptr<Integrator> RungeKuttaCashKarp54Integrator_ctor_list(const python::list& slaves);
+shared_ptr<Integrator> RungeKuttaCashKarp54Integrator_ctor_list(const boost::python::list& slaves);
class RungeKuttaCashKarp54Integrator: public Integrator {
public:
@@ -41,7 +41,7 @@
/*ctor*/
init();
,
- .def("__init__",python::make_constructor(RungeKuttaCashKarp54Integrator_ctor_list),"Construct from (possibly nested) list of slaves.")
+ .def("__init__",boost::python::make_constructor(RungeKuttaCashKarp54Integrator_ctor_list),"Construct from (possibly nested) list of slaves.")
/*py*/
);
};
=== modified file 'pkg/dem/SampleCapillaryPressureEngine.cpp'
--- pkg/dem/SampleCapillaryPressureEngine.cpp 2013-05-30 20:17:45 +0000
+++ pkg/dem/SampleCapillaryPressureEngine.cpp 2014-05-23 13:03:50 +0000
@@ -16,7 +16,6 @@
#include<yade/lib/base/Math.hpp>
#include <boost/lexical_cast.hpp>
-using namespace boost;
using namespace std;
YADE_PLUGIN((SampleCapillaryPressureEngine));
@@ -43,7 +42,7 @@
if ((S > (sigma_iso - (sigma_iso*SigmaPrecision))) && (S < (sigma_iso + (sigma_iso*SigmaPrecision)))) {
string fileName = "../data/" + Phase1End + "_" +
- lexical_cast<string>(scene->iter) + ".xml";
+ boost::lexical_cast<string>(scene->iter) + ".xml";
cerr << "saving snapshot: " << fileName << " ...";
Omega::instance().saveSimulation(fileName);
pressureVariationActivated = true;
@@ -74,4 +73,4 @@
UnbalancedForce = ComputeUnbalancedForce(scene);
}
-#endif //DEPREC CODE
\ No newline at end of file
+#endif //DEPREC CODE
=== modified file 'pkg/dem/ScGeom.hpp'
--- pkg/dem/ScGeom.hpp 2013-03-06 20:47:43 +0000
+++ pkg/dem/ScGeom.hpp 2014-05-23 13:05:19 +0000
@@ -55,8 +55,8 @@
,
/* extra initializers */ ((radius1,GenericSpheresContact::refR1)) ((radius2,GenericSpheresContact::refR2)),
/* ctor */ createIndex(); twist_axis=orthonormal_axis=Vector3r::Zero();,
- /* py */ .def("incidentVel",&ScGeom::getIncidentVel_py,(python::arg("i"),python::arg("avoidGranularRatcheting")=true),"Return incident velocity of the interaction (see also :yref:`Ig2_Sphere_Sphere_ScGeom.avoidGranularRatcheting` for explanation of the ratcheting argument).")
- .def("relAngVel",&ScGeom::getRelAngVel_py,(python::arg("i")),"Return relative angular velocity of the interaction.")
+ /* py */ .def("incidentVel",&ScGeom::getIncidentVel_py,(boost::python::arg("i"),boost::python::arg("avoidGranularRatcheting")=true),"Return incident velocity of the interaction (see also :yref:`Ig2_Sphere_Sphere_ScGeom.avoidGranularRatcheting` for explanation of the ratcheting argument).")
+ .def("relAngVel",&ScGeom::getRelAngVel_py,(boost::python::arg("i")),"Return relative angular velocity of the interaction.")
);
REGISTER_CLASS_INDEX(ScGeom,GenericSpheresContact);
};
=== modified file 'pkg/dem/Shop.hpp'
--- pkg/dem/Shop.hpp 2014-02-27 08:27:24 +0000
+++ pkg/dem/Shop.hpp 2014-05-23 13:05:19 +0000
@@ -47,7 +47,7 @@
static shared_ptr<FrictMat> defaultGranularMat();
//! Return vector of pairs (center,radius) loaded from a file with numbers inside
- static vector<tuple<Vector3r,Real,int> > loadSpheresFromFile(const string& fname,Vector3r& minXYZ, Vector3r& maxXYZ, Vector3r* cellSize=NULL);
+ static vector<boost::tuple<Vector3r,Real,int> > loadSpheresFromFile(const string& fname,Vector3r& minXYZ, Vector3r& maxXYZ, Vector3r* cellSize=NULL);
//! Save spheres in the current simulation into a text file
static void saveSpheresToFile(string fileName);
=== modified file 'pkg/dem/Shop_01.cpp'
--- pkg/dem/Shop_01.cpp 2013-10-23 09:49:41 +0000
+++ pkg/dem/Shop_01.cpp 2014-05-23 13:05:19 +0000
@@ -159,7 +159,7 @@
rb->forces.sync();
shared_ptr<NewtonIntegrator> newton;
Vector3r gravity = Vector3r::Zero();
- FOREACH(shared_ptr<Engine>& e, rb->engines){ newton=dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) {gravity=newton->gravity; break;} }
+ FOREACH(shared_ptr<Engine>& e, rb->engines){ newton=boost::dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) {gravity=newton->gravity; break;} }
// get maximum force on a body and sum of all forces (for averaging)
Real sumF=0,maxF=0,currF; int nb=0;
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
@@ -247,7 +247,7 @@
/*! Create body - sphere. */
shared_ptr<Body> Shop::sphere(Vector3r center, Real radius, shared_ptr<Material> mat){
shared_ptr<Body> body(new Body);
- body->material=mat ? mat : static_pointer_cast<Material>(defaultGranularMat());
+ body->material=mat ? mat : boost::static_pointer_cast<Material>(defaultGranularMat());
body->state->pos=center;
body->state->mass=4.0/3.0*Mathr::PI*radius*radius*radius*body->material->density;
body->state->inertia=Vector3r(2.0/5.0*body->state->mass*radius*radius,2.0/5.0*body->state->mass*radius*radius,2.0/5.0*body->state->mass*radius*radius);
@@ -259,7 +259,7 @@
/*! Create body - box. */
shared_ptr<Body> Shop::box(Vector3r center, Vector3r extents, shared_ptr<Material> mat){
shared_ptr<Body> body(new Body);
- body->material=mat ? mat : static_pointer_cast<Material>(defaultGranularMat());
+ body->material=mat ? mat : boost::static_pointer_cast<Material>(defaultGranularMat());
body->state->pos=center;
Real mass=8.0*extents[0]*extents[1]*extents[2]*body->material->density;
body->state->mass=mass;
@@ -272,7 +272,7 @@
/*! Create body - tetrahedron. */
shared_ptr<Body> Shop::tetra(Vector3r v_global[4], shared_ptr<Material> mat){
shared_ptr<Body> body(new Body);
- body->material=mat ? mat : static_pointer_cast<Material>(defaultGranularMat());
+ body->material=mat ? mat : boost::static_pointer_cast<Material>(defaultGranularMat());
Vector3r centroid=(v_global[0]+v_global[1]+v_global[2]+v_global[3])*.25;
Vector3r v[4]; for(int i=0; i<4; i++) v[i]=v_global[i]-centroid;
body->state->pos=centroid;
@@ -293,7 +293,7 @@
FOREACH(shared_ptr<Body> b, *scene->bodies){
if (!b->isDynamic()) continue;
- shared_ptr<Sphere> intSph=dynamic_pointer_cast<Sphere>(b->shape);
+ shared_ptr<Sphere> intSph=boost::dynamic_pointer_cast<Sphere>(b->shape);
if(!intSph) continue;
const Vector3r& pos=b->state->pos;
f<<pos[0]<<" "<<pos[1]<<" "<<pos[2]<<" "<<intSph->radius<<endl; // <<" "<<1<<" "<<1<<endl;
@@ -404,11 +404,11 @@
return ( std::pow(S,3) - Vv ) / std::pow(S,3);
};
-vector<tuple<Vector3r,Real,int> > Shop::loadSpheresFromFile(const string& fname, Vector3r& minXYZ, Vector3r& maxXYZ, Vector3r* cellSize){
+vector<boost::tuple<Vector3r,Real,int> > Shop::loadSpheresFromFile(const string& fname, Vector3r& minXYZ, Vector3r& maxXYZ, Vector3r* cellSize){
if(!boost::filesystem::exists(fname)) {
throw std::invalid_argument(string("File with spheres `")+fname+"' doesn't exist.");
}
- vector<tuple<Vector3r,Real,int> > spheres;
+ vector<boost::tuple<Vector3r,Real,int> > spheres;
ifstream sphereFile(fname.c_str());
if(!sphereFile.good()) throw std::runtime_error("File with spheres `"+fname+"' couldn't be opened.");
Vector3r C;
@@ -422,16 +422,16 @@
vector<string> tokens; FOREACH(const string& s, toks) tokens.push_back(s);
if(tokens.empty()) continue;
if(tokens[0]=="##PERIODIC::"){
- if(tokens.size()!=4) throw std::invalid_argument(("Spheres file "+fname+":"+lexical_cast<string>(lineNo)+" contains ##PERIODIC::, but the line is malformed.").c_str());
- if(cellSize){ *cellSize=Vector3r(lexical_cast<Real>(tokens[1]),lexical_cast<Real>(tokens[2]),lexical_cast<Real>(tokens[3])); }
+ if(tokens.size()!=4) throw std::invalid_argument(("Spheres file "+fname+":"+boost::lexical_cast<string>(lineNo)+" contains ##PERIODIC::, but the line is malformed.").c_str());
+ if(cellSize){ *cellSize=Vector3r(boost::lexical_cast<Real>(tokens[1]),boost::lexical_cast<Real>(tokens[2]),boost::lexical_cast<Real>(tokens[3])); }
continue;
}
- if(tokens.size()!=5 and tokens.size()!=4) throw std::invalid_argument(("Line "+lexical_cast<string>(lineNo)+" in the spheres file "+fname+" has "+lexical_cast<string>(tokens.size())+" columns (must be 4 or 5).").c_str());
- C=Vector3r(lexical_cast<Real>(tokens[0]),lexical_cast<Real>(tokens[1]),lexical_cast<Real>(tokens[2]));
- r=lexical_cast<Real>(tokens[3]);
+ if(tokens.size()!=5 and tokens.size()!=4) throw std::invalid_argument(("Line "+boost::lexical_cast<string>(lineNo)+" in the spheres file "+fname+" has "+boost::lexical_cast<string>(tokens.size())+" columns (must be 4 or 5).").c_str());
+ C=Vector3r(boost::lexical_cast<Real>(tokens[0]),boost::lexical_cast<Real>(tokens[1]),boost::lexical_cast<Real>(tokens[2]));
+ r=boost::lexical_cast<Real>(tokens[3]);
for(int j=0; j<3; j++) { minXYZ[j]=(spheres.size()>0?min(C[j]-r,minXYZ[j]):C[j]-r); maxXYZ[j]=(spheres.size()>0?max(C[j]+r,maxXYZ[j]):C[j]+r);}
- if(tokens.size()==5)clumpId=lexical_cast<int>(tokens[4]);
- spheres.push_back(tuple<Vector3r,Real,int>(C,r,clumpId));
+ if(tokens.size()==5)clumpId=boost::lexical_cast<int>(tokens[4]);
+ spheres.push_back(boost::tuple<Vector3r,Real,int>(C,r,clumpId));
}
return spheres;
}
@@ -441,8 +441,8 @@
Real dt=std::numeric_limits<Real>::infinity();
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
if(!b || !b->material || !b->shape) continue;
- shared_ptr<ElastMat> ebp=dynamic_pointer_cast<ElastMat>(b->material);
- shared_ptr<Sphere> s=dynamic_pointer_cast<Sphere>(b->shape);
+ shared_ptr<ElastMat> ebp=boost::dynamic_pointer_cast<ElastMat>(b->material);
+ shared_ptr<Sphere> s=boost::dynamic_pointer_cast<Sphere>(b->shape);
if(!ebp || !s) continue;
Real density=b->state->mass/((4/3.)*Mathr::PI*pow(s->radius,3));
dt=min(dt,s->radius/sqrt(ebp->young/density));
=== modified file 'pkg/dem/Shop_02.cpp'
--- pkg/dem/Shop_02.cpp 2014-04-02 15:34:57 +0000
+++ pkg/dem/Shop_02.cpp 2014-05-23 13:05:19 +0000
@@ -67,8 +67,8 @@
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
if(!b || !b->material || !b->shape) continue;
- shared_ptr<ElastMat> ebp=dynamic_pointer_cast<ElastMat>(b->material);
- shared_ptr<Sphere> s=dynamic_pointer_cast<Sphere>(b->shape);
+ shared_ptr<ElastMat> ebp=boost::dynamic_pointer_cast<ElastMat>(b->material);
+ shared_ptr<Sphere> s=boost::dynamic_pointer_cast<Sphere>(b->shape);
if(!ebp || !s) continue;
Real density=b->state->mass/((4/3.)*Mathr::PI*pow(s->radius,3));
@@ -118,7 +118,7 @@
IGeomDispatcher* geomMeta=NULL;
IPhysDispatcher* physMeta=NULL;
shared_ptr<Scene> rb=Omega::instance().getScene();
- if(rb->interactions->find(Body::id_t(id1),Body::id_t(id2))!=0) throw runtime_error(string("Interaction #")+lexical_cast<string>(id1)+"+#"+lexical_cast<string>(id2)+" already exists.");
+ if(rb->interactions->find(Body::id_t(id1),Body::id_t(id2))!=0) throw runtime_error(string("Interaction #")+boost::lexical_cast<string>(id1)+"+#"+boost::lexical_cast<string>(id2)+" already exists.");
FOREACH(const shared_ptr<Engine>& e, rb->engines){
if(!geomMeta) { geomMeta=dynamic_cast<IGeomDispatcher*>(e.get()); if(geomMeta) continue; }
if(!physMeta) { physMeta=dynamic_cast<IPhysDispatcher*>(e.get()); if(physMeta) continue; }
@@ -129,8 +129,8 @@
if(!geomMeta) throw runtime_error("No IGeomDispatcher in engines or inside InteractionLoop.");
if(!physMeta) throw runtime_error("No IPhysDispatcher in engines or inside InteractionLoop.");
shared_ptr<Body> b1=Body::byId(id1,rb), b2=Body::byId(id2,rb);
- if(!b1) throw runtime_error(("No body #"+lexical_cast<string>(id1)).c_str());
- if(!b2) throw runtime_error(("No body #"+lexical_cast<string>(id2)).c_str());
+ if(!b1) throw runtime_error(("No body #"+boost::lexical_cast<string>(id1)).c_str());
+ if(!b2) throw runtime_error(("No body #"+boost::lexical_cast<string>(id2)).c_str());
shared_ptr<Interaction> i=geomMeta->explicitAction(b1,b2,/*force*/force);
assert(force && i);
if(!i) return i;
@@ -427,12 +427,9 @@
FOREACH(shared_ptr<Body> b, *scene->bodies){
if (!b || !b->isDynamic()) continue;
if(((mask>0) and ((b->groupMask & mask)==0))) continue;
- Sphere* s=dynamic_cast<Sphere*>(b->shape.get());
- if ( (s) or ( (!s) && (b->isClump()) ) ){
- b->state->vel=Vector3r::Zero();
- b->state->angVel=Vector3r::Zero();
- b->state->angMom=Vector3r::Zero();
- }
+ b->state->vel=Vector3r::Zero();
+ b->state->angVel=Vector3r::Zero();
+ b->state->angMom=Vector3r::Zero();
}
}
=== modified file 'pkg/dem/SimpleShear.cpp'
--- pkg/dem/SimpleShear.cpp 2011-05-18 10:54:46 +0000
+++ pkg/dem/SimpleShear.cpp 2014-05-23 13:05:19 +0000
@@ -262,25 +262,25 @@
}
if (t==tries)
{
- string str1="Generated a sample with " + lexical_cast<string>(i) + " spheres inside box of dimensions: ("
- + lexical_cast<string>(dimensions[0]) + ","
- + lexical_cast<string>(dimensions[1]) + ","
- + lexical_cast<string>(dimensions[2]) + ").\n";
- return str1 + "More than " + lexical_cast<string>(tries) + " tries while generating sphere number " +
- lexical_cast<string>(i+1) + "/" + lexical_cast<string>(number) + ".";
+ string str1="Generated a sample with " + boost::lexical_cast<string>(i) + " spheres inside box of dimensions: ("
+ + boost::lexical_cast<string>(dimensions[0]) + ","
+ + boost::lexical_cast<string>(dimensions[1]) + ","
+ + boost::lexical_cast<string>(dimensions[2]) + ").\n";
+ return str1 + "More than " + boost::lexical_cast<string>(tries) + " tries while generating sphere number " +
+ boost::lexical_cast<string>(i+1) + "/" + boost::lexical_cast<string>(number) + ".";
}
}
- return "Generated a sample with " + lexical_cast<string>(number) + " spheres inside box of dimensions: ("
- + lexical_cast<string>(dimensions[0]) + ","
- + lexical_cast<string>(dimensions[1]) + ","
- + lexical_cast<string>(dimensions[2]) + ").";
+ return "Generated a sample with " + boost::lexical_cast<string>(number) + " spheres inside box of dimensions: ("
+ + boost::lexical_cast<string>(dimensions[0]) + ","
+ + boost::lexical_cast<string>(dimensions[1]) + ","
+ + boost::lexical_cast<string>(dimensions[2]) + ").";
}
std::pair<string,bool> SimpleShear::ImportCloud(vector<BasicSphere>& sphere_list,string importFilename)
{
sphere_list.clear();
int nombre=0;
- if(importFilename.size() != 0 && filesystem::exists(importFilename) )
+ if(importFilename.size() != 0 && boost::filesystem::exists(importFilename) )
{
ifstream loadFile(importFilename.c_str()); // cree l'objet loadFile de la classe ifstream qui va permettre de lire ce qu'il y a dans importFilename
@@ -308,7 +308,7 @@
sphere_list.push_back(s);
nombre++;
}
- return std::make_pair(std::string("Echantillon correctement genere : " + lexical_cast<string>(nombre) + " billes"),true);
+ return std::make_pair(std::string("Echantillon correctement genere : " + boost::lexical_cast<string>(nombre) + " billes"),true);
}
else
{
=== modified file 'pkg/dem/SpherePack.cpp'
--- pkg/dem/SpherePack.cpp 2013-09-23 17:39:59 +0000
+++ pkg/dem/SpherePack.cpp 2014-05-23 13:05:19 +0000
@@ -18,7 +18,7 @@
CREATE_LOGGER(SpherePack);
using namespace std;
-using namespace boost;
+
namespace py=boost::python;
@@ -36,7 +36,7 @@
void SpherePack::fromLists(const vector<Vector3r>& centers, const vector<Real>& radii){
pack.clear();
- if(centers.size()!=radii.size()) throw std::invalid_argument(("The same number of centers and radii must be given (is "+lexical_cast<string>(centers.size())+", "+lexical_cast<string>(radii.size())+")").c_str());
+ if(centers.size()!=radii.size()) throw std::invalid_argument(("The same number of centers and radii must be given (is "+boost::lexical_cast<string>(centers.size())+", "+boost::lexical_cast<string>(radii.size())+")").c_str());
size_t l=centers.size();
for(size_t i=0; i<l; i++){
add(centers[i],radii[i]);
@@ -51,12 +51,12 @@
};
void SpherePack::fromFile(string file) {
- typedef tuple<Vector3r,Real,int> tupleVector3rRealInt;
+ typedef boost::tuple<Vector3r,Real,int> tupleVector3rRealInt;
vector<tupleVector3rRealInt> ss;
Vector3r mn,mx;
ss=Shop::loadSpheresFromFile(file,mn,mx,&cellSize);
pack.clear();
- FOREACH(const tupleVector3rRealInt& s, ss) pack.push_back(Sph(get<0>(s),get<1>(s),get<2>(s)));
+ FOREACH(const tupleVector3rRealInt& s, ss) pack.push_back(Sph(boost::get<0>(s),boost::get<1>(s),boost::get<2>(s)));
}
void SpherePack::toFile(const string fname) const {
@@ -75,7 +75,7 @@
Scene* scene=Omega::instance().getScene().get();
FOREACH(const shared_ptr<Body>& b, *scene->bodies){
if(!b) continue;
- shared_ptr<Sphere> intSph=dynamic_pointer_cast<Sphere>(b->shape);
+ shared_ptr<Sphere> intSph=boost::dynamic_pointer_cast<Sphere>(b->shape);
if(!intSph) continue;
pack.push_back(Sph(b->state->pos,intSph->radius,(b->isClumpMember()?b->clumpId:-1)));
}
@@ -118,7 +118,7 @@
// transform sizes and cummulated fractions values in something convenient for the generation process
if(psdSizes.size()>0){
err=(mode>=0); mode=RDIST_PSD;
- if(psdSizes.size()!=psdCumm.size()) throw invalid_argument(("SpherePack.makeCloud: psdSizes and psdCumm must have same dimensions ("+lexical_cast<string>(psdSizes.size())+"!="+lexical_cast<string>(psdCumm.size())).c_str());
+ if(psdSizes.size()!=psdCumm.size()) throw invalid_argument(("SpherePack.makeCloud: psdSizes and psdCumm must have same dimensions ("+boost::lexical_cast<string>(psdSizes.size())+"!="+boost::lexical_cast<string>(psdCumm.size())).c_str());
if(psdSizes.size()<=1) throw invalid_argument("SpherePack.makeCloud: psdSizes must have at least 2 items");
if((*psdCumm.begin())!=0. && (*psdCumm.rbegin())!=1.) throw invalid_argument("SpherePack.makeCloud: first and last items of psdCumm *must* be exactly 0 and 1.");
psdRadii.reserve(psdSizes.size());
@@ -129,7 +129,7 @@
if (i==0) psdCumm2.push_back(0);
else psdCumm2.push_back(psdCumm2[i-1] + 3.0* (volume?volume:(area*psdSizes[psdSizes.size()-1])) *(1-porosity)/Mathr::PI*(psdCumm[i]-psdCumm[i-1])/(psdSizes[i]-psdSizes[i-1])*(pow(psdSizes[i-1],-2)-pow(psdSizes[i],-2)));
}
- LOG_DEBUG(i<<". "<<psdRadii[i]<<", cdf="<<psdCumm[i]<<", cdf2="<<(distributeMass?lexical_cast<string>(psdCumm2[i]):string("--")));
+ LOG_DEBUG(i<<". "<<psdRadii[i]<<", cdf="<<psdCumm[i]<<", cdf2="<<(distributeMass?boost::lexical_cast<string>(psdCumm2[i]):string("--")));
// check monotonicity
if(i>0 && (psdSizes[i-1]>psdSizes[i] || psdCumm[i-1]>psdCumm[i])) throw invalid_argument("SpherePack:makeCloud: psdSizes and psdCumm must be both non-decreasing.");
}
@@ -540,7 +540,7 @@
}
bool SpherePack::hasClumps() const { FOREACH(const Sph& s, pack){ if(s.clumpId>=0) return true; } return false; }
-python::tuple SpherePack::getClumps() const{
+py::tuple SpherePack::getClumps() const{
std::map<int,py::list> clumps;
py::list standalone; size_t packSize=pack.size();
for(size_t i=0; i<packSize; i++){
@@ -552,6 +552,6 @@
py::list clumpList;
typedef std::pair<int,py::list> intListPair;
FOREACH(const intListPair& c, clumps) clumpList.append(c.second);
- return python::make_tuple(standalone,clumpList);
+ return py::make_tuple(standalone,clumpList);
}
=== modified file 'pkg/dem/SpherePack.hpp'
--- pkg/dem/SpherePack.hpp 2013-05-29 09:48:51 +0000
+++ pkg/dem/SpherePack.hpp 2014-05-23 13:03:50 +0000
@@ -11,13 +11,20 @@
#include<boost/python.hpp>
#include<boost/python/object.hpp>
#include<boost/version.hpp>
-using namespace boost;
#include<boost/foreach.hpp>
#ifndef FOREACH
#define FOREACH BOOST_FOREACH
#endif
+#ifndef __GXX_EXPERIMENTAL_CXX0X__
+# include<boost/shared_ptr.hpp>
+ using boost::shared_ptr;
+#else
+# include<memory>
+ using std::shared_ptr;
+#endif
+
#include<yade/lib/base/Logging.hpp>
#include<yade/lib/base/Math.hpp>
@@ -41,25 +48,25 @@
struct Sph{
Vector3r c; Real r; int clumpId;
Sph(const Vector3r& _c, Real _r, int _clumpId=-1): c(_c), r(_r), clumpId(_clumpId) {};
- python::tuple asTuple() const {
- if(clumpId<0) return python::make_tuple(c,r);
- return python::make_tuple(c,r,clumpId);
+ boost::python::tuple asTuple() const {
+ if(clumpId<0) return boost::python::make_tuple(c,r);
+ return boost::python::make_tuple(c,r,clumpId);
}
- python::tuple asTupleNoClump() const { return python::make_tuple(c,r); }
+ boost::python::tuple asTupleNoClump() const { return boost::python::make_tuple(c,r); }
};
std::vector<Sph> pack;
Vector3r cellSize;
Real appliedPsdScaling;//a scaling factor that can be applied on size distribution
bool isPeriodic;
SpherePack(): cellSize(Vector3r::Zero()), appliedPsdScaling(1.), isPeriodic(0) {};
- SpherePack(const python::list& l):cellSize(Vector3r::Zero()){ fromList(l); }
+ SpherePack(const boost::python::list& l):cellSize(Vector3r::Zero()){ 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);
+ void fromList(const boost::python::list& l);
void fromLists(const vector<Vector3r>& centers, const vector<Real>& radii); // used as ctor in python
- python::list toList() const;
+ boost::python::list toList() const;
void fromFile(const string file);
void toFile(const string file) const;
void fromSimulation();
@@ -89,7 +96,7 @@
// 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); }
+ boost::python::tuple aabb_py() const { Vector3r mn,mx; aabb(mn,mx); return boost::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){
@@ -105,9 +112,9 @@
sphVol*=(4/3.)*Mathr::PI;
return sphVol/(dd[0]*dd[1]*dd[2]);
}
- python::tuple psd(int bins=10, bool mass=false) const;
+ boost::python::tuple psd(int bins=10, bool mass=false) const;
bool hasClumps() const;
- python::tuple getClumps() const;
+ boost::python::tuple getClumps() const;
// transformations
void translate(const Vector3r& shift){ FOREACH(Sph& s, pack) s.c+=shift; }
@@ -133,13 +140,13 @@
// iteration
size_t len() const{ return pack.size(); }
- python::tuple getitem(size_t idx){ if(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(); }
+ boost::python::tuple getitem(size_t idx){ if(idx>=pack.size()) throw runtime_error("Index "+boost::lexical_cast<string>(idx)+" out of range 0.."+boost::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()){ PyErr_SetNone(PyExc_StopIteration); python::throw_error_already_set(); }
+ boost::python::tuple next(){
+ if(pos==sPack.pack.size()){ PyErr_SetNone(PyExc_StopIteration); boost::python::throw_error_already_set(); }
return sPack.pack[pos++].asTupleNoClump();
}
};
=== modified file 'pkg/dem/SpheresFactory.cpp'
--- pkg/dem/SpheresFactory.cpp 2012-10-10 17:00:26 +0000
+++ pkg/dem/SpheresFactory.cpp 2014-05-23 13:05:19 +0000
@@ -24,7 +24,7 @@
void SpheresFactory::action(){
if(!collider){
- FOREACH(const shared_ptr<Engine>& e, scene->engines){ collider=dynamic_pointer_cast<Collider>(e); if(collider) break; }
+ FOREACH(const shared_ptr<Engine>& e, scene->engines){ collider=boost::dynamic_pointer_cast<Collider>(e); if(collider) break; }
if(!collider) throw runtime_error("SpheresFactory: No Collider instance found in engines (needed for collision detection).");
}
@@ -162,7 +162,7 @@
// create particle
int mId=(materialId>=0 ? materialId : scene->materials.size()+materialId);
- if(mId<0 || (size_t) mId>=scene->materials.size()) throw std::invalid_argument(("SpheresFactory: invalid material id "+lexical_cast<string>(materialId)).c_str());
+ if(mId<0 || (size_t) mId>=scene->materials.size()) throw std::invalid_argument(("SpheresFactory: invalid material id "+boost::lexical_cast<string>(materialId)).c_str());
const shared_ptr<Material>& material=scene->materials[mId];
shared_ptr<Body> b(new Body);
shared_ptr<Sphere> sphere(new Sphere);
=== modified file 'pkg/dem/TesselationWrapper.cpp'
--- pkg/dem/TesselationWrapper.cpp 2014-03-21 18:47:45 +0000
+++ pkg/dem/TesselationWrapper.cpp 2014-05-23 13:05:19 +0000
@@ -344,7 +344,7 @@
mma.analyser->DefToFile(outputFile.c_str());
}
-python::dict TesselationWrapper::getVolPoroDef(bool deformation)
+boost::python::dict TesselationWrapper::getVolPoroDef(bool deformation)
{
delete Tes;
CGT::TriaxialState* ts;
@@ -379,7 +379,7 @@
if (deformation) MATRIX3R_TO_NUMPY(mma.analyser->ParticleDeformation[id],def[id]);
//cerr << V_it->info().v()<<" "<<ParticleDeformation[id]<<endl;
}
- python::dict ret;
+ boost::python::dict ret;
ret["vol"]=vol;
ret["poro"]=poro;
if (deformation) ret["def"]=def;
=== modified file 'pkg/dem/TesselationWrapper.hpp'
--- pkg/dem/TesselationWrapper.hpp 2014-04-01 13:18:38 +0000
+++ pkg/dem/TesselationWrapper.hpp 2014-05-23 13:05:19 +0000
@@ -124,18 +124,18 @@
inf=1e10;
mma.analyser->SetConsecutive(false);
,/*py*/
- .def("triangulate",&TesselationWrapper::insertSceneSpheres,(python::arg("reset")=true),"triangulate spheres of the packing")
- .def("setState",&TesselationWrapper::setState,(python::arg("state")=0),"Make the current state of the simulation the initial (0) or final (1) configuration for the definition of displacement increments, use only state=0 if you just want to get volmumes and porosity.")
- .def("loadState",&TesselationWrapper::loadState,(python::arg("inputFile")="state",python::arg("state")=0,python::arg("bz2")=true),"Load a file with positions to define state 0 or 1.")
- .def("saveState",&TesselationWrapper::saveState,(python::arg("outputFile")="state",python::arg("state")=0,python::arg("bz2")=true),"Save a file with positions, can be later reloaded in order to define state 0 or 1.")
- .def("volume",&TesselationWrapper::Volume,(python::arg("id")=0),"Returns the volume of Voronoi's cell of a sphere.")
- .def("defToVtk",&TesselationWrapper::defToVtk,(python::arg("outputFile")="def.vtk"),"Write local deformations in vtk format from states 0 and 1.")
- .def("defToVtkFromStates",&TesselationWrapper::defToVtkFromStates,(python::arg("input1")="state1",python::arg("input2")="state2",python::arg("outputFile")="def.vtk",python::arg("bz2")=true),"Write local deformations in vtk format from state files (since the file format is very special, consider using defToVtkFromPositions if the input files were not generated by TesselationWrapper).")
- .def("defToVtkFromPositions",&TesselationWrapper::defToVtkFromPositions,(python::arg("input1")="pos1",python::arg("input2")="pos2",python::arg("outputFile")="def.vtk",python::arg("bz2")=false),"Write local deformations in vtk format from positions files (one sphere per line, with x,y,z,rad separated by spaces).")
+ .def("triangulate",&TesselationWrapper::insertSceneSpheres,(boost::python::arg("reset")=true),"triangulate spheres of the packing")
+ .def("setState",&TesselationWrapper::setState,(boost::python::arg("state")=0),"Make the current state of the simulation the initial (0) or final (1) configuration for the definition of displacement increments, use only state=0 if you just want to get volmumes and porosity.")
+ .def("loadState",&TesselationWrapper::loadState,(boost::python::arg("inputFile")="state",boost::python::arg("state")=0,boost::python::arg("bz2")=true),"Load a file with positions to define state 0 or 1.")
+ .def("saveState",&TesselationWrapper::saveState,(boost::python::arg("outputFile")="state",boost::python::arg("state")=0,boost::python::arg("bz2")=true),"Save a file with positions, can be later reloaded in order to define state 0 or 1.")
+ .def("volume",&TesselationWrapper::Volume,(boost::python::arg("id")=0),"Returns the volume of Voronoi's cell of a sphere.")
+ .def("defToVtk",&TesselationWrapper::defToVtk,(boost::python::arg("outputFile")="def.vtk"),"Write local deformations in vtk format from states 0 and 1.")
+ .def("defToVtkFromStates",&TesselationWrapper::defToVtkFromStates,(boost::python::arg("input1")="state1",boost::python::arg("input2")="state2",boost::python::arg("outputFile")="def.vtk",boost::python::arg("bz2")=true),"Write local deformations in vtk format from state files (since the file format is very special, consider using defToVtkFromPositions if the input files were not generated by TesselationWrapper).")
+ .def("defToVtkFromPositions",&TesselationWrapper::defToVtkFromPositions,(boost::python::arg("input1")="pos1",boost::python::arg("input2")="pos2",boost::python::arg("outputFile")="def.vtk",boost::python::arg("bz2")=false),"Write local deformations in vtk format from positions files (one sphere per line, with x,y,z,rad separated by spaces).")
.def("computeVolumes",&TesselationWrapper::computeVolumes,"compute volumes of all Voronoi's cells.")
- .def("getVolPoroDef",&TesselationWrapper::getVolPoroDef,(python::arg("deformation")=false),"Return a table with per-sphere computed quantities. Include deformations on the increment defined by states 0 and 1 if deformation=True (make sure to define states 0 and 1 consistently).")
+ .def("getVolPoroDef",&TesselationWrapper::getVolPoroDef,(boost::python::arg("deformation")=false),"Return a table with per-sphere computed quantities. Include deformations on the increment defined by states 0 and 1 if deformation=True (make sure to define states 0 and 1 consistently).")
.def("computeDeformations",&TesselationWrapper::computeDeformations,"compute per-particle deformation. Get it with :yref:`TesselationWrapper::deformation` (id,i,j).")
- .def("deformation",&TesselationWrapper::deformation,(python::arg("id"),python::arg("i"),python::arg("j")),"Get particle deformation")
+ .def("deformation",&TesselationWrapper::deformation,(boost::python::arg("id"),boost::python::arg("i"),boost::python::arg("j")),"Get particle deformation")
);
DECLARE_LOGGER;
};
=== modified file 'pkg/dem/Tetra.cpp'
--- pkg/dem/Tetra.cpp 2013-10-04 12:04:43 +0000
+++ pkg/dem/Tetra.cpp 2014-05-23 13:05:19 +0000
@@ -956,14 +956,14 @@
FOREACH(const shared_ptr<Interaction>& I, *scene->interactions){
// normally, we would test isReal(), but TetraVolumetricLaw doesn't use phys at all
if (!I->geom) continue; // Ig2_Tetra_Tetra_TTetraGeom::go returned false for this interaction, skip it
- const shared_ptr<TTetraGeom>& contactGeom(dynamic_pointer_cast<TTetraGeom>(I->geom));
+ const shared_ptr<TTetraGeom>& contactGeom(boost::dynamic_pointer_cast<TTetraGeom>(I->geom));
if(!contactGeom) continue;
const Body::id_t idA=I->getId1(), idB=I->getId2();
const shared_ptr<Body>& A=Body::byId(idA), B=Body::byId(idB);
- const shared_ptr<ElastMat>& physA(dynamic_pointer_cast<ElastMat>(A->material));
- const shared_ptr<ElastMat>& physB(dynamic_pointer_cast<ElastMat>(B->material));
+ const shared_ptr<ElastMat>& physA(boost::dynamic_pointer_cast<ElastMat>(A->material));
+ const shared_ptr<ElastMat>& physB(boost::dynamic_pointer_cast<ElastMat>(B->material));
/* Cross-section is volumetrically equivalent to the penetration configuration */
@@ -1143,7 +1143,7 @@
Quaternionr TetrahedronWithLocalAxesPrincipal(shared_ptr<Body>& tetraBody){
//const shared_ptr<RigidBodyParameters>& rbp(YADE_PTR_CAST<RigidBodyParameters>(tetraBody->physicalParameters));
State* rbp=tetraBody->state.get();
- const shared_ptr<Tetra>& tMold(dynamic_pointer_cast<Tetra>(tetraBody->shape));
+ const shared_ptr<Tetra>& tMold(boost::dynamic_pointer_cast<Tetra>(tetraBody->shape));
#define v0 tMold->v[0]
#define v1 tMold->v[1]
=== modified file 'pkg/dem/TriaxialCompressionEngine.cpp'
--- pkg/dem/TriaxialCompressionEngine.cpp 2013-03-06 20:39:22 +0000
+++ pkg/dem/TriaxialCompressionEngine.cpp 2014-05-23 13:05:19 +0000
@@ -129,12 +129,12 @@
{
if(!noFiles){
string fileName = "./"+ Key + "_" + Phase1End + "_" +
- lexical_cast<string> ( scene->iter ) + "_" +
- lexical_cast<string> ( currentState ) + ".xml";
+ boost::lexical_cast<string> ( scene->iter ) + "_" +
+ boost::lexical_cast<string> ( currentState ) + ".xml";
LOG_INFO ( "saving snapshot: "<<fileName );
Omega::instance().saveSimulation ( fileName );
- fileName="./"+ Key + "_"+Phase1End+"_"+lexical_cast<string> ( scene->iter ) + "_" +
- lexical_cast<string> ( currentState ) +".spheres";
+ fileName="./"+ Key + "_"+Phase1End+"_"+boost::lexical_cast<string> ( scene->iter ) + "_" +
+ boost::lexical_cast<string> ( currentState ) +".spheres";
LOG_INFO ( "saving spheres: "<<fileName );
Shop::saveSpheresToFile ( fileName );
}
=== modified file 'pkg/dem/TriaxialStateRecorder.cpp'
--- pkg/dem/TriaxialStateRecorder.cpp 2013-02-04 18:23:35 +0000
+++ pkg/dem/TriaxialStateRecorder.cpp 2014-05-23 13:05:19 +0000
@@ -57,16 +57,16 @@
}
porosity = ( V - Vs ) /V;
- out << lexical_cast<string> ( scene->iter ) << " "
- << lexical_cast<string> ( triaxialStressController->stress[triaxialStressController->wall_right][0] ) << " "
- << lexical_cast<string> ( triaxialStressController->stress[triaxialStressController->wall_top][1] ) << " "
- << lexical_cast<string> ( triaxialStressController->stress[triaxialStressController->wall_front][2] ) << " "
- << lexical_cast<string> ( triaxialStressController->strain[0] ) << " "
- << lexical_cast<string> ( triaxialStressController->strain[1] ) << " "
- << lexical_cast<string> ( triaxialStressController->strain[2] ) << " "
- << lexical_cast<string> ( triaxialStressController->ComputeUnbalancedForce () ) << " "
- << lexical_cast<string> ( porosity ) << " "
- << lexical_cast<string> ( Shop::kineticEnergy() )
+ out << boost::lexical_cast<string> ( scene->iter ) << " "
+ << boost::lexical_cast<string> ( triaxialStressController->stress[triaxialStressController->wall_right][0] ) << " "
+ << boost::lexical_cast<string> ( triaxialStressController->stress[triaxialStressController->wall_top][1] ) << " "
+ << boost::lexical_cast<string> ( triaxialStressController->stress[triaxialStressController->wall_front][2] ) << " "
+ << boost::lexical_cast<string> ( triaxialStressController->strain[0] ) << " "
+ << boost::lexical_cast<string> ( triaxialStressController->strain[1] ) << " "
+ << boost::lexical_cast<string> ( triaxialStressController->strain[2] ) << " "
+ << boost::lexical_cast<string> ( triaxialStressController->ComputeUnbalancedForce () ) << " "
+ << boost::lexical_cast<string> ( porosity ) << " "
+ << boost::lexical_cast<string> ( Shop::kineticEnergy() )
<< endl;
}
=== modified file 'pkg/dem/TriaxialStressController.hpp'
--- pkg/dem/TriaxialStressController.hpp 2014-03-24 12:23:56 +0000
+++ pkg/dem/TriaxialStressController.hpp 2014-05-23 13:05:19 +0000
@@ -146,7 +146,7 @@
.def_readonly("max_vel1",&TriaxialStressController::max_vel1,"see :yref:`TriaxialStressController::max_vel` |ycomp|")
.def_readonly("max_vel2",&TriaxialStressController::max_vel2,"see :yref:`TriaxialStressController::max_vel` |ycomp|")
.def_readonly("max_vel3",&TriaxialStressController::max_vel3,"see :yref:`TriaxialStressController::max_vel` |ycomp|")
- .def("stress",&TriaxialStressController::getStress,(python::arg("id")),"Return the mean stress vector acting on boundary 'id', with 'id' between 0 and 5.")
+ .def("stress",&TriaxialStressController::getStress,(boost::python::arg("id")),"Return the mean stress vector acting on boundary 'id', with 'id' between 0 and 5.")
)
DECLARE_LOGGER;
};
=== modified file 'pkg/dem/TriaxialTest.cpp'
--- pkg/dem/TriaxialTest.cpp 2013-03-06 20:39:22 +0000
+++ pkg/dem/TriaxialTest.cpp 2014-05-23 13:05:19 +0000
@@ -56,7 +56,6 @@
CREATE_LOGGER(TriaxialTest);
YADE_PLUGIN((TriaxialTest));
-using namespace boost;
using namespace std;
TriaxialTest::~TriaxialTest () {}
@@ -91,10 +90,10 @@
upperCorner=lowerCorner+dimensions;
num=sphere_pack.makeCloud(lowerCorner,upperCorner,radiusMean,radiusStdDev,numberOfGrains);
}
- message+="Generated a sample with " + lexical_cast<string>(num) + " spheres inside box of dimensions: ("
- + lexical_cast<string>(upperCorner[0]-lowerCorner[0]) + ","
- + lexical_cast<string>(upperCorner[1]-lowerCorner[1]) + ","
- + lexical_cast<string>(upperCorner[2]-lowerCorner[2]) + ").";}
+ message+="Generated a sample with " + boost::lexical_cast<string>(num) + " spheres inside box of dimensions: ("
+ + boost::lexical_cast<string>(upperCorner[0]-lowerCorner[0]) + ","
+ + boost::lexical_cast<string>(upperCorner[1]-lowerCorner[1]) + ","
+ + boost::lexical_cast<string>(upperCorner[2]-lowerCorner[2]) + ").";}
else {
if(radiusMean>0) LOG_WARN("radiusMean ignored, since importFilename specified.");
sphere_pack.fromFile(importFilename);
=== modified file 'pkg/dem/UniaxialStrainer.cpp'
--- pkg/dem/UniaxialStrainer.cpp 2014-04-02 07:44:58 +0000
+++ pkg/dem/UniaxialStrainer.cpp 2014-05-23 13:05:19 +0000
@@ -37,7 +37,7 @@
originalLength=axisCoord(posIds[0])-axisCoord(negIds[0]);
LOG_DEBUG("Reference particles: positive #"<<posIds[0]<<" at "<<axisCoord(posIds[0])<<"; negative #"<<negIds[0]<<" at "<<axisCoord(negIds[0]));
LOG_INFO("Setting initial length to "<<originalLength<<" (between #"<<negIds[0]<<" and #"<<posIds[0]<<")");
- if(originalLength<=0) throw runtime_error(("UniaxialStrainer: Initial length is negative or zero (swapped reference particles?)! "+lexical_cast<string>(originalLength)).c_str());
+ if(originalLength<=0) throw runtime_error(("UniaxialStrainer: Initial length is negative or zero (swapped reference particles?)! "+boost::lexical_cast<string>(originalLength)).c_str());
/* this happens is nan propagates from e.g. brefcom consitutive law in case 2 bodies have _exactly_ the same position
* (the the normal strain is 0./0.=nan). That is an user's error, however and should not happen. */
if(isnan(originalLength)) throw logic_error("UniaxialStrainer: Initial length is NaN!");
@@ -67,7 +67,7 @@
case -1: v0=-absSpeed; v1=0; break;
case 0: v0=-absSpeed/2; v1=absSpeed/2; break;
case 1: v0=0; v1=absSpeed; break;
- default: throw std::invalid_argument(("UniaxialStrainer: unknown asymmetry value "+lexical_cast<string>(asymmetry)+" (should be -1,0,1)").c_str());
+ default: throw std::invalid_argument(("UniaxialStrainer: unknown asymmetry value "+boost::lexical_cast<string>(asymmetry)+" (should be -1,0,1)").c_str());
}
assert(p1>p0);
// set speeds for particles on the boundary
=== modified file 'pkg/dem/VTKRecorder.cpp'
--- pkg/dem/VTKRecorder.cpp 2014-05-08 05:57:04 +0000
+++ pkg/dem/VTKRecorder.cpp 2014-05-23 13:05:19 +0000
@@ -647,7 +647,7 @@
vtkSmartPointer<vtkXMLUnstructuredGridWriter> writer = vtkSmartPointer<vtkXMLUnstructuredGridWriter>::New();
if(compress) writer->SetCompressor(compressor);
if(ascii) writer->SetDataModeToAscii();
- string fn=fileName+"spheres."+lexical_cast<string>(scene->iter)+".vtu";
+ string fn=fileName+"spheres."+boost::lexical_cast<string>(scene->iter)+".vtu";
writer->SetFileName(fn.c_str());
#ifdef YADE_VTK6
writer->SetInputData(spheresUg);
@@ -675,7 +675,7 @@
vtkSmartPointer<vtkXMLUnstructuredGridWriter> writer = vtkSmartPointer<vtkXMLUnstructuredGridWriter>::New();
if(compress) writer->SetCompressor(compressor);
if(ascii) writer->SetDataModeToAscii();
- string fn=fileName+"facets."+lexical_cast<string>(scene->iter)+".vtu";
+ string fn=fileName+"facets."+boost::lexical_cast<string>(scene->iter)+".vtu";
writer->SetFileName(fn.c_str());
#ifdef YADE_VTK6
writer->SetInputData(facetsUg);
@@ -703,7 +703,7 @@
vtkSmartPointer<vtkXMLUnstructuredGridWriter> writer = vtkSmartPointer<vtkXMLUnstructuredGridWriter>::New();
if(compress) writer->SetCompressor(compressor);
if(ascii) writer->SetDataModeToAscii();
- string fn=fileName+"boxes."+lexical_cast<string>(scene->iter)+".vtu";
+ string fn=fileName+"boxes."+boost::lexical_cast<string>(scene->iter)+".vtu";
writer->SetFileName(fn.c_str());
#ifdef YADE_VTK6
writer->SetInputData(boxesUg);
@@ -740,7 +740,7 @@
vtkSmartPointer<vtkXMLPolyDataWriter> writer = vtkSmartPointer<vtkXMLPolyDataWriter>::New();
if(compress) writer->SetCompressor(compressor);
if(ascii) writer->SetDataModeToAscii();
- string fn=fileName+"intrs."+lexical_cast<string>(scene->iter)+".vtp";
+ string fn=fileName+"intrs."+boost::lexical_cast<string>(scene->iter)+".vtp";
writer->SetFileName(fn.c_str());
#ifdef YADE_VTK6
writer->SetInputData(intrPd);
@@ -761,7 +761,7 @@
vtkSmartPointer<vtkXMLUnstructuredGridWriter> writer = vtkSmartPointer<vtkXMLUnstructuredGridWriter>::New();
if(compress) writer->SetCompressor(compressor);
if(ascii) writer->SetDataModeToAscii();
- string fn=fileName+"pericell."+lexical_cast<string>(scene->iter)+".vtu";
+ string fn=fileName+"pericell."+boost::lexical_cast<string>(scene->iter)+".vtu";
writer->SetFileName(fn.c_str());
#ifdef YADE_VTK6
writer->SetInputData(pericellUg);
@@ -818,7 +818,7 @@
vtkSmartPointer<vtkXMLUnstructuredGridWriter> writer = vtkSmartPointer<vtkXMLUnstructuredGridWriter>::New();
if(compress) writer->SetCompressor(compressor);
if(ascii) writer->SetDataModeToAscii();
- string fn=fileName+"cracks."+lexical_cast<string>(scene->iter)+".vtu";
+ string fn=fileName+"cracks."+boost::lexical_cast<string>(scene->iter)+".vtu";
writer->SetFileName(fn.c_str());
#ifdef YADE_VTK6
writer->SetInputData(crackUg);
@@ -835,7 +835,7 @@
// crackUgNew->GetPointData()->AddArray(crackSizeNew);
// crackUgNew->GetPointData()->AddArray(crackNormNew); //same remark about the orientation...
//
-// fn=fileName+"newcracks."+lexical_cast<string>(scene->iter)+".vtu";
+// fn=fileName+"newcracks."+boost::lexical_cast<string>(scene->iter)+".vtu";
// writer->SetFileName(fn.c_str());
// #ifdef YADE_VTK6
// writer->SetInputData(crackUgNew);
@@ -855,7 +855,7 @@
if(recActive[REC_PERICELL]) multiblockDataset->SetBlock(i++,pericellUg);
vtkSmartPointer<vtkXMLMultiBlockDataWriter> writer = vtkSmartPointer<vtkXMLMultiBlockDataWriter>::New();
if(ascii) writer->SetDataModeToAscii();
- string fn=fileName+lexical_cast<string>(scene->iter)+".vtm";
+ string fn=fileName+boost::lexical_cast<string>(scene->iter)+".vtm";
writer->SetFileName(fn.c_str());
#ifdef YADE_VTK6
writer->SetInputData(multiblockDataset);
=== modified file 'pkg/dem/ViscoelasticCapillarPM.hpp'
--- pkg/dem/ViscoelasticCapillarPM.hpp 2014-05-08 05:57:04 +0000
+++ pkg/dem/ViscoelasticCapillarPM.hpp 2014-05-23 13:20:43 +0000
@@ -6,9 +6,9 @@
virtual ~ViscElCapMat();
YADE_CLASS_BASE_DOC_ATTRS_CTOR(ViscElCapMat,ViscElMat,"Material for extended viscoelastic model of contact with capillary parameters.",
((bool,Capillar,false,,"True, if capillar forces need to be added."))
- ((Real,Vb,NaN,,"Liquid bridge volume [m^3]"))
- ((Real,gamma,NaN,,"Surface tension [N/m]"))
- ((Real,theta,NaN,,"Contact angle [°]"))
+ ((Real,Vb,0.0,,"Liquid bridge volume [m^3]"))
+ ((Real,gamma,0.0,,"Surface tension [N/m]"))
+ ((Real,theta,0.0,,"Contact angle [°]"))
((std::string,CapillarType,"",,"Different types of capillar interaction: Willett_numeric, Willett_analytic [Willett2000]_ , Weigert [Weigert1999]_ , Rabinovich [Rabinov2005]_ , Lambert (simplified, corrected Rabinovich model) [Lambert2008]_ ")),
createIndex();
);
@@ -29,12 +29,12 @@
((bool,liqBridgeCreated,false,,"Whether liquid bridge was created, only after a normal contact of spheres"))
((bool,liqBridgeActive,false,, "Whether liquid bridge is active at the moment"))
((Real,sCrit,false,,"Critical bridge length [m]"))
- ((Real,Vb,NaN,,"Liquid bridge volume [m^3]"))
- ((Real,gamma,NaN,,"Surface tension [N/m]"))
- ((Real,theta,NaN,,"Contact angle [rad]"))
+ ((Real,Vb,0.0,,"Liquid bridge volume [m^3]"))
+ ((Real,gamma,0.0,,"Surface tension [N/m]"))
+ ((Real,theta,0.0,,"Contact angle [rad]"))
((CapType,CapillarType,None_Capillar,,"Different types of capillar interaction: Willett_numeric, Willett_analytic, Weigert, Rabinovich, Lambert, Soulie"))
#ifdef YADE_LIQMIGRATION
- ((Real,Vmax,-1,,"Maximal liquid bridge volume [m^3]"))
+ ((Real,Vmax,0.0,,"Maximal liquid bridge volume [m^3]"))
#endif
,
createIndex();
@@ -97,8 +97,8 @@
((Real,vMaxCoef,0.03,, "Coefficient for vMax, [-]."))
,/* ctor */
,/* py */
- .def("totalLiq",&LiqControl::totalLiqVol,(python::arg("mask")=0),"Return total volume of water in simulation.")
- .def("liqBody",&LiqControl::liqVolBody,(python::arg("id")=-1),"Return total volume of water in body.")
+ .def("totalLiq",&LiqControl::totalLiqVol,(boost::python::arg("mask")=0),"Return total volume of water in simulation.")
+ .def("liqBody",&LiqControl::liqVolBody,(boost::python::arg("id")=-1),"Return total volume of water in body.")
);
};
=== modified file 'pkg/pfv/DummyFlowEngine.cpp'
--- pkg/pfv/DummyFlowEngine.cpp 2014-04-03 16:45:33 +0000
+++ pkg/pfv/DummyFlowEngine.cpp 2014-05-23 13:20:43 +0000
@@ -48,7 +48,7 @@
((Real, myNewAttribute, 0,,"useless example"))
,/*DummyFlowEngineT()*/,
,
- .def("fancyFunction",&DummyFlowEngine::fancyFunction,(python::arg("what")=0),"test function")
+ .def("fancyFunction",&DummyFlowEngine::fancyFunction,(boost::python::arg("what")=0),"test function")
)
DECLARE_LOGGER;
};
@@ -57,4 +57,4 @@
void DummyFlowEngine::fancyFunction(Real what) {cerr<<"yes, I'm a new function"<<end;}
#undef TEMPLATE_FLOW_NAME DummyFlowEngineT //To be sure it will not conflict, maybe not needed
-#endif //DummyFLOW
\ No newline at end of file
+#endif //DummyFLOW
=== modified file 'pkg/pfv/FlowEngine.hpp'
--- pkg/pfv/FlowEngine.hpp 2014-04-24 21:37:44 +0000
+++ pkg/pfv/FlowEngine.hpp 2014-05-23 13:05:19 +0000
@@ -161,13 +161,13 @@
return (solver->onlySpheresInteractions.size());}
int onlySpheresInteractions(unsigned int interaction) {
return (solver->onlySpheresInteractions[interaction]);}
- python::list getConstrictions(bool all) {
- vector<Real> csd=solver->getConstrictions(); python::list pycsd;
+ boost::python::list getConstrictions(bool all) {
+ vector<Real> csd=solver->getConstrictions(); boost::python::list pycsd;
for (unsigned int k=0;k<csd.size();k++) if ((all && csd[k]!=0) || csd[k]>0) pycsd.append(csd[k]); return pycsd;}
- python::list getConstrictionsFull(bool all) {
- vector<Constriction> csd=solver->getConstrictionsFull(); python::list pycsd;
+ boost::python::list getConstrictionsFull(bool all) {
+ vector<Constriction> csd=solver->getConstrictionsFull(); boost::python::list pycsd;
for (unsigned int k=0;k<csd.size();k++) if ((all && csd[k].second[0]!=0) || csd[k].second[0]>0) {
- python::list cons;
+ boost::python::list cons;
cons.append(csd[k].first.first);
cons.append(csd[k].first.second);
cons.append(csd[k].second[0]);
@@ -195,8 +195,8 @@
double getPorePressure(Vector3r pos){return solver->getPorePressure(pos[0], pos[1], pos[2]);}
int getCell(double posX, double posY, double posZ){return solver->getCell(posX, posY, posZ);}
unsigned int nCells(){return solver->T[solver->currentTes].cellHandles.size();}
- python::list getVertices(unsigned int id){
- python::list ids;
+ boost::python::list getVertices(unsigned int id){
+ boost::python::list ids;
if (id>=solver->T[solver->currentTes].cellHandles.size()) {LOG_ERROR("id out of range, max value is "<<solver->T[solver->currentTes].cellHandles.size()); return ids;}
for (unsigned int i=0;i<4;i++) ids.append(solver->T[solver->currentTes].cellHandles[id]->vertex(i)->info().id());
return ids;
@@ -310,49 +310,49 @@
ellapsedIter=0;
metisForced=false;
,
- .def("imposeFlux",&TemplateFlowEngine::imposeFlux,(python::arg("pos"),python::arg("p")),"Impose incoming flux in boundary cell of location 'pos'.")
- .def("imposePressure",&TemplateFlowEngine::imposePressure,(python::arg("pos"),python::arg("p")),"Impose pressure in cell of location 'pos'. The index of the condition is returned (for multiple imposed pressures at different points).")
- .def("setImposedPressure",&TemplateFlowEngine::setImposedPressure,(python::arg("cond"),python::arg("p")),"Set pressure value at the point indexed 'cond'.")
+ .def("imposeFlux",&TemplateFlowEngine::imposeFlux,(boost::python::arg("pos"),boost::python::arg("p")),"Impose incoming flux in boundary cell of location 'pos'.")
+ .def("imposePressure",&TemplateFlowEngine::imposePressure,(boost::python::arg("pos"),boost::python::arg("p")),"Impose pressure in cell of location 'pos'. The index of the condition is returned (for multiple imposed pressures at different points).")
+ .def("setImposedPressure",&TemplateFlowEngine::setImposedPressure,(boost::python::arg("cond"),boost::python::arg("p")),"Set pressure value at the point indexed 'cond'.")
.def("clearImposedPressure",&TemplateFlowEngine::clearImposedPressure,"Clear the list of points with pressure imposed.")
.def("clearImposedFlux",&TemplateFlowEngine::clearImposedFlux,"Clear the list of points with flux imposed.")
- .def("getCellFlux",&TemplateFlowEngine::getCellFlux,(python::arg("cond")),"Get influx in cell associated to an imposed P (indexed using 'cond').")
- .def("getBoundaryFlux",&TemplateFlowEngine::getBoundaryFlux,(python::arg("boundary")),"Get total flux through boundary defined by its body id.\n\n.. note:: The flux may be not zero even for no-flow condition. This artifact comes from cells which are incident to two or more boundaries (along the edges of the sample, typically). Such flux evaluation on impermeable boundary is just irrelevant, it does not imply that the boundary condition is not applied properly.")
- .def("getConstrictions",&TemplateFlowEngine::getConstrictions,(python::arg("all")=true),"Get the list of constriction radii (inscribed circle) for all finite facets (if all==True) or all facets not incident to a virtual bounding sphere (if all==False). When all facets are returned, negative radii denote facet incident to one or more fictious spheres.")
- .def("getConstrictionsFull",&TemplateFlowEngine::getConstrictionsFull,(python::arg("all")=true),"Get the list of constrictions (inscribed circle) for all finite facets (if all==True), or all facets not incident to a fictious bounding sphere (if all==False). When all facets are returned, negative radii denote facet incident to one or more fictious spheres. The constrictions are returned in the format {{cell1,cell2}{rad,nx,ny,nz}}")
+ .def("getCellFlux",&TemplateFlowEngine::getCellFlux,(boost::python::arg("cond")),"Get influx in cell associated to an imposed P (indexed using 'cond').")
+ .def("getBoundaryFlux",&TemplateFlowEngine::getBoundaryFlux,(boost::python::arg("boundary")),"Get total flux through boundary defined by its body id.\n\n.. note:: The flux may be not zero even for no-flow condition. This artifact comes from cells which are incident to two or more boundaries (along the edges of the sample, typically). Such flux evaluation on impermeable boundary is just irrelevant, it does not imply that the boundary condition is not applied properly.")
+ .def("getConstrictions",&TemplateFlowEngine::getConstrictions,(boost::python::arg("all")=true),"Get the list of constriction radii (inscribed circle) for all finite facets (if all==True) or all facets not incident to a virtual bounding sphere (if all==False). When all facets are returned, negative radii denote facet incident to one or more fictious spheres.")
+ .def("getConstrictionsFull",&TemplateFlowEngine::getConstrictionsFull,(boost::python::arg("all")=true),"Get the list of constrictions (inscribed circle) for all finite facets (if all==True), or all facets not incident to a fictious bounding sphere (if all==False). When all facets are returned, negative radii denote facet incident to one or more fictious spheres. The constrictions are returned in the format {{cell1,cell2}{rad,nx,ny,nz}}")
.def("edgeSize",&TemplateFlowEngine::edgeSize,"Return the number of interactions.")
.def("OSI",&TemplateFlowEngine::OSI,"Return the number of interactions only between spheres.")
- .def("saveVtk",&TemplateFlowEngine::saveVtk,(python::arg("folder")="./VTK"),"Save pressure field in vtk format. Specify a folder name for output.")
- .def("avFlVelOnSph",&TemplateFlowEngine::avFlVelOnSph,(python::arg("idSph")),"compute a sphere-centered average fluid velocity")
- .def("fluidForce",&TemplateFlowEngine::fluidForce,(python::arg("idSph")),"Return the fluid force on sphere idSph.")
- .def("shearLubForce",&TemplateFlowEngine::shearLubForce,(python::arg("idSph")),"Return the shear lubrication force on sphere idSph.")
- .def("shearLubTorque",&TemplateFlowEngine::shearLubTorque,(python::arg("idSph")),"Return the shear lubrication torque on sphere idSph.")
- .def("normalLubForce",&TemplateFlowEngine::normalLubForce,(python::arg("idSph")),"Return the normal lubrication force on sphere idSph.")
- .def("bodyShearLubStress",&TemplateFlowEngine::bodyShearLubStress,(python::arg("idSph")),"Return the shear lubrication stress on sphere idSph.")
- .def("bodyNormalLubStress",&TemplateFlowEngine::bodyNormalLubStress,(python::arg("idSph")),"Return the normal lubrication stress on sphere idSph.")
- .def("shearVelocity",&TemplateFlowEngine::shearVelocity,(python::arg("idSph")),"Return the shear velocity of the interaction.")
- .def("normalVelocity",&TemplateFlowEngine::normalVelocity,(python::arg("idSph")),"Return the normal velocity of the interaction.")
- .def("normalVect",&TemplateFlowEngine::normalVect,(python::arg("idSph")),"Return the normal vector between particles.")
- .def("surfaceDistanceParticle",&TemplateFlowEngine::surfaceDistanceParticle,(python::arg("interaction")),"Return the distance between particles.")
- .def("onlySpheresInteractions",&TemplateFlowEngine::onlySpheresInteractions,(python::arg("interaction")),"Return the id of the interaction only between spheres.")
- .def("pressureProfile",&TemplateFlowEngine::pressureProfile,(python::arg("wallUpY"),python::arg("wallDownY")),"Measure pore pressure in 6 equally-spaced points along the height of the sample")
- .def("getPorePressure",&TemplateFlowEngine::getPorePressure,(python::arg("pos")),"Measure pore pressure in position pos[0],pos[1],pos[2]")
- .def("averageSlicePressure",&TemplateFlowEngine::averageSlicePressure,(python::arg("posY")),"Measure slice-averaged pore pressure at height posY")
+ .def("saveVtk",&TemplateFlowEngine::saveVtk,(boost::python::arg("folder")="./VTK"),"Save pressure field in vtk format. Specify a folder name for output.")
+ .def("avFlVelOnSph",&TemplateFlowEngine::avFlVelOnSph,(boost::python::arg("idSph")),"compute a sphere-centered average fluid velocity")
+ .def("fluidForce",&TemplateFlowEngine::fluidForce,(boost::python::arg("idSph")),"Return the fluid force on sphere idSph.")
+ .def("shearLubForce",&TemplateFlowEngine::shearLubForce,(boost::python::arg("idSph")),"Return the shear lubrication force on sphere idSph.")
+ .def("shearLubTorque",&TemplateFlowEngine::shearLubTorque,(boost::python::arg("idSph")),"Return the shear lubrication torque on sphere idSph.")
+ .def("normalLubForce",&TemplateFlowEngine::normalLubForce,(boost::python::arg("idSph")),"Return the normal lubrication force on sphere idSph.")
+ .def("bodyShearLubStress",&TemplateFlowEngine::bodyShearLubStress,(boost::python::arg("idSph")),"Return the shear lubrication stress on sphere idSph.")
+ .def("bodyNormalLubStress",&TemplateFlowEngine::bodyNormalLubStress,(boost::python::arg("idSph")),"Return the normal lubrication stress on sphere idSph.")
+ .def("shearVelocity",&TemplateFlowEngine::shearVelocity,(boost::python::arg("idSph")),"Return the shear velocity of the interaction.")
+ .def("normalVelocity",&TemplateFlowEngine::normalVelocity,(boost::python::arg("idSph")),"Return the normal velocity of the interaction.")
+ .def("normalVect",&TemplateFlowEngine::normalVect,(boost::python::arg("idSph")),"Return the normal vector between particles.")
+ .def("surfaceDistanceParticle",&TemplateFlowEngine::surfaceDistanceParticle,(boost::python::arg("interaction")),"Return the distance between particles.")
+ .def("onlySpheresInteractions",&TemplateFlowEngine::onlySpheresInteractions,(boost::python::arg("interaction")),"Return the id of the interaction only between spheres.")
+ .def("pressureProfile",&TemplateFlowEngine::pressureProfile,(boost::python::arg("wallUpY"),boost::python::arg("wallDownY")),"Measure pore pressure in 6 equally-spaced points along the height of the sample")
+ .def("getPorePressure",&TemplateFlowEngine::getPorePressure,(boost::python::arg("pos")),"Measure pore pressure in position pos[0],pos[1],pos[2]")
+ .def("averageSlicePressure",&TemplateFlowEngine::averageSlicePressure,(boost::python::arg("posY")),"Measure slice-averaged pore pressure at height posY")
.def("averagePressure",&TemplateFlowEngine::averagePressure,"Measure averaged pore pressure in the entire volume")
.def("updateBCs",&TemplateFlowEngine::updateBCs,"tells the engine to update it's boundary conditions before running (especially useful when changing boundary pressure - should not be needed for point-wise imposed pressure)")
.def("emulateAction",&TemplateFlowEngine::emulateAction,"get scene and run action (may be used to manipulate an engine outside the timestepping loop).")
- .def("getCell",&TemplateFlowEngine::getCell,(python::arg("pos")),"get id of the cell containing (X,Y,Z).")
+ .def("getCell",&TemplateFlowEngine::getCell,(boost::python::arg("pos")),"get id of the cell containing (X,Y,Z).")
.def("nCells",&TemplateFlowEngine::nCells,"get the total number of finite cells in the triangulation.")
- .def("getVertices",&TemplateFlowEngine::getVertices,(python::arg("id")),"get the vertices of a cell")
+ .def("getVertices",&TemplateFlowEngine::getVertices,(boost::python::arg("id")),"get the vertices of a cell")
#ifdef LINSOLV
- .def("exportMatrix",&TemplateFlowEngine::exportMatrix,(python::arg("filename")="matrix"),"Export system matrix to a file with all entries (even zeros will displayed).")
- .def("exportTriplets",&TemplateFlowEngine::exportTriplets,(python::arg("filename")="triplets"),"Export system matrix to a file with only non-zero entries.")
+ .def("exportMatrix",&TemplateFlowEngine::exportMatrix,(boost::python::arg("filename")="matrix"),"Export system matrix to a file with all entries (even zeros will displayed).")
+ .def("exportTriplets",&TemplateFlowEngine::exportTriplets,(boost::python::arg("filename")="triplets"),"Export system matrix to a file with only non-zero entries.")
.def("cholmodStats",&TemplateFlowEngine::cholmodStats,"get statistics of cholmod solver activity")
.def("metisUsed",&TemplateFlowEngine::metisUsed,"check wether metis lib is effectively used")
.add_property("forceMetis",&TemplateFlowEngine::getForceMetis,&TemplateFlowEngine::setForceMetis,"If true, METIS is used for matrix preconditioning, else Cholmod is free to choose the best method (which may be METIS to, depending on the matrix). See ``nmethods`` in Cholmod documentation")
#endif
.def("compTessVolumes",&TemplateFlowEngine::compTessVolumes,"Like TesselationWrapper::computeVolumes()")
- .def("volume",&TemplateFlowEngine::getVolume,(python::arg("id")=0),"Returns the volume of Voronoi's cell of a sphere.")
+ .def("volume",&TemplateFlowEngine::getVolume,(boost::python::arg("id")=0),"Returns the volume of Voronoi's cell of a sphere.")
)
};
// Definition of functions in a separate file for clarity
=== modified file 'pkg/pfv/SoluteFlowEngine.cpp'
--- pkg/pfv/SoluteFlowEngine.cpp 2014-04-11 08:07:46 +0000
+++ pkg/pfv/SoluteFlowEngine.cpp 2014-05-23 13:20:43 +0000
@@ -46,10 +46,10 @@
///No additional variable yet, else input here
// ((Vector3r, gradP, Vector3r::Zero(),,"Macroscopic pressure gradient"))
,,,
- .def("soluteTransport",&SoluteFlowEngine::soluteTransport,(python::arg("deltatime"),python::arg("D")),"Solute transport (advection and diffusion) engine for diffusion use a diffusion coefficient (D) other than 0.")
- .def("getConcentration",&SoluteFlowEngine::getConcentration,(python::arg("id")),"get concentration of pore with ID")
- .def("insertConcentration",&SoluteFlowEngine::insertConcentration,(python::arg("id"),python::arg("conc")),"Insert Concentration (ID, Concentration)")
- .def("solute_BC",&SoluteFlowEngine::soluteBC,(python::arg("bc_id1"),python::arg("bc_id2"),python::arg("bc_concentration1"),python::arg("bc_concentration2"),python::arg("s")),"Enter X,Y,Z for concentration observation'.")
+ .def("soluteTransport",&SoluteFlowEngine::soluteTransport,(boost::python::arg("deltatime"),boost::python::arg("D")),"Solute transport (advection and diffusion) engine for diffusion use a diffusion coefficient (D) other than 0.")
+ .def("getConcentration",&SoluteFlowEngine::getConcentration,(boost::python::arg("id")),"get concentration of pore with ID")
+ .def("insertConcentration",&SoluteFlowEngine::insertConcentration,(boost::python::arg("id"),boost::python::arg("conc")),"Insert Concentration (ID, Concentration)")
+ .def("solute_BC",&SoluteFlowEngine::soluteBC,(boost::python::arg("bc_id1"),boost::python::arg("bc_id2"),boost::python::arg("bc_concentration1"),boost::python::arg("bc_concentration2"),boost::python::arg("s")),"Enter X,Y,Z for concentration observation'.")
//I guess there is getConcentrationPlane missing here, but it is not on github
)
};
=== modified file 'py/WeightedAverage2d.cpp'
--- py/WeightedAverage2d.cpp 2010-11-07 11:46:20 +0000
+++ py/WeightedAverage2d.cpp 2014-05-23 13:03:50 +0000
@@ -17,7 +17,7 @@
BOOST_PYTHON_MODULE(WeightedAverage2d)
{
boost::python::scope().attr("__doc__")="Smoothing (2d gauss-weighted average) for postprocessing scalars in 2d.";
- boost::python::class_<pyGaussAverage>("GaussAverage",python::init<python::tuple,python::tuple,python::tuple,Real,python::optional<Real> >(python::args("min","max","nCells","stDev","relThreshold"),"Create empty container for data, which can be added using add and later retrieved using avg."))
+ boost::python::class_<pyGaussAverage>("GaussAverage",boost::python::init<boost::python::tuple,boost::python::tuple,boost::python::tuple,Real,boost::python::optional<Real> >(boost::python::args("min","max","nCells","stDev","relThreshold"),"Create empty container for data, which can be added using add and later retrieved using avg."))
.def("add",&pyGaussAverage::addPt)
.def("avg",&pyGaussAverage::avg)
.def("avgPerUnitArea",&pyGaussAverage::avgPerUnitArea)
=== modified file 'py/_polyhedra_utils.cpp'
--- py/_polyhedra_utils.cpp 2014-04-02 15:19:41 +0000
+++ py/_polyhedra_utils.cpp 2014-05-23 13:05:19 +0000
@@ -87,24 +87,23 @@
Real dt=std::numeric_limits<Real>::infinity();
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
if(!b || !b->material || !b->shape) continue;
- shared_ptr<Sphere> s=dynamic_pointer_cast<Sphere>(b->shape);
- shared_ptr<Polyhedra> p=dynamic_pointer_cast<Polyhedra>(b->shape);
+ shared_ptr<Sphere> s=boost::dynamic_pointer_cast<Sphere>(b->shape);
+ shared_ptr<Polyhedra> p=boost::dynamic_pointer_cast<Polyhedra>(b->shape);
if(!s && !p) continue;
if(!p){
//spheres
- shared_ptr<ElastMat> ebp=dynamic_pointer_cast<ElastMat>(b->material);
+ shared_ptr<ElastMat> ebp=boost::dynamic_pointer_cast<ElastMat>(b->material);
if(!ebp) continue;
Real density=b->state->mass/((4./3.)*Mathr::PI*pow(s->radius,3));
dt=min(dt,s->radius/sqrt(ebp->young/density));
}else{
//polyhedrons
- shared_ptr<PolyhedraMat> ebp=dynamic_pointer_cast<PolyhedraMat>(b->material);
+ shared_ptr<PolyhedraMat> ebp=boost::dynamic_pointer_cast<PolyhedraMat>(b->material);
if(!ebp) continue;
Real density=b->state->mass/p->GetVolume();
//get equivalent radius and use same equation as for sphere
Real equi_radius=pow(p->GetVolume()/((4./3.)*Mathr::PI),1./3.);
- //dt=min(dt,equi_radius/sqrt(ebp->Kn*equi_radius/density));
- dt=min(dt,equi_radius/sqrt(ebp->Kn/equi_radius/density));
+ dt=min(dt,equi_radius/sqrt(ebp->Kn*equi_radius/density));
}
}
if (dt==std::numeric_limits<Real>::infinity()) {
@@ -164,7 +163,7 @@
double total_volume = 0;
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
if(!b || !b->shape) continue;
- shared_ptr<Polyhedra> p=dynamic_pointer_cast<Polyhedra>(b->shape);
+ shared_ptr<Polyhedra> p=boost::dynamic_pointer_cast<Polyhedra>(b->shape);
if(p){
sieve_volume.push_back(std::pair<double,double>(SieveSize(p),p->GetVolume()));
total_volume += p->GetVolume();
@@ -192,7 +191,7 @@
myfile.open ("sizes.dat");
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
if(!b || !b->shape) continue;
- shared_ptr<Polyhedra> p=dynamic_pointer_cast<Polyhedra>(b->shape);
+ shared_ptr<Polyhedra> p=boost::dynamic_pointer_cast<Polyhedra>(b->shape);
if(p){
myfile << SizeOfPolyhedra(p) << endl;
}
@@ -326,10 +325,182 @@
return v;
}
+//**************************************************************************
+/* Generate truncated icosahedron*/
+vector<Vector3r> TruncIcosaHedPoints(Vector3r radii){
+ vector<Vector3r> v;
+
+ double p = (1.+sqrt(5.))/2.;
+ Vector3r f,c,b;
+ f = radii/sqrt(9.*p + 1.);
+ vector<Vector3r> A,B;
+ A.push_back(Vector3r(0.,1.,3.*p)); A.push_back(Vector3r(2.,1.+2.*p,p)); A.push_back(Vector3r(1.,2.+p,2.*p));
+ for(int i=0;i<(int) A.size() ;i++){
+ B.clear();
+ c = Vector3r(A[i][0]*f[0],A[i][1]*f[1],A[i][2]*f[2]);
+ B.push_back(c); B.push_back(Vector3r(c[1],c[2],c[0])); B.push_back(Vector3r(c[2],c[0],c[1]));
+ for(int j=0;j<(int) B.size() ;j++){
+ b = B[j];
+ v.push_back(b);
+ if (b[0] != 0.){
+ v.push_back(Vector3r(-b[0], b[1], b[2]));
+ if (b[1] != 0.){
+ v.push_back(Vector3r(-b[0],-b[1], b[2]));
+ if (b[2] != 0.) v.push_back(Vector3r(-b[0],-b[1],-b[2]));
+ }
+ if (b[2] != 0.) v.push_back(Vector3r(-b[0], b[1],-b[2]));
+ }
+ if (b[1] != 0.){
+ v.push_back(Vector3r( b[0],-b[1], b[2]));
+ if (b[2] != 0.) v.push_back(Vector3r( b[0],-b[1],-b[2]));
+ }
+ if (b[2] != 0.) v.push_back(Vector3r( b[0], b[1],-b[2]));
+ }
+ }
+ return v;
+}
+
+//**************************************************************************
+/* Generate SnubCube*/
+vector<Vector3r> SnubCubePoints(Vector3r radii){
+ vector<Vector3r> v;
+
+ double c1 = 0.337754;
+ double c2 = 1.14261;
+ double c3 = 0.621226;
+ Vector3r f,b;
+ f = radii/1.3437133737446;
+ vector<Vector3r> A;
+ A.push_back(Vector3r(c2,c1,c3)); A.push_back(Vector3r(c1,c3,c2)); A.push_back(Vector3r(c3,c2,c1));
+ A.push_back(Vector3r(-c1,-c2,-c3)); A.push_back(Vector3r(-c2,-c3,-c1)); A.push_back(Vector3r(-c3,-c1,-c2));
+ for(int i=0;i<(int) A.size();i++){
+ b = Vector3r(A[i][0]*f[0],A[i][1]*f[1],A[i][2]*f[2]);
+ v.push_back(b);
+ v.push_back(Vector3r(-b[0],-b[1], b[2]));
+ v.push_back(Vector3r(-b[0], b[1],-b[2]));
+ v.push_back(Vector3r( b[0],-b[1],-b[2]));
+ }
+ return v;
+}
+
+//**************************************************************************
+/* Generate ball*/
+vector<Vector3r> BallPoints(Vector3r radii, int NumFacets,int seed){
+ vector<Vector3r> v;
+ if (NumFacets == 60) v = TruncIcosaHedPoints(radii);
+ if (NumFacets == 24) v = SnubCubePoints(radii);
+ else{
+ double inc = Mathr::PI * (3. - pow(5.,0.5));
+ double off = 2. / double(NumFacets);
+ double y,r,phi;
+ for(int k=0; k<NumFacets; k++){
+ y = double(k) * off - 1. + (off / 2.);
+ r = pow(1. - y*y,0.5);
+ phi = double(k) * inc;
+ v.push_back(Vector3r(cos(phi)*r*radii[0], y*radii[1], sin(phi)*r*radii[2]));
+ }
+ }
+
+ // randomly rotate
+ srand(seed);
+ Quaternionr Rot(double(rand())/RAND_MAX,double(rand())/RAND_MAX,double(rand())/RAND_MAX,double(rand())/RAND_MAX);
+ Rot.normalize();
+ for(int i=0; i< (int) v.size();i++) {
+ v[i] = Rot*(Vector3r(v[i][0],v[i][1],v[i][2]));
+ }
+ return v;
+}
+
+//**********************************************************************************
+//generate "packing" of non-overlapping balls
+vector<Vector3r> fillBoxByBalls_cpp(Vector3r minCoord, Vector3r maxCoord, Vector3r sizemin, Vector3r sizemax, Vector3r ratio, int seed, shared_ptr<Material> mat, int NumPoints){
+ vector<Vector3r> v;
+ Polyhedra trialP;
+ Polyhedron trial, trial_moved;
+ srand(seed);
+ int it = 0;
+ vector<Polyhedron> polyhedrons;
+ vector<vector<Vector3r> > vv;
+ Vector3r position;
+ bool intersection;
+ int count = 0;
+ Vector3r radii;
+
+
+ bool fixed_ratio = 0;
+ if (ratio[0] > 0 && ratio[1] > 0 && ratio[2]>0){
+ fixed_ratio = 1;
+ sizemax[0] = min(min(sizemax[0]/ratio[0], sizemax[1]/ratio[1]), sizemax[2]/ratio[2]);
+ sizemin[0] = max(max(sizemin[0]/ratio[0], sizemin[1]/ratio[1]), sizemin[2]/ratio[2]);
+ }
+
+ fixed_ratio = 1; //force spherical
+
+ //it - number of trials to make packing possibly more/less dense
+ Vector3r random_size;
+ while (it<1000){
+ it = it+1;
+ if (it == 1){
+ if (fixed_ratio) {
+ double rrr = (rand()*(sizemax[0]-sizemin[0])/RAND_MAX + sizemin[0])/2.;
+ radii = Vector3r(rrr,rrr,rrr);
+ }else {
+ radii = Vector3r(rand()*(sizemax[0]-sizemin[0])/2.,rand()*(sizemax[1]-sizemin[1])/2.,rand()*(sizemax[2]-sizemin[2])/2.)/RAND_MAX + sizemin/2.;
+ }
+ trialP.v = BallPoints(radii,NumPoints,rand());
+ trialP.Initialize();
+ trial = trialP.GetPolyhedron();
+ Matrix3r rot_mat = (trialP.GetOri()).toRotationMatrix();
+ Transformation t_rot(rot_mat(0,0),rot_mat(0,1),rot_mat(0,2),rot_mat(1,0),rot_mat(1,1),rot_mat(1,2),rot_mat(2,0),rot_mat(2,1),rot_mat(2,2),1.);
+ std::transform( trial.points_begin(), trial.points_end(), trial.points_begin(), t_rot);
+ }
+ position = Vector3r(rand()*(maxCoord[0]-minCoord[0]),rand()*(maxCoord[1]-minCoord[1]),rand()*(maxCoord[2]-minCoord[2]))/RAND_MAX + minCoord;
+
+ //move CGAL structure Polyhedron
+ Transformation transl(CGAL::TRANSLATION, ToCGALVector(position));
+ trial_moved = trial;
+ std::transform( trial_moved.points_begin(), trial_moved.points_end(), trial_moved.points_begin(), transl);
+ //calculate plane equations
+ std::transform( trial_moved.facets_begin(), trial_moved.facets_end(), trial_moved.planes_begin(),Plane_equation());
+
+ intersection = false;
+ //call test with boundary
+ for(Polyhedron::Vertex_iterator vi = trial_moved.vertices_begin(); (vi != trial_moved.vertices_end()) && (!intersection); vi++){
+ intersection = (vi->point().x()<minCoord[0]) || (vi->point().x()>maxCoord[0]) || (vi->point().y()<minCoord[1]) || (vi->point().y()>maxCoord[1]) || (vi->point().z()<minCoord[2]) || (vi->point().z()>maxCoord[2]);
+ }
+ //call test with other polyhedrons
+ for(vector<Polyhedron>::iterator a = polyhedrons.begin(); (a != polyhedrons.end()) && (!intersection); a++){
+ intersection = do_intersect(*a,trial_moved);
+ if (intersection) break;
+ }
+ if (!intersection){
+ polyhedrons.push_back(trial_moved);
+ v.clear();
+ for(Polyhedron::Vertex_iterator vi = trial_moved.vertices_begin(); vi != trial_moved.vertices_end(); vi++){
+ v.push_back(FromCGALPoint(vi->point()));
+ }
+ vv.push_back(v);
+ it = 0;
+ count ++;
+
+ }
+ }
+ cout << "generated " << count << " polyhedrons"<< endl;
+
+ //can't be used - no information about material
+ Scene* scene=Omega::instance().getScene().get();
+ for(vector<vector<Vector3r> >::iterator p=vv.begin(); p!=vv.end(); ++p){
+ shared_ptr<Body> BP = NewPolyhedra(*p, mat);
+ BP->shape->color = Vector3r(double(rand())/RAND_MAX,double(rand())/RAND_MAX,double(rand())/RAND_MAX);
+ scene->bodies->insert(BP);
+ }
+ return v;
+}
+
//**********************************************************************************
//split polyhedra
-void Split(const shared_ptr<Body> body, Vector3r direction){
- SplitPolyhedra(body, direction);
+void Split(const shared_ptr<Body> body, Vector3r direction, Vector3r point){
+ SplitPolyhedra(body, direction, point);
}
//**********************************************************************************
@@ -361,14 +532,15 @@
py::def("PWaveTimeStep",PWaveTimeStep,"Get timestep accoring to the velocity of P-Wave propagation; computed from sphere radii, rigidities and masses.");
py::def("do_Polyhedras_Intersect",do_Polyhedras_Intersect,"check polyhedras intersection");
py::def("fillBox_cpp",fillBox_cpp,"Generate non-overlaping polyhedrons in box");
+ py::def("fillBoxByBalls_cpp",fillBoxByBalls_cpp,"Generate non-overlaping 'spherical' polyhedrons in box");
py::def("MinCoord",MinCoord,"returns min coordinates");
py::def("MaxCoord",MaxCoord,"returns max coordinates");
py::def("SieveSize",SieveSize,"returns approximate sieve size of polyhedron");
py::def("SieveCurve",SieveCurve,"save sieve curve coordinates into file");
py::def("SizeOfPolyhedra",SizeOfPolyhedra,"returns max, middle an min size in perpendicular directions");
py::def("SizeRatio",SizeRatio,"save sizes of polyhedra into file");
- py::def("convexHull",convexHull,"");
- py::def("Split",Split,"split polyhedron perpendicularly to given direction direction");
+ py::def("convexHull",convexHull,"....");
+ py::def("Split",Split,"split polyhedron perpendicularly to given direction through given point");
}
#endif // YADE_CGAL
=== modified file 'py/_utils.cpp'
--- py/_utils.cpp 2014-04-15 16:49:07 +0000
+++ py/_utils.cpp 2014-05-23 13:05:19 +0000
@@ -28,7 +28,7 @@
Real inf=std::numeric_limits<Real>::infinity();
Vector3r minimum(inf,inf,inf),maximum(-inf,-inf,-inf);
FOREACH(const shared_ptr<Body>& b, *Omega::instance().getScene()->bodies){
- shared_ptr<Sphere> s=dynamic_pointer_cast<Sphere>(b->shape); if(!s) continue;
+ shared_ptr<Sphere> s=boost::dynamic_pointer_cast<Sphere>(b->shape); if(!s) continue;
Vector3r rrr(s->radius,s->radius,s->radius);
minimum=minimum.cwiseMin(b->state->pos-(centers?Vector3r::Zero():rrr));
maximum=maximum.cwiseMax(b->state->pos+(centers?Vector3r::Zero():rrr));
@@ -42,7 +42,7 @@
Real minCoord=py::extract<double>(extrema[0][axis])(),maxCoord=py::extract<double>(extrema[1][axis])();
py::list minIds,maxIds;
FOREACH(const shared_ptr<Body>& b, *Omega::instance().getScene()->bodies){
- shared_ptr<Sphere> s=dynamic_pointer_cast<Sphere>(b->shape); if(!s) continue;
+ shared_ptr<Sphere> s=boost::dynamic_pointer_cast<Sphere>(b->shape); if(!s) continue;
if(b->state->pos[axis]-s->radius*distFactor<=minCoord) minIds.append(b->getId());
if(b->state->pos[axis]+s->radius*distFactor>=maxCoord) maxIds.append(b->getId());
}
@@ -76,45 +76,6 @@
Real PWaveTimeStep(){return Shop::PWaveTimeStep();};
Real RayleighWaveTimeStep(){return Shop::RayleighWaveTimeStep();};
-// FIXME: rewrite for ScGeom or remove
-// Real elasticEnergyInAABB(py::tuple Aabb){
-// Vector3r bbMin=py::extract<Vector3r>(Aabb[0])(), bbMax=py::extract<Vector3r>(Aabb[1])();
-// shared_ptr<Scene> rb=Omega::instance().getScene();
-// Real E=0;
-// FOREACH(const shared_ptr<Interaction>&i, *rb->interactions){
-// if(!i->phys) continue;
-// shared_ptr<NormShearPhys> bc=dynamic_pointer_cast<NormShearPhys>(i->phys); if(!bc) continue;
-// shared_ptr<Dem3DofGeom> geom=dynamic_pointer_cast<Dem3DofGeom>(i->geom); if(!geom){LOG_ERROR("NormShearPhys contact doesn't have Dem3DofGeom associated?!"); continue;}
-// const shared_ptr<Body>& b1=Body::byId(i->getId1(),rb), b2=Body::byId(i->getId2(),rb);
-// bool isIn1=isInBB(b1->state->pos,bbMin,bbMax), isIn2=isInBB(b2->state->pos,bbMin,bbMax);
-// if(!isIn1 && !isIn2) continue;
-// LOG_DEBUG("Interaction #"<<i->getId1()<<"--#"<<i->getId2());
-// Real weight=1.;
-// if((!isIn1 && isIn2) || (isIn1 && !isIn2)){
-// //shared_ptr<Body> bIn=isIn1?b1:b2, bOut=isIn2?b2:b1;
-// Vector3r vIn=(isIn1?b1:b2)->state->pos, vOut=(isIn2?b1:b2)->state->pos;
-// #define _WEIGHT_COMPONENT(axis) if(vOut[axis]<bbMin[axis]) weight=min(weight,abs((vOut[axis]-bbMin[axis])/(vOut[axis]-vIn[axis]))); else if(vOut[axis]>bbMax[axis]) weight=min(weight,abs((vOut[axis]-bbMax[axis])/(vOut[axis]-vIn[axis])));
-// _WEIGHT_COMPONENT(0); _WEIGHT_COMPONENT(1); _WEIGHT_COMPONENT(2);
-// assert(weight>=0 && weight<=1);
-// //cerr<<"Interaction crosses Aabb boundary, weight is "<<weight<<endl;
-// //LOG_DEBUG("Interaction crosses Aabb boundary, weight is "<<weight);
-// } else {assert(isIn1 && isIn2); /* cerr<<"Interaction inside, weight is "<<weight<<endl;*/ /*LOG_DEBUG("Interaction inside, weight is "<<weight);*/}
-// E+=geom->refLength*weight*(.5*bc->kn*pow(geom->strainN(),2)+.5*bc->ks*pow(geom->strainT().norm(),2));
-// }
-// return E;
-// }
-
-/* return histogram ([bin1Min,bin2Min,…],[value1,value2,…]) from projections of interactions
- * to the plane perpendicular to axis∈[0,1,2]; the number of bins can be specified and they cover
- * the range (0,π), since interactions are bidirecional, hence periodically the same on (π,2π).
- *
- * Only contacts using ScGeom are considered.
- * Both bodies must be in the mask (except if mask is 0, when all bodies are considered)
- * If the projection is shorter than minProjLen, it is skipped.
- *
- * If both bodies are _outside_ the aabb (if specified), the interaction is skipped.
- *
- */
py::tuple interactionAnglesHistogram(int axis, int mask=0, size_t bins=20, py::tuple aabb=py::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=py::len(aabb)>0; if(useBB){bbMin=py::extract<Vector3r>(aabb[0])();bbMax=py::extract<Vector3r>(aabb[1])();}
@@ -273,7 +234,7 @@
switch(mode){
case none: wire=false; break;
case all: wire=true; break;
- case noSpheres: wire=!(bool)(dynamic_pointer_cast<Sphere>(b->shape)); break;
+ case noSpheres: wire=!(bool)(boost::dynamic_pointer_cast<Sphere>(b->shape)); break;
default: throw logic_error("No such case possible");
}
b->shape->wire=wire;
@@ -364,11 +325,6 @@
NormShearPhys* nsi=dynamic_cast<NormShearPhys*>(I->phys.get());
if(!nsi) continue;
Vector3r pos1,pos2;
- /*
- Dem3DofGeom* d3dg=dynamic_cast<Dem3DofGeom*>(I->geom.get()); // Dem3DofGeom has copy of se3 in itself, otherwise we have to look up the bodies
- if(d3dg){ pos1=d3dg->se31.position; pos2=d3dg->se32.position; }
- else{ pos1=Body::byId(I->getId1(),scene)->state->pos; pos2=Body::byId(I->getId2(),scene)->state->pos; }
- */
pos1=Body::byId(I->getId1(),scene)->state->pos; pos2=Body::byId(I->getId2(),scene)->state->pos;
Real dot1=(pos1-planePt).dot(normal), dot2=(pos2-planePt).dot(normal);
if(dot1*dot2>0) continue; // both (centers of) bodies are on the same side of the plane=> this interaction has to be disregarded
@@ -508,7 +464,7 @@
py::def("ptInAABB",isInBB,"Return True/False whether the point p is within box given by its min and max corners");
py::def("negPosExtremeIds",negPosExtremeIds,negPosExtremeIds_overloads(py::args("axis","distFactor"),"Return list of ids for spheres (only) that are on extremal ends of the specimen along given axis; distFactor multiplies their radius so that sphere that do not touch the boundary coordinate can also be returned."));
py::def("approxSectionArea",approxSectionArea,"Compute area of convex hull when when taking (swept) spheres crossing the plane at coord, perpendicular to axis.");
- py::def("coordsAndDisplacements",coordsAndDisplacements,(python::arg("axis"),python::arg("Aabb")=python::tuple()),"Return tuple of 2 same-length lists for coordinates and displacements (coordinate minus reference coordinate) along given axis (1st arg); if the Aabb=((x_min,y_min,z_min),(x_max,y_max,z_max)) box is given, only bodies within this box will be considered.");
+ py::def("coordsAndDisplacements",coordsAndDisplacements,(py::arg("axis"),py::arg("Aabb")=py::tuple()),"Return tuple of 2 same-length lists for coordinates and displacements (coordinate minus reference coordinate) along given axis (1st arg); if the Aabb=((x_min,y_min,z_min),(x_max,y_max,z_max)) box is given, only bodies within this box will be considered.");
py::def("setRefSe3",setRefSe3,"Set reference :yref:`positions<State::refPos>` and :yref:`orientations<State::refOri>` of all :yref:`bodies<Body>` equal to their current :yref:`positions<State::pos>` and :yref:`orientations<State::ori>`.");
py::def("interactionAnglesHistogram",interactionAnglesHistogram,interactionAnglesHistogram_overloads(py::args("axis","mask","bins","aabb")));
py::def("bodyNumInteractionsHistogram",bodyNumInteractionsHistogram,bodyNumInteractionsHistogram_overloads(py::args("aabb")));
@@ -533,7 +489,6 @@
py::def("flipCell",&Shop::flipCell,(py::arg("flip")=Matrix3r(Matrix3r::Zero())),"Flip periodic cell so that angles between $R^3$ axes and transformed axes are as small as possible. This function relies on the fact that periodic cell defines by repetition or its corners regular grid of points in $R^3$; however, all cells generating identical grid are equivalent and can be flipped one over another. This necessiatates adjustment of :yref:`Interaction.cellDist` for interactions that cross boundary and didn't before (or vice versa), and re-initialization of collider. The *flip* argument can be used to specify desired flip: integers, each column for one axis; if zero matrix, best fit (minimizing the angles) is computed automatically.\n\nIn c++, this function is accessible as ``Shop::flipCell``.\n\n.. warning:: This function is currently broken and should not be used.");
py::def("getViscoelasticFromSpheresInteraction",getViscoelasticFromSpheresInteraction,(py::arg("tc"),py::arg("en"),py::arg("es")),"Attention! The function is deprecated! Compute viscoelastic interaction parameters from analytical solution of a pair spheres collision problem:\n\n.. math:: k_n=\\frac{m}{t_c^2}\\left(\\pi^2+(\\ln e_n)^2\\right) \\\\ c_n=-\\frac{2m}{t_c}\\ln e_n \\\\ k_t=\\frac{2}{7}\\frac{m}{t_c^2}\\left(\\pi^2+(\\ln e_t)^2\\right) \\\\ c_t=-\\frac{2}{7}\\frac{m}{t_c}\\ln e_t \n\n\nwhere $k_n$, $c_n$ are normal elastic and viscous coefficients and $k_t$, $c_t$ shear elastic and viscous coefficients. For details see [Pournin2001]_.\n\n:param float m: sphere mass $m$\n:param float tc: collision time $t_c$\n:param float en: normal restitution coefficient $e_n$\n:param float es: tangential restitution coefficient $e_s$\n:return: dictionary with keys ``kn`` (the value of $k_n$), ``cn`` ($c_n$), ``kt`` ($k_t$), ``ct`` ($c_t$).");
py::def("stressTensorOfPeriodicCell",Shop::getStress,(py::args("volume")=0),"Deprecated, use utils.getStress instead |ydeprecated|");
- //py::def("stressTensorOfPeriodicCell",Shop__stressTensorOfPeriodicCell,(py::args("smallStrains")=false),"Compute overall (macroscopic) stress of periodic cell using equation published in [Kuhl2001]_:\n\n.. math:: \\vec{\\sigma}=\\frac{1}{V}\\sum_cl^c[\\vec{N}^cf_N^c+\\vec{T}^{cT}\\cdot\\vec{f}^c_T],\n\nwhere $V$ is volume of the cell, $l^c$ length of interaction $c$, $f^c_N$ normal force and $\\vec{f}^c_T$ shear force. Sumed are values over all interactions $c$. $\\vec{N}^c$ and $\\vec{T}^{cT}$ are projection tensors (see the original publication for more details):\n\n.. math:: \\vec{N}=\\vec{n}\\otimes\\vec{n}\\rightarrow N_{ij}=n_in_j\n\n.. math:: \\vec{T}^T=\\vec{I}_{sym}\\cdot\\vec{n}-\\vec{n}\\otimes\\vec{n}\\otimes\\vec{n}\\rightarrow T^T_{ijk}=\\frac{1}{2}(\\delta_{ik}\\delta_{jl}+\\delta_{il}\\delta_{jk})n_l-n_in_jn_k\n\n.. math:: \\vec{T}^T\\cdot\\vec{f}_T\\equiv T^T_{ijk}f_k=(\\delta_{ik}n_j/2+\\delta_{jk}n_i/2-n_in_jn_k)f_k=n_jf_i/2+n_if_j/2-n_in_jn_kf_k,\n\nwhere $n$ is unit vector oriented along the interaction (:yref:`normal<GenericSpheresContact::normal>`) and $\\delta$ is Kronecker's delta. As $\\vec{n}$ and $\\vec{f}_T$ are perpendicular (therfore $n_if_i=0$) we can write\n\n.. math:: \\sigma_{ij}=\\frac{1}{V}\\sum l[n_in_jf_N+n_jf^T_i/2+n_if^T_j/2]\n\n:param bool smallStrains: if false (large strains), real values of volume and interaction lengths are computed. If true, only :yref:`refLength<Dem3DofGeom::refLength>` of interactions and initial volume are computed (can save some time).\n\n:return: macroscopic stress tensor as Matrix3");
py::def("normalShearStressTensors",Shop__normalShearStressTensors,(py::args("compressionPositive")=false,py::args("splitNormalTensor")=false,py::args("thresholdForce")=NaN),"Compute overall stress tensor of the periodic cell decomposed in 2 parts, one contributed by normal forces, the other by shear forces. The formulation can be found in [Thornton2000]_, eq. (3):\n\n.. math:: \\tens{\\sigma}_{ij}=\\frac{2}{V}\\sum R N \\vec{n}_i \\vec{n}_j+\\frac{2}{V}\\sum R T \\vec{n}_i\\vec{t}_j\n\nwhere $V$ is the cell volume, $R$ is \"contact radius\" (in our implementation, current distance between particle centroids), $\\vec{n}$ is the normal vector, $\\vec{t}$ is a vector perpendicular to $\\vec{n}$, $N$ and $T$ are norms of normal and shear forces.\n\n:param bool splitNormalTensor: if true the function returns normal stress tensor split into two parts according to the two subnetworks of strong an weak forces.\n\n:param Real thresholdForce: threshold value according to which the normal stress tensor can be split (e.g. a zero value would make distinction between tensile and compressive forces).");
py::def("fabricTensor",Shop__fabricTensor,(py::args("splitTensor")=false,py::args("revertSign")=false,py::args("thresholdForce")=NaN),"Compute the fabric tensor of the periodic cell. The original paper can be found in [Satake1982]_.\n\n:param bool splitTensor: split the fabric tensor into two parts related to the strong and weak contact forces respectively.\n\n:param bool revertSign: it must be set to true if the contact law's convention takes compressive forces as positive.\n\n:param Real thresholdForce: if the fabric tensor is split into two parts, a threshold value can be specified otherwise the mean contact force is considered by default. It is worth to note that this value has a sign and the user needs to set it according to the convention adopted for the contact law. To note that this value could be set to zero if one wanted to make distinction between compressive and tensile forces.");
py::def("bodyStressTensors",Shop__getStressLWForEachBody,"Compute and return a table with per-particle stress tensors. Each tensor represents the average stress in one particle, obtained from the contour integral of applied load as detailed below. This definition is considering each sphere as a continuum. It can be considered exact in the context of spheres at static equilibrium, interacting at contact points with negligible volume changes of the solid phase (this last assumption is not restricting possible deformations and volume changes at the packing scale).\n\nProof: \n\nFirst, we remark the identity: $\\sigma_{ij}=\\delta_{ik}\\sigma_{kj}=x_{i,k}\\sigma_{kj}=(x_{i}\\sigma_{kj})_{,k}-x_{i}\\sigma_{kj,k}$.\n\nAt equilibrium, the divergence of stress is null: $\\sigma_{kj,k}=\\vec{0}$. Consequently, after divergence theorem: $\\frac{1}{V}\\int_V \\sigma_{ij}dV = \\frac{1}{V}\\int_V (x_{i}\\sigma_{kj})_{,k}dV = \\frac{1}{V}\\int_{\\partial V}x_i\\sigma_{kj}n_kdS = \\frac{1}{V}\\sum_bx_i^bf_j^b$.\n\nThe last equality is implicitely based on the representation of external loads as Dirac distributions whose zeros are the so-called *contact points*: 0-sized surfaces on which the *contact forces* are applied, located at $x_i$ in the deformed configuration.\n\nA weighted average of per-body stresses will give the average stress inside the solid phase. There is a simple relation between the stress inside the solid phase and the stress in an equivalent continuum in the absence of fluid pressure. For porosity $n$, the relation reads: $\\sigma_{ij}^{equ.}=(1-n)\\sigma_{ij}^{solid}$.\n\nThis last relation may not be very useful if porosity is not homogeneous. If it happens, one can define the equivalent bulk stress a the particles scale by assigning a volume to each particle. This volume can be obtained from :yref:`TesselationWrapper` (see e.g. [Catalano2014a]_)");
@@ -542,7 +497,7 @@
py::def("getBodyIdsContacts",Shop__getBodyIdsContacts,(py::args("bodyID")=0),"Get a list of body-ids, which contacts the given body.");
py::def("maxOverlapRatio",maxOverlapRatio,"Return maximum overlap ration in interactions (with :yref:`ScGeom`) of two :yref:`spheres<Sphere>`. The ratio is computed as $\\frac{u_N}{2(r_1 r_2)/r_1+r_2}$, where $u_N$ is the current overlap distance and $r_1$, $r_2$ are radii of the two spheres in contact.");
py::def("shiftBodies",shiftBodies,(py::arg("ids"),py::arg("shift")),"Shifts bodies listed in ids without updating their velocities.");
- py::def("calm",Shop__calm,(py::arg("mask")=-1),"Set translational and rotational velocities of all bodies to zero.");
+ py::def("calm",Shop__calm,(py::arg("mask")=-1),"Set translational and rotational velocities of bodies to zero. Applied to all bodies by default. To calm only some bodies, use mask parameter, it will calm only bodies with groupMask compatible to given value");
py::def("setNewVerticesOfFacet",setNewVerticesOfFacet,(py::arg("b"),py::arg("v1"),py::arg("v2"),py::arg("v3")),"Sets new vertices (in global coordinates) to given facet.");
py::def("setContactFriction",Shop::setContactFriction,py::arg("angleRad"),"Modify the friction angle (in radians) inside the material classes and existing contacts. The friction for non-dynamic bodies is not modified.");
py::def("growParticles",Shop::growParticles,(py::args("multiplier"), py::args("updateMass")=true, py::args("dynamicOnly")=true, py::args("discretization")=0), "Change the size of spheres and sphere clumps by the multiplier. If updateMass=True, then the mass is updated. dynamicOnly=True is mandatory in many cases since in current implementation the function would crash on the non-spherical and non-dynamic bodies (e.g. facets, boxes, etc.). For clumps the masses and inertias are adapted automatically when discretization>0 (for details of inertia tensor integration scheme see :yref:`clump()<BodyContainer.clump>`).");
=== modified file 'py/pack/_packObb.cpp'
--- py/pack/_packObb.cpp 2013-03-07 18:28:01 +0000
+++ py/pack/_packObb.cpp 2014-05-23 13:03:50 +0000
@@ -12,7 +12,7 @@
#include<vector>
#include<stdexcept>
-using namespace boost;
+
#ifndef FOREACH
#define FOREACH BOOST_FOREACH
#endif
@@ -63,19 +63,19 @@
}
}
-python::tuple bestFitOBB_py(const python::tuple& _pts){
- int l=python::len(_pts);
+boost::python::tuple bestFitOBB_py(const boost::python::tuple& _pts){
+ int l=boost::python::len(_pts);
if(l<=1) throw std::runtime_error("Cloud must have at least 2 points.");
std::vector<Vector3r> pts; pts.resize(l);
- for(int i=0; i<l; i++) pts[i]=python::extract<Vector3r>(_pts[i]);
+ for(int i=0; i<l; i++) pts[i]=boost::python::extract<Vector3r>(_pts[i]);
Quaternionr rot; Vector3r halfSize, center;
bestFitOBB(pts,center,halfSize,rot);
- return python::make_tuple(center,halfSize,rot);
+ return boost::python::make_tuple(center,halfSize,rot);
}
BOOST_PYTHON_MODULE(_packObb){
YADE_SET_DOCSTRING_OPTS;
- python::scope().attr("__doc__")="Computation of oriented bounding box for cloud of points.";
- python::def("cloudBestFitOBB",bestFitOBB_py,"Return (Vector3 center, Vector3 halfSize, Quaternion orientation) of\nbest-fit oriented bounding-box for given tuple of points\n(uses brute-force velome minimization, do not use for very large clouds).");
+ boost::python::scope().attr("__doc__")="Computation of oriented bounding box for cloud of points.";
+ boost::python::def("cloudBestFitOBB",bestFitOBB_py,"Return (Vector3 center, Vector3 halfSize, Quaternion orientation) of\nbest-fit oriented bounding-box for given tuple of points\n(uses brute-force velome minimization, do not use for very large clouds).");
};
=== modified file 'py/pack/_packSpheres.cpp'
--- py/pack/_packSpheres.cpp 2013-08-14 08:01:55 +0000
+++ py/pack/_packSpheres.cpp 2014-05-23 13:03:50 +0000
@@ -5,26 +5,27 @@
#include<yade/lib/base/Math.hpp>
BOOST_PYTHON_MODULE(_packSpheres){
- python::scope().attr("__doc__")="Creation, manipulation, IO for generic sphere packings.";
+ boost::python::scope().attr("__doc__")="Creation, manipulation, IO for generic sphere packings.";
YADE_SET_DOCSTRING_OPTS;
- python::class_<SpherePack>("SpherePack","Set of spheres represented as centers and radii. This class is returned by :yref:`yade.pack.randomDensePack`, :yref:`yade.pack.randomPeriPack` and others. The object supports iteration over spheres, as in \n\n\t>>> sp=SpherePack()\n\t>>> for center,radius in sp: print center,radius\n\n\t>>> for sphere in sp: print sphere[0],sphere[1] ## same, but without unpacking the tuple automatically\n\n\t>>> for i in range(0,len(sp)): print sp[i][0], sp[i][1] ## same, but accessing spheres by index\n\n\n.. admonition:: Special constructors\n\n\tConstruct from list of ``[(c1,r1),(c2,r2),…]``. To convert two same-length lists of ``centers`` and ``radii``, construct with ``zip(centers,radii)``.\n",python::init<python::optional<python::list> >(python::args("list"),"Empty constructor, optionally taking list [ ((cx,cy,cz),r), … ] for initial data." ))
+ boost::python::class_<SpherePack>("SpherePack","Set of spheres represented as centers and radii. This class is returned by :yref:`yade.pack.randomDensePack`, :yref:`yade.pack.randomPeriPack` and others. The object supports iteration over spheres, as in \n\n\t>>> sp=SpherePack()\n\t>>> for center,radius in sp: print center,radius\n\n\t>>> for sphere in sp: print sphere[0],sphere[1] ## same, but without unpacking the tuple automatically\n\n\t>>> for i in range(0,len(sp)): print sp[i][0], sp[i][1] ## same, but accessing spheres by index\n\n\n.. admonition:: Special constructors\n\n\tConstruct from list of ``[(c1,r1),(c2,r2),…]``. To convert two same-length lists of ``centers`` and ``radii``, construct with ``zip(centers,radii)``.\n",boost::python::init<boost::python::optional<boost::python::list> >(boost::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("fromList",&SpherePack::fromLists,(python::arg("centers"),python::arg("radii")),"Make packing from given list, same format as for constructor. Discards current data.")
- .def("load",&SpherePack::fromFile,(python::arg("fileName")),"Load packing from external text file (current data will be discarded).")
- .def("save",&SpherePack::toFile,(python::arg("fileName")),"Save packing to external text file (will be overwritten).")
+ .def("fromList",&SpherePack::fromLists,(boost::python::arg("centers"),boost::python::arg("radii")),"Make packing from given list, same format as for constructor. Discards current data.")
+ .def("load",&SpherePack::fromFile,(boost::python::arg("fileName")),"Load packing from external text file (current data will be discarded).")
+ .def("save",&SpherePack::toFile,(boost::python::arg("fileName")),"Save packing to external text file (will be overwritten).")
.def("fromSimulation",&SpherePack::fromSimulation,"Make packing corresponding to the current simulation. Discards current data.")
- .def("makeCloud",&SpherePack::makeCloud,(python::arg("minCorner")=Vector3r(Vector3r::Zero()),python::arg("maxCorner")=Vector3r(Vector3r::Zero()),python::arg("rMean")=-1,python::arg("rRelFuzz")=0,python::arg("num")=-1,python::arg("periodic")=false,python::arg("porosity")=0.65,python::arg("psdSizes")=vector<Real>(),python::arg("psdCumm")=vector<Real>(),python::arg("distributeMass")=false,python::arg("seed")=0,python::arg("hSize")=Matrix3r(Matrix3r::Zero())),"Create random loose packing enclosed in a parallelepiped (also works in 2D if minCorner[k]=maxCorner[k] for one coordinate)."
+ .def("makeCloud",&SpherePack::makeCloud,(boost::python::arg("minCorner")=Vector3r(Vector3r::Zero()),boost::python::arg("maxCorner")=Vector3r(Vector3r::Zero()),boost::python::arg("rMean")=-1,boost::python::arg("rRelFuzz")=0,boost::python::arg("num")=-1,boost::python::arg("periodic")=false,boost::python::arg("porosity")=0.65,boost::python::arg("psdSizes")=vector<Real>(),boost::python::arg("psdCumm")=vector<Real>(),boost::python::arg("distributeMass")=false,boost::python::arg("seed")=0,boost::python::arg("hSize")=Matrix3r(Matrix3r::Zero())),"Create random loose packing enclosed in a parallelepiped (also works in 2D if minCorner[k]=maxCorner[k] for one coordinate)."
"\nSphere radius distribution can be specified using one of the following ways:\n\n#. *rMean*, *rRelFuzz* and *num* gives uniform radius distribution in *rMean×(1 ± rRelFuzz)*. Less than *num* spheres can be generated if it is too high.\n#. *rRelFuzz*, *num* and (optional) *porosity*, which estimates mean radius so that *porosity* is attained at the end. *rMean* must be less than 0 (default). *porosity* is only an initial guess for the generation algorithm, which will retry with higher porosity until the prescibed *num* is obtained.\n#. *psdSizes* and *psdCumm*, two arrays specifying points of the `particle size distribution <http://en.wikipedia.org/wiki/Particle_size_distribution>`__ function. As many spheres as possible are generated.\n#. *psdSizes*, *psdCumm*, *num*, and (optional) *porosity*, like above but if *num* is not obtained, *psdSizes* will be scaled down uniformly, until *num* is obtained (see :yref:`appliedPsdScaling<yade._packSpheres.SpherePack.appliedPsdScaling>`).\n\nBy default (with ``distributeMass==False``), the distribution is applied to particle radii. The usual sense of \"particle size distribution\" is the distribution of *mass fraction* (rather than particle count); this can be achieved with ``distributeMass=True``."
"\n\nIf *num* is defined, then sizes generation is deterministic, giving the best fit of target distribution. It enables spheres placement in descending size order, thus giving lower porosity than the random generation."
"\n\n:param Vector3 minCorner: lower corner of an axis-aligned box\n:param Vector3 maxCorner: upper corner of an axis-aligned box\n:param Matrix3 hSize: base vectors of a generalized box (arbitrary parallelepiped, typically :yref:`Cell::hSize`), superseeds minCorner and maxCorner if defined. For periodic boundaries only.\n:param float rMean: mean radius or spheres\n:param float rRelFuzz: dispersion of radius relative to rMean\n:param int num: number of spheres to be generated. If negavite (default), generate as many as possible with stochastic sizes, ending after a fixed number of tries to place the sphere in space, else generate exactly *num* spheres with deterministic size distribution.\n:param bool periodic: whether the packing to be generated should be periodic\n:param float porosity: initial guess for the iterative generation procedure (if *num*>1). The algorithm will be retrying until the number of generated spheres is *num*. The first iteration tries with the provided porosity, but next iterations increase it if necessary (hence an initialy high porosity can speed-up the algorithm). If *psdSizes* is not defined, *rRelFuzz* ($z$) and *num* ($N$) are used so that the porosity given ($\\rho$) is approximately achieved at the end of generation, $r_m=\\sqrt[3]{\\frac{V(1-\\rho)}{\\frac{4}{3}\\pi(1+z^2)N}}$. The default is $\\rho$=0.5. The optimal value depends on *rRelFuzz* or *psdSizes*.\n:param psdSizes: sieve sizes (particle diameters) when particle size distribution (PSD) is specified\n:param psdCumm: cummulative fractions of particle sizes given by *psdSizes*; must be the same length as *psdSizes* and should be non-decreasing\n:param bool distributeMass: if ``True``, given distribution will be used to distribute sphere's mass rather than radius of them.\n:param seed: number used to initialize the random number generator.\n:returns: number of created spheres, which can be lower than *num* depending on the method used.\n")
- .def("psd",&SpherePack::psd,(python::arg("bins")=50,python::arg("mass")=true),"Return `particle size distribution <http://en.wikipedia.org/wiki/Particle_size_distribution>`__ of the packing.\n:param int bins: number of bins between minimum and maximum diameter\n:param mass: Compute relative mass rather than relative particle count for each bin. Corresponds to :yref:`distributeMass parameter for makeCloud<yade.pack.SpherePack.makeCloud>`.\n:returns: tuple of ``(cumm,edges)``, where ``cumm`` are cummulative fractions for respective diameters and ``edges`` are those diameter values. Dimension of both arrays is equal to ``bins+1``.")
+ .def("psd",&SpherePack::psd,(boost::python::arg("bins")=50,boost::python::arg("mass")=true),"Return `particle size distribution <http://en.wikipedia.org/wiki/Particle_size_distribution>`__ of the packing.\n:param int bins: number of bins between minimum and maximum diameter\n:param mass: Compute relative mass rather than relative particle count for each bin. Corresponds to :yref:`distributeMass parameter for makeCloud<yade.pack.SpherePack.makeCloud>`.\n:returns: tuple of ``(cumm,edges)``, where ``cumm`` are cummulative fractions for respective diameters and ``edges`` are those diameter values. Dimension of both arrays is equal to ``bins+1``.")
// new psd
- .def("particleSD",&SpherePack::particleSD,(python::arg("minCorner"),python::arg("maxCorner"),python::arg("rMean"),python::arg("periodic")=false,python::arg("name"),python::arg("numSph"),python::arg("radii")=vector<Real>(),python::arg("passing")=vector<Real>(),python::arg("passingIsNotPercentageButCount")=false,python::arg("seed")=0),"Create random packing enclosed in box given by minCorner and maxCorner, containing numSph spheres. Returns number of created spheres, which can be < num if the packing is too tight. The computation is done according to the given psd.")
- .def("particleSD2",&SpherePack::particleSD2,(python::arg("radii"),python::arg("passing"),python::arg("numSph"),python::arg("periodic")=false,python::arg("cloudPorosity")=.8,python::arg("seed")=0),"Create random packing following the given particle size distribution (radii and volume/mass passing for each fraction) and total number of particles *numSph*. The cloud size (periodic or aperiodic) is computed from the PSD and is always cubic.")
- .def("particleSD_2d",&SpherePack::particleSD_2d,(python::arg("minCorner"),python::arg("maxCorner"),python::arg("rMean"),python::arg("periodic")=false,python::arg("name"),python::arg("numSph"),python::arg("radii")=vector<Real>(),python::arg("passing")=vector<Real>(),python::arg("passingIsNotPercentageButCount")=false,python::arg("seed")=0),"Create random packing on XY plane, defined by minCorner and maxCorner, containing numSph spheres. Returns number of created spheres, which can be < num if the packing is too tight. The computation is done according to the given psd.")
- .def("makeClumpCloud",&SpherePack::makeClumpCloud,(python::arg("minCorner"),python::arg("maxCorner"),python::arg("clumps"),python::arg("periodic")=false,python::arg("num")=-1,python::arg("seed")=0),"Create random loose packing of clumps within box given by *minCorner* and *maxCorner*. Clumps are selected with equal probability. At most *num* clumps will be positioned if *num* is positive; otherwise, as many clumps as possible will be put in space, until maximum number of attempts to place a new clump randomly is attained.\n:param seed: number used to initialize the random number generator.")
+ .def("particleSD",&SpherePack::particleSD,(boost::python::arg("minCorner"),boost::python::arg("maxCorner"),boost::python::arg("rMean"),boost::python::arg("periodic")=false,boost::python::arg("name"),boost::python::arg("numSph"),boost::python::arg("radii")=vector<Real>(),boost::python::arg("passing")=vector<Real>(),boost::python::arg("passingIsNotPercentageButCount")=false, boost::python::arg("seed")=0),"Create random packing enclosed in box given by minCorner and maxCorner, containing numSph spheres. Returns number of created spheres, which can be < num if the packing is too tight. The computation is done according to the given psd.")
+ .def("particleSD2",&SpherePack::particleSD2,(boost::python::arg("radii"),boost::python::arg("passing"),boost::python::arg("numSph"),boost::python::arg("periodic")=false,boost::python::arg("cloudPorosity")=.8,boost::python::arg("seed")=0),"Create random packing following the given particle size distribution (radii and volume/mass passing for each fraction) and total number of particles *numSph*. The cloud size (periodic or aperiodic) is computed from the PSD and is always cubic.")
+ .def("particleSD_2d",&SpherePack::particleSD_2d,(boost::python::arg("minCorner"),boost::python::arg("maxCorner"),boost::python::arg("rMean"),boost::python::arg("periodic")=false,boost::python::arg("name"),boost::python::arg("numSph"),boost::python::arg("radii")=vector<Real>(),boost::python::arg("passing")=vector<Real>(),boost::python::arg("passingIsNotPercentageButCount")=false,boost::python::arg("seed")=0),"Create random packing on XY plane, defined by minCorner and maxCorner, containing numSph spheres. Returns number of created spheres, which can be < num if the packing is too tight. The computation is done according to the given psd.")
+
+ .def("makeClumpCloud",&SpherePack::makeClumpCloud,(boost::python::arg("minCorner"),boost::python::arg("maxCorner"),boost::python::arg("clumps"),boost::python::arg("periodic")=false,boost::python::arg("num")=-1,boost::python::arg("seed")=0),"Create random loose packing of clumps within box given by *minCorner* and *maxCorner*. Clumps are selected with equal probability. At most *num* clumps will be positioned if *num* is positive; otherwise, as many clumps as possible will be put in space, until maximum number of attempts to place a new clump randomly is attained.\n:param seed: number used to initialize the random number generator.")
//
.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.")
@@ -35,7 +36,7 @@
.def("cellRepeat",&SpherePack::cellRepeat,"Repeat the packing given number of times in each dimension. Periodicity is retained, cellSize changes. Raises exception for non-periodic packing.")
.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,(python::arg("axis"),python::arg("angle")),"Rotate all spheres around packing center (in terms of aabb()), given axis and angle of the rotation.")
+ .def("rotate",&SpherePack::rotate,(boost::python::arg("axis"),boost::python::arg("angle")),"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("hasClumps",&SpherePack::hasClumps,"Whether this object contains clumps.")
.def("getClumps",&SpherePack::getClumps,"Return lists of sphere ids sorted by clumps they belong to. The return value is (standalones,[clump1,clump2,…]), where each item is list of id's of spheres.")
@@ -44,7 +45,7 @@
.def("__iter__",&SpherePack::getIterator,"Return iterator over spheres.")
.def_readonly("appliedPsdScaling",&SpherePack::appliedPsdScaling,"A factor between 0 and 1, uniformly applied on all sizes of of the PSD.")
;
- python::class_<SpherePack::_iterator>("SpherePackIterator",python::init<SpherePack::_iterator&>())
+ boost::python::class_<SpherePack::_iterator>("SpherePackIterator",boost::python::init<SpherePack::_iterator&>())
.def("__iter__",&SpherePack::_iterator::iter)
.def("next",&SpherePack::_iterator::next)
;
=== modified file 'py/polyhedra_utils.py'
--- py/polyhedra_utils.py 2013-10-15 16:14:46 +0000
+++ py/polyhedra_utils.py 2014-05-16 11:58:59 +0000
@@ -79,8 +79,54 @@
ball = polyhedra(material,v=pts)
ball.state.pos = center
return ball
+
+#**********************************************************************************
+def polyhedraTruncIcosaHed(radius, material, centre,mask=1):
+ pts = []
+
+ p = (1.+math.sqrt(5.))/2.
+ f = radius/math.sqrt(9.*p + 1.)
+ A = [[0.,1.,3.*p],[2.,1.+2.*p,p],[1.,2.+p,2.*p]]
+ for a in A:
+ a = [a[0]*f,a[1]*f,a[2]*f]
+ B = [a,[a[1],a[2],a[0]],[a[2],a[0],a[1]]]
+ for b in B:
+ pts.append(b)
+ if not b[0] == 0:
+ pts.append([-b[0], b[1], b[2]])
+ if not b[1] == 0:
+ pts.append([-b[0],-b[1], b[2]])
+ if not b[2] == 0: pts.append([-b[0],-b[1],-b[2]])
+ if not b[2] == 0:
+ pts.append([-b[0], b[1],-b[2]])
+ if not b[1] == 0:
+ pts.append([ b[0],-b[1], b[2]])
+ if not b[2] == 0:
+ pts.append([ b[0],-b[1],-b[2]])
+ if not b[2] == 0: pts.append([ b[0], b[1],-b[2]])
+ ball = polyhedra(material,v=pts)
+ ball.state.pos = centre
+ return ball
#**********************************************************************************
+def polyhedraSnubCube(radius, material, centre, mask=1):
+ pts = []
+
+ f = radius/1.3437133737446
+ c1 = 0.337754
+ c2 = 1.14261
+ c3 = 0.621226
+ A = [[c2,c1,c3],[c1,c3,c2],[c3,c2,c1],[-c1,-c2,-c3],[-c2,-c3,-c1],[-c3,-c1,-c2]]
+ for a in A:
+ a = [a[0]*f,a[1]*f,a[2]*f]
+ pts.append([-a[0],-a[1], a[2]])
+ pts.append([ a[0],-a[1],-a[2]])
+ pts.append([-a[0], a[1],-a[2]])
+ pts.append([ a[0], a[1], a[2]])
+ ball = polyhedra(material,v=pts)
+ ball.state.pos = centre
+ return ball
+#**********************************************************************************
#fill box [mincoord, maxcoord] by non-overlaping polyhedrons with random geometry and sizes within the range (uniformly distributed)
def fillBox(mincoord, maxcoord,material,sizemin=[1,1,1],sizemax=[1,1,1],ratio=[0,0,0],seed=None,mask=1):
"""fill box [mincoord, maxcoord] by non-overlaping polyhedrons with random geometry and sizes within the range (uniformly distributed)
@@ -98,5 +144,16 @@
# if(math.isnan(v[i][0])):
# O.bodies.append(polyhedra(material,seed=random.randint(0,1E6),v=v[lastnan+1:i],mask=1,fixed=False))
# lastnan = i
+
+#**********************************************************************************
+#fill box [mincoord, maxcoord] by non-overlaping polyhedrons with random geometry and sizes within the range (uniformly distributed)
+def fillBoxByBalls(mincoord, maxcoord,material,sizemin=[1,1,1],sizemax=[1,1,1],ratio=[0,0,0],seed=None,mask=1,numpoints=60):
+ random.seed(seed);
+ v = fillBoxByBalls_cpp(mincoord, maxcoord, sizemin,sizemax, ratio, random.randint(0,1E6), material,numpoints)
+ #lastnan = -1
+ #for i in range(0,len(v)):
+ # if(math.isnan(v[i][0])):
+ # O.bodies.append(polyhedra(material,seed=random.randint(0,1E6),v=v[lastnan+1:i],mask=1,fixed=False))
+ # lastnan = i
=== modified file 'py/wrapper/customConverters.cpp'
--- py/wrapper/customConverters.cpp 2012-01-31 18:21:29 +0000
+++ py/wrapper/customConverters.cpp 2014-05-23 13:05:19 +0000
@@ -44,39 +44,34 @@
#include<yade/pkg/common/MatchMaker.hpp>
-
-
-using namespace boost::python;
-
-
// move this to the miniEigen wrapper later
/* two-way se3 handling */
struct custom_se3_to_tuple{
static PyObject* convert(const Se3r& se3){
- python::tuple ret=python::make_tuple(se3.position,se3.orientation);
- return incref(ret.ptr());
+ boost::python::tuple ret=boost::python::make_tuple(se3.position,se3.orientation);
+ return boost::python::incref(ret.ptr());
}
};
struct custom_Se3r_from_seq{
custom_Se3r_from_seq(){
- converter::registry::push_back(&convertible,&construct,type_id<Se3r>());
+ boost::python::converter::registry::push_back(&convertible,&construct,boost::python::type_id<Se3r>());
}
static void* convertible(PyObject* obj_ptr){
if(!PySequence_Check(obj_ptr)) return 0;
if(PySequence_Size(obj_ptr)!=2 && PySequence_Size(obj_ptr)!=7) return 0;
return obj_ptr;
}
- static void construct(PyObject* obj_ptr, converter::rvalue_from_python_stage1_data* data){
- void* storage=((converter::rvalue_from_python_storage<Se3r>*)(data))->storage.bytes;
+ static void construct(PyObject* obj_ptr, boost::python::converter::rvalue_from_python_stage1_data* data){
+ void* storage=((boost::python::converter::rvalue_from_python_storage<Se3r>*)(data))->storage.bytes;
new (storage) Se3r; Se3r* se3=(Se3r*)storage;
if(PySequence_Size(obj_ptr)==2){ // from vector and quaternion
- se3->position=extract<Vector3r>(PySequence_GetItem(obj_ptr,0));
- se3->orientation=extract<Quaternionr>(PySequence_GetItem(obj_ptr,1));
+ se3->position=boost::python::extract<Vector3r>(PySequence_GetItem(obj_ptr,0));
+ se3->orientation=boost::python::extract<Quaternionr>(PySequence_GetItem(obj_ptr,1));
} else if(PySequence_Size(obj_ptr)==7){ // 3 vector components, 3 axis components, angle
- se3->position=Vector3r(extract<Real>(PySequence_GetItem(obj_ptr,0)),extract<Real>(PySequence_GetItem(obj_ptr,1)),extract<Real>(PySequence_GetItem(obj_ptr,2)));
- Vector3r axis=Vector3r(extract<Real>(PySequence_GetItem(obj_ptr,3)),extract<Real>(PySequence_GetItem(obj_ptr,4)),extract<Real>(PySequence_GetItem(obj_ptr,5)));
- Real angle=extract<Real>(PySequence_GetItem(obj_ptr,6));
+ se3->position=Vector3r(boost::python::extract<Real>(PySequence_GetItem(obj_ptr,0)),boost::python::extract<Real>(PySequence_GetItem(obj_ptr,1)),boost::python::extract<Real>(PySequence_GetItem(obj_ptr,2)));
+ Vector3r axis=Vector3r(boost::python::extract<Real>(PySequence_GetItem(obj_ptr,3)),boost::python::extract<Real>(PySequence_GetItem(obj_ptr,4)),boost::python::extract<Real>(PySequence_GetItem(obj_ptr,5)));
+ Real angle=boost::python::extract<Real>(PySequence_GetItem(obj_ptr,6));
se3->orientation=Quaternionr(AngleAxisr(angle,axis));
} else throw std::logic_error(__FILE__ ": First, the sequence size for Se3r object was 2 or 7, but now is not? (programming error, please report!");
data->convertible=storage;
@@ -84,69 +79,69 @@
};
-struct custom_OpenMPAccumulator_to_float{ static PyObject* convert(const OpenMPAccumulator<Real>& acc){ return incref(PyFloat_FromDouble(acc.get())); } };
+struct custom_OpenMPAccumulator_to_float{ static PyObject* convert(const OpenMPAccumulator<Real>& acc){ return boost::python::incref(PyFloat_FromDouble(acc.get())); } };
struct custom_OpenMPAccumulator_from_float{
- custom_OpenMPAccumulator_from_float(){ converter::registry::push_back(&convertible,&construct,type_id<OpenMPAccumulator<Real> >()); }
+ custom_OpenMPAccumulator_from_float(){ boost::python::converter::registry::push_back(&convertible,&construct,boost::python::type_id<OpenMPAccumulator<Real> >()); }
static void* convertible(PyObject* obj_ptr){ return PyFloat_Check(obj_ptr) ? obj_ptr : 0; }
- static void construct(PyObject* obj_ptr, converter::rvalue_from_python_stage1_data* data){ void* storage=((converter::rvalue_from_python_storage<OpenMPAccumulator<Real> >*)(data))->storage.bytes; new (storage) OpenMPAccumulator<Real>; ((OpenMPAccumulator<Real>*)storage)->set(extract<Real>(obj_ptr)); data->convertible=storage; }
+ static void construct(PyObject* obj_ptr, boost::python::converter::rvalue_from_python_stage1_data* data){ void* storage=((boost::python::converter::rvalue_from_python_storage<OpenMPAccumulator<Real> >*)(data))->storage.bytes; new (storage) OpenMPAccumulator<Real>; ((OpenMPAccumulator<Real>*)storage)->set(boost::python::extract<Real>(obj_ptr)); data->convertible=storage; }
};
-struct custom_OpenMPAccumulator_to_int { static PyObject* convert(const OpenMPAccumulator<int>& acc){ return incref(PyInt_FromLong((long)acc.get())); } };
+struct custom_OpenMPAccumulator_to_int { static PyObject* convert(const OpenMPAccumulator<int>& acc){ return boost::python::incref(PyInt_FromLong((long)acc.get())); } };
struct custom_OpenMPAccumulator_from_int{
- custom_OpenMPAccumulator_from_int(){ converter::registry::push_back(&convertible,&construct,type_id<OpenMPAccumulator<int> >()); }
+ custom_OpenMPAccumulator_from_int(){ boost::python::converter::registry::push_back(&convertible,&construct,boost::python::type_id<OpenMPAccumulator<int> >()); }
static void* convertible(PyObject* obj_ptr){ return PyInt_Check(obj_ptr) ? obj_ptr : 0; }
- static void construct(PyObject* obj_ptr, converter::rvalue_from_python_stage1_data* data){ void* storage=((converter::rvalue_from_python_storage<OpenMPAccumulator<int> >*)(data))->storage.bytes; new (storage) OpenMPAccumulator<int>; ((OpenMPAccumulator<int>*)storage)->set(extract<int>(obj_ptr)); data->convertible=storage; }
+ static void construct(PyObject* obj_ptr, boost::python::converter::rvalue_from_python_stage1_data* data){ void* storage=((boost::python::converter::rvalue_from_python_storage<OpenMPAccumulator<int> >*)(data))->storage.bytes; new (storage) OpenMPAccumulator<int>; ((OpenMPAccumulator<int>*)storage)->set(boost::python::extract<int>(obj_ptr)); data->convertible=storage; }
};
template<typename T>
struct custom_vvector_to_list{
static PyObject* convert(const std::vector<std::vector<T> >& vv){
- python::list ret; FOREACH(const std::vector<T>& v, vv){
- python::list ret2;
+ boost::python::list ret; FOREACH(const std::vector<T>& v, vv){
+ boost::python::list ret2;
FOREACH(const T& e, v) ret2.append(e);
ret.append(ret2);
}
- return incref(ret.ptr());
+ return boost::python::incref(ret.ptr());
}
};
template<typename containedType>
struct custom_list_to_list{
static PyObject* convert(const std::list<containedType>& v){
- python::list ret; FOREACH(const containedType& e, v) ret.append(e);
- return incref(ret.ptr());
+ boost::python::list ret; FOREACH(const containedType& e, v) ret.append(e);
+ return boost::python::incref(ret.ptr());
}
};
/*** c++-list to python-list */
template<typename containedType>
struct custom_vector_to_list{
static PyObject* convert(const std::vector<containedType>& v){
- python::list ret; FOREACH(const containedType& e, v) ret.append(e);
- return incref(ret.ptr());
+ boost::python::list ret; FOREACH(const containedType& e, v) ret.append(e);
+ return boost::python::incref(ret.ptr());
}
};
template<typename containedType>
struct custom_vector_from_seq{
- custom_vector_from_seq(){ converter::registry::push_back(&convertible,&construct,type_id<std::vector<containedType> >()); }
+ custom_vector_from_seq(){ boost::python::converter::registry::push_back(&convertible,&construct,boost::python::type_id<std::vector<containedType> >()); }
static void* convertible(PyObject* obj_ptr){
// the second condition is important, for some reason otherwise there were attempted conversions of Body to list which failed afterwards.
if(!PySequence_Check(obj_ptr) || !PyObject_HasAttrString(obj_ptr,"__len__")) return 0;
return obj_ptr;
}
- static void construct(PyObject* obj_ptr, converter::rvalue_from_python_stage1_data* data){
- void* storage=((converter::rvalue_from_python_storage<std::vector<containedType> >*)(data))->storage.bytes;
+ static void construct(PyObject* obj_ptr, boost::python::converter::rvalue_from_python_stage1_data* data){
+ void* storage=((boost::python::converter::rvalue_from_python_storage<std::vector<containedType> >*)(data))->storage.bytes;
new (storage) std::vector<containedType>();
std::vector<containedType>* v=(std::vector<containedType>*)(storage);
- int l=PySequence_Size(obj_ptr); if(l<0) abort(); /*std::cerr<<"l="<<l<<"; "<<typeid(containedType).name()<<std::endl;*/ v->reserve(l); for(int i=0; i<l; i++) { v->push_back(extract<containedType>(PySequence_GetItem(obj_ptr,i))); }
+ int l=PySequence_Size(obj_ptr); if(l<0) abort(); /*std::cerr<<"l="<<l<<"; "<<typeid(containedType).name()<<std::endl;*/ v->reserve(l); for(int i=0; i<l; i++) { v->push_back(boost::python::extract<containedType>(PySequence_GetItem(obj_ptr,i))); }
data->convertible=storage;
}
};
struct custom_ptrMatchMaker_from_float{
- custom_ptrMatchMaker_from_float(){ converter::registry::push_back(&convertible,&construct,type_id<shared_ptr<MatchMaker> >()); }
+ custom_ptrMatchMaker_from_float(){ boost::python::converter::registry::push_back(&convertible,&construct,boost::python::type_id<shared_ptr<MatchMaker> >()); }
static void* convertible(PyObject* obj_ptr){ if(!PyNumber_Check(obj_ptr)) { cerr<<"Not convertible to MatchMaker"<<endl; return 0; } return obj_ptr; }
- static void construct(PyObject* obj_ptr, converter::rvalue_from_python_stage1_data* data){
- void* storage=((converter::rvalue_from_python_storage<shared_ptr<MatchMaker> >*)(data))->storage.bytes;
+ static void construct(PyObject* obj_ptr, boost::python::converter::rvalue_from_python_stage1_data* data){
+ void* storage=((boost::python::converter::rvalue_from_python_storage<shared_ptr<MatchMaker> >*)(data))->storage.bytes;
new (storage) shared_ptr<MatchMaker>(new MatchMaker); // allocate the object at given address
shared_ptr<MatchMaker>* mm=(shared_ptr<MatchMaker>*)(storage); // convert that address to our type
(*mm)->algo="val"; (*mm)->val=PyFloat_AsDouble(obj_ptr); (*mm)->postLoad(**mm);
@@ -154,48 +149,12 @@
}
};
-#if 0
-template<typename numT, int dim>
-struct custom_numpyBoost_to_py{
- static PyObject* convert(numpy_boost<numT, dim> nb){
- return nb.py_ptr(); // handles incref internally
- }
-};
-#endif
-
-#if 0
-template<typename T>
-std::string vectorRepr(const vector<T>& v){ std::string ret("["); for(size_t i=0; i<v.size(); i++) { if(i>0) ret+=","; ret+=lexical_cast<string>(v[i]); } return ret+"]"; }
-template<>
-std::string vectorRepr(const vector<std::string>& v){ std::string ret("["); for(size_t i=0; i<v.size(); i++) { if(i>0) ret+=","; ret+="'"+lexical_cast<string>(v[i])+"'"; } return ret+"]"; }
-
-// is not picked up?
-bool operator<(const Vector3r& a, const Vector3r& b){ return a[0]<b[0]; }
-#endif
-
-
-using namespace boost::python;
-
BOOST_PYTHON_MODULE(_customConverters){
- // syntax ??
- // http://language-binding.net/pyplusplus/documentation/indexing_suite_v2.html.html#container_proxy
- // http://www.mail-archive.com/cplusplus-sig@xxxxxxxxxx/msg00862.html
- //class_<indexing::container_proxy<std::vector<string> >,bases<class_<std::vector<string> > > >("vecStr").def(indexing::container_suite<indexing::container_proxy<std::vector<string> > >());
- //class_<std::vector<string> >("vecStr").def(indexing::container_suite<std::vector<string> >());
-
- #if 0
- custom_vector_from_seq<string>(); class_<std::vector<string> >("vector_" "string").def(indexing::container_suite<std::vector<string> >()).def("__repr__",&vectorRepr<string>);
- custom_vector_from_seq<int>(); class_<std::vector<int> >("vector_" "int").def(indexing::container_suite<std::vector<int> >()).def("__repr__",&vectorRepr<int>);
- custom_vector_from_seq<Real>(); class_<std::vector<Real> >("vector_" "Real").def(indexing::container_suite<std::vector<Real> >()).def("__repr__",&vectorRepr<Real>);
- // this needs operator< for Vector3r (defined above, but not picked up for some reason)
- custom_vector_from_seq<Vector3r>(); class_<std::vector<Vector3r> >("vector_" "Vector3r").def(indexing::container_suite<std::vector<Vector3r> >()).def("__repr__",&vectorRepr<Vector3r>);
- #endif
-
- custom_Se3r_from_seq(); to_python_converter<Se3r,custom_se3_to_tuple>();
-
- custom_OpenMPAccumulator_from_float(); to_python_converter<OpenMPAccumulator<Real>, custom_OpenMPAccumulator_to_float>();
- custom_OpenMPAccumulator_from_int(); to_python_converter<OpenMPAccumulator<int>, custom_OpenMPAccumulator_to_int>();
+ custom_Se3r_from_seq(); boost::python::to_python_converter<Se3r,custom_se3_to_tuple>();
+
+ custom_OpenMPAccumulator_from_float(); boost::python::to_python_converter<OpenMPAccumulator<Real>, custom_OpenMPAccumulator_to_float>();
+ custom_OpenMPAccumulator_from_int(); boost::python::to_python_converter<OpenMPAccumulator<int>, custom_OpenMPAccumulator_to_int>();
// todo: OpenMPAccumulator<int>
custom_ptrMatchMaker_from_float();
@@ -204,12 +163,12 @@
//custom_StrArrayMap_to_dict();
// register from-python converter and to-python converter
- to_python_converter<std::vector<std::vector<std::string> >,custom_vvector_to_list<std::string> >();
- //to_python_converter<std::list<shared_ptr<Functor> >, custom_list_to_list<shared_ptr<Functor> > >();
- //to_python_converter<std::list<shared_ptr<Functor> >, custom_list_to_list<shared_ptr<Functor> > >();
+ boost::python::to_python_converter<std::vector<std::vector<std::string> >,custom_vvector_to_list<std::string> >();
+ //boost::python::to_python_converter<std::list<shared_ptr<Functor> >, custom_list_to_list<shared_ptr<Functor> > >();
+ //boost::python::to_python_converter<std::list<shared_ptr<Functor> >, custom_list_to_list<shared_ptr<Functor> > >();
// register 2-way conversion between c++ vector and python homogeneous sequence (list/tuple) of corresponding type
- #define VECTOR_SEQ_CONV(Type) custom_vector_from_seq<Type>(); to_python_converter<std::vector<Type>, custom_vector_to_list<Type> >();
+ #define VECTOR_SEQ_CONV(Type) custom_vector_from_seq<Type>(); boost::python::to_python_converter<std::vector<Type>, custom_vector_to_list<Type> >();
VECTOR_SEQ_CONV(int);
VECTOR_SEQ_CONV(bool);
VECTOR_SEQ_CONV(Real);
@@ -246,15 +205,6 @@
VECTOR_SEQ_CONV(shared_ptr<GlExtraDrawer>);
#endif
#undef VECTOR_SEQ_CONV
-
- #if 0
- import_array();
- to_python_converter<numpy_boost<Real,1>, custom_numpyBoost_to_py<Real,1> >();
- to_python_converter<numpy_boost<Real,2>, custom_numpyBoost_to_py<Real,2> >();
- to_python_converter<numpy_boost<int,1>, custom_numpyBoost_to_py<int,1> >();
- to_python_converter<numpy_boost<int,2>, custom_numpyBoost_to_py<int,2> >();
- #endif
-
}
=== modified file 'py/wrapper/yadeWrapper.cpp'
--- py/wrapper/yadeWrapper.cpp 2014-04-15 14:45:52 +0000
+++ py/wrapper/yadeWrapper.cpp 2014-05-23 13:05:19 +0000
@@ -63,7 +63,6 @@
#include<locale>
#include<boost/archive/codecvt_null.hpp>
-using namespace boost;
using namespace std;
namespace py = boost::python;
@@ -84,7 +83,7 @@
shared_ptr<Body> pyNext(){
BodyContainer::iterator ret;
while(I!=Iend){ ret=I; ++I; if(*ret) return *ret; }
- PyErr_SetNone(PyExc_StopIteration); python::throw_error_already_set(); /* never reached, but makes the compiler happier */ throw;
+ PyErr_SetNone(PyExc_StopIteration); py::throw_error_already_set(); /* never reached, but makes the compiler happier */ throw;
}
};
@@ -92,8 +91,8 @@
private:
void checkClump(shared_ptr<Body> b){
if (!(b->isClump())){
- PyErr_SetString(PyExc_TypeError,("Error: Body"+lexical_cast<string>(b->getId())+" is not a clump.").c_str());
- python::throw_error_already_set();
+ PyErr_SetString(PyExc_TypeError,("Error: Body"+boost::lexical_cast<string>(b->getId())+" is not a clump.").c_str());
+ py::throw_error_already_set();
}
}
typedef std::map<Body::id_t,Se3r> MemberMap;
@@ -103,12 +102,12 @@
pyBodyContainer(const shared_ptr<BodyContainer>& _proxee): proxee(_proxee){}
shared_ptr<Body> pyGetitem(Body::id_t _id){
int id=(_id>=0 ? _id : proxee->size()+_id);
- if(id<0 || (size_t)id>=proxee->size()){ PyErr_SetString(PyExc_IndexError, "Body id out of range."); python::throw_error_already_set(); /* make compiler happy; never reached */ return shared_ptr<Body>(); }
+ if(id<0 || (size_t)id>=proxee->size()){ PyErr_SetString(PyExc_IndexError, "Body id out of range."); py::throw_error_already_set(); /* make compiler happy; never reached */ return shared_ptr<Body>(); }
else return (*proxee)[id];
}
Body::id_t append(shared_ptr<Body> b){
// shoud be >=0, but Body is by default created with id 0... :-|
- if(b->getId()>=0){ PyErr_SetString(PyExc_IndexError,("Body already has id "+lexical_cast<string>(b->getId())+" set; appending such body (for the second time) is not allowed.").c_str()); python::throw_error_already_set(); }
+ if(b->getId()>=0){ PyErr_SetString(PyExc_IndexError,("Body already has id "+boost::lexical_cast<string>(b->getId())+" set; appending such body (for the second time) is not allowed.").c_str()); py::throw_error_already_set(); }
return proxee->insert(b);
}
vector<Body::id_t> appendList(vector<shared_ptr<Body> > bb){
@@ -152,11 +151,21 @@
Clump::updateProperties(clumpBody, discretization);
return clumpBody->getId();
}
- python::tuple appendClump(vector<shared_ptr<Body> > bb, unsigned int discretization){
+ py::tuple appendClump(vector<shared_ptr<Body> > bb, unsigned int discretization){
// append constituent particles
vector<Body::id_t> ids(appendList(bb));
// clump them together (the clump fcn) and return
- return python::make_tuple(clump(ids, discretization),ids);
+ return py::make_tuple(clump(ids, discretization),ids);
+ }
+ void updateClumpProperties(py::list excludeList,unsigned int discretization){
+ //convert excludeList to a c++ list
+ vector<Body::id_t> excludeListC;
+ for (int ii = 0; ii < py::len(excludeList); ii++) excludeListC.push_back(py::extract<Body::id_t>(excludeList[ii])());
+ FOREACH(const shared_ptr<Body>& b, *proxee){
+ if ( !(std::find(excludeListC.begin(), excludeListC.end(), b->getId()) != excludeListC.end()) ) {
+ if (b->isClump()) Clump::updateProperties(b, discretization);
+ }
+ }
}
void addToClump(vector<Body::id_t> bids, Body::id_t cid, unsigned int discretization){
Scene* scene(Omega::instance().getScene().get()); // get scene
@@ -166,21 +175,21 @@
FOREACH(Body::id_t bid, bids) {
shared_ptr<Body> bp = Body::byId(bid,scene); // get body pointer
if (bp->isClump()){
- if (bp == clp) {PyErr_Warn(PyExc_UserWarning,("Warning: Body "+lexical_cast<string>(bid)+" and clump "+lexical_cast<string>(cid)+" are the same bodies. Body was not added.").c_str()); return;}
+ if (bp == clp) {PyErr_Warn(PyExc_UserWarning,("Warning: Body "+boost::lexical_cast<string>(bid)+" and clump "+boost::lexical_cast<string>(cid)+" are the same bodies. Body was not added.").c_str()); return;}
Clump::add(clp,bp);//add clump bid to clump cid
eraseList.push_back(bid);
}
else if (bp->isClumpMember()){
Body::id_t bpClumpId = bp->clumpId;
shared_ptr<Body> bpClumpPointer = Body::byId(bpClumpId,scene);
- if (bpClumpPointer == clp) {PyErr_Warn(PyExc_UserWarning,("Warning: Body "+lexical_cast<string>(bid)+" is already a clump member of clump "+lexical_cast<string>(cid)+". Body was not added.").c_str()); return;}
+ if (bpClumpPointer == clp) {PyErr_Warn(PyExc_UserWarning,("Warning: Body "+boost::lexical_cast<string>(bid)+" is already a clump member of clump "+boost::lexical_cast<string>(cid)+". Body was not added.").c_str()); return;}
Clump::add(clp,bpClumpPointer);//add clump bpClumpId to clump cid
eraseList.push_back(bpClumpId);
}
else Clump::add(clp,bp);// bp must be a standalone!
}
Clump::updateProperties(clp, discretization);
- FOREACH(Body::id_t bid, eraseList) proxee->erase(bid);//erase old clumps
+ FOREACH(Body::id_t bid, eraseList) proxee->erase(bid,false);//erase old clumps
}
void releaseFromClump(Body::id_t bid, Body::id_t cid, unsigned int discretization){
Scene* scene(Omega::instance().getScene().get()); // get scene
@@ -192,29 +201,29 @@
if (cid == bpClumpId){
const shared_ptr<Clump>& clump=YADE_PTR_CAST<Clump>(clp->shape);
std::map<Body::id_t,Se3r>& members = clump->members;
- if (members.size() == 2) {PyErr_Warn(PyExc_UserWarning,("Warning: Body "+lexical_cast<string>(bid)+" not released from clump "+lexical_cast<string>(cid)+", because number of clump members would get < 2!").c_str()); return;}
+ if (members.size() == 2) {PyErr_Warn(PyExc_UserWarning,("Warning: Body "+boost::lexical_cast<string>(bid)+" not released from clump "+boost::lexical_cast<string>(cid)+", because number of clump members would get < 2!").c_str()); return;}
Clump::del(clp,bp);//release bid from cid
Clump::updateProperties(clp, discretization);
- } else { PyErr_Warn(PyExc_UserWarning,("Warning: Body "+lexical_cast<string>(bid)+" must be a clump member of clump "+lexical_cast<string>(cid)+". Body was not released.").c_str()); return;}
- } else { PyErr_Warn(PyExc_UserWarning,("Warning: Body "+lexical_cast<string>(bid)+" is not a clump member. Body was not released.").c_str()); return;}
+ } else { PyErr_Warn(PyExc_UserWarning,("Warning: Body "+boost::lexical_cast<string>(bid)+" must be a clump member of clump "+boost::lexical_cast<string>(cid)+". Body was not released.").c_str()); return;}
+ } else { PyErr_Warn(PyExc_UserWarning,("Warning: Body "+boost::lexical_cast<string>(bid)+" is not a clump member. Body was not released.").c_str()); return;}
}
- python::list replaceByClumps(python::list ctList, vector<Real> amounts, unsigned int discretization){
- python::list ret;
+ py::list replaceByClumps(py::list ctList, vector<Real> amounts, unsigned int discretization){
+ py::list ret;
Real checkSum = 0.0;
FOREACH(Real amount, amounts) {
if (amount < 0.0) {
PyErr_SetString(PyExc_ValueError,("Error: One or more of given amounts are negative!"));
- python::throw_error_already_set();
+ py::throw_error_already_set();
}
else checkSum += amount;
}
if (checkSum > 1.0){
- PyErr_SetString(PyExc_ValueError,("Error: Sum of amounts "+lexical_cast<string>(checkSum)+" should not be bigger than 1.0!").c_str());
- python::throw_error_already_set();
+ PyErr_SetString(PyExc_ValueError,("Error: Sum of amounts "+boost::lexical_cast<string>(checkSum)+" should not be bigger than 1.0!").c_str());
+ py::throw_error_already_set();
}
- if (python::len(ctList) != (unsigned) amounts.size()) {//avoid unsigned comparison warning
- PyErr_SetString(PyExc_ValueError,("Error: Length of amounts list ("+lexical_cast<string>(amounts.size())+") differs from length of template list ("+lexical_cast<string>(python::len(ctList))+").").c_str());
- python::throw_error_already_set();
+ if (py::len(ctList) != (unsigned) amounts.size()) {//avoid unsigned comparison warning
+ PyErr_SetString(PyExc_ValueError,("Error: Length of amounts list ("+boost::lexical_cast<string>(amounts.size())+") differs from length of template list ("+boost::lexical_cast<string>(py::len(ctList))+").").c_str());
+ py::throw_error_already_set();
}
//set a random generator (code copied from pkg/dem/SpherePack.cpp):
static boost::minstd_rand randGen((int)TimingInfo::getNow(/* get the number even if timing is disabled globally */ true));
@@ -237,10 +246,10 @@
//relPosList: [relPos1,relPos2, ...] (list of vectors)
//extract attributes from python objects:
- python::object ctTmp = ctList[ii];
- int numCM = python::extract<int>(ctTmp.attr("numCM"))();// number of clump members
- python::list relRadListTmp = python::extract<python::list>(ctTmp.attr("relRadii"))();
- python::list relPosListTmp = python::extract<python::list>(ctTmp.attr("relPositions"))();
+ py::object ctTmp = ctList[ii];
+ int numCM = py::extract<int>(ctTmp.attr("numCM"))();// number of clump members
+ py::list relRadListTmp = py::extract<py::list>(ctTmp.attr("relRadii"))();
+ py::list relPosListTmp = py::extract<py::list>(ctTmp.attr("relPositions"))();
//get relative radii and positions; calculate volumes; get balance point: get axis aligned bounding box; get minimum radius;
vector<Real> relRadTmp(numCM), relVolTmp(numCM);
@@ -248,9 +257,9 @@
Vector3r relPosTmpMean = Vector3r::Zero();
Real rMin=1./0.; AlignedBox3r aabb;
for (int jj = 0; jj < numCM; jj++) {
- relRadTmp[jj] = python::extract<Real>(relRadListTmp[jj])();
+ relRadTmp[jj] = py::extract<Real>(relRadListTmp[jj])();
relVolTmp[jj] = (4./3.)*Mathr::PI*pow(relRadTmp[jj],3.);
- relPosTmp[jj] = python::extract<Vector3r>(relPosListTmp[jj])();
+ relPosTmp[jj] = py::extract<Vector3r>(relPosListTmp[jj])();
relPosTmpMean += relPosTmp[jj];
aabb.extend(relPosTmp[jj] + Vector3r::Constant(relRadTmp[jj]));
aabb.extend(relPosTmp[jj] - Vector3r::Constant(relRadTmp[jj]));
@@ -370,23 +379,23 @@
idsTmp[jj] = newSphere->id;
}
//cout << "thread " << omp_get_thread_num() << " unsets locker" << endl;
- #ifdef YADE_OPENMP
+ #ifdef YADE_OPENMP
omp_unset_lock(&locker);//end of critical section
- #endif
+ #endif
Body::id_t newClumpId = clump(idsTmp, discretization);
- ret.append(python::make_tuple(newClumpId,idsTmp));
- erase(b->id);
+ ret.append(py::make_tuple(newClumpId,idsTmp));
+ erase(b->id,false);
}
}
return ret;
}
- Real getRoundness(python::list excludeList){
+ Real getRoundness(py::list excludeList){
Scene* scene(Omega::instance().getScene().get()); // get scene
shared_ptr<Sphere> sph (new Sphere);
int Sph_Index = sph->getClassIndexStatic(); // get sphere index for checking if bodies are spheres
//convert excludeList to a c++ list
vector<Body::id_t> excludeListC;
- for (int ii = 0; ii < python::len(excludeList); ii++) excludeListC.push_back(python::extract<Body::id_t>(excludeList[ii])());
+ for (int ii = 0; ii < py::len(excludeList); ii++) excludeListC.push_back(py::extract<Body::id_t>(excludeList[ii])());
Real RC_sum = 0.0; //sum of local roundnesses
Real R1, R2, vol, dens;
int c = 0; //counter
@@ -420,7 +429,7 @@
vector<Body::id_t> replace(vector<shared_ptr<Body> > bb){proxee->clear(); return appendList(bb);}
long length(){return proxee->size();}
void clear(){proxee->clear();}
- bool erase(Body::id_t id){ return proxee->erase(id); }
+ bool erase(Body::id_t id, bool eraseClumpMembers){ return proxee->erase(id,eraseClumpMembers); }
};
@@ -428,28 +437,28 @@
public:
pyTags(const shared_ptr<Scene> _mb): mb(_mb){}
const shared_ptr<Scene> mb;
- bool hasKey(const string& key){ FOREACH(string val, mb->tags){ if(algorithm::starts_with(val,key+"=")){ return true;} } return false; }
+ bool hasKey(const string& key){ FOREACH(string val, mb->tags){ if(boost::algorithm::starts_with(val,key+"=")){ return true;} } return false; }
string getItem(const string& key){
FOREACH(string& val, mb->tags){
- if(algorithm::starts_with(val,key+"=")){ string val1(val); algorithm::erase_head(val1,key.size()+1); return val1;}
+ if(boost::algorithm::starts_with(val,key+"=")){ string val1(val); boost::algorithm::erase_head(val1,key.size()+1); return val1;}
}
PyErr_SetString(PyExc_KeyError,("Invalid key: "+key+".").c_str());
- python::throw_error_already_set(); /* make compiler happy; never reached */ return string();
+ py::throw_error_already_set(); /* make compiler happy; never reached */ return string();
}
void setItem(const string& key,const string& item){
if(key.find("=")!=string::npos) {
PyErr_SetString(PyExc_KeyError, "Key must not contain the '=' character (implementation limitation; sorry).");
- python::throw_error_already_set();
+ py::throw_error_already_set();
}
- FOREACH(string& val, mb->tags){if(algorithm::starts_with(val,key+"=")){ val=key+"="+item; return; } }
+ FOREACH(string& val, mb->tags){if(boost::algorithm::starts_with(val,key+"=")){ val=key+"="+item; return; } }
mb->tags.push_back(key+"="+item);
}
- python::list keys(){
- python::list ret;
+ py::list keys(){
+ py::list ret;
FOREACH(string val, mb->tags){
size_t i=val.find("=");
if(i==string::npos) throw runtime_error("Tags must be in the key=value format (internal error?)");
- algorithm::erase_tail(val,val.size()-i); ret.append(val);
+ boost::algorithm::erase_tail(val,val.size()-i); ret.append(val);
}
return ret;
}
@@ -464,7 +473,7 @@
shared_ptr<Interaction> pyNext(){
InteractionContainer::iterator ret;
while(I!=Iend){ ret=I; ++I; if((*ret)->isReal()) return *ret; }
- PyErr_SetNone(PyExc_StopIteration); python::throw_error_already_set();
+ PyErr_SetNone(PyExc_StopIteration); py::throw_error_already_set();
throw; // to avoid compiler warning; never reached
//InteractionContainer::iterator ret=I; ++I; return *ret;
}
@@ -477,11 +486,11 @@
pyInteractionIterator pyIter(){return pyInteractionIterator(proxee);}
shared_ptr<Interaction> pyGetitem(vector<Body::id_t> id12){
//if(!PySequence_Check(id12.ptr())) throw invalid_argument("Key must be a tuple");
- //if(python::len(id12)!=2) throw invalid_argument("Key must be a 2-tuple: id1,id2.");
+ //if(py::len(id12)!=2) throw invalid_argument("Key must be a 2-tuple: id1,id2.");
if(id12.size()==2){
//if(max(id12[0],id12[1])>
shared_ptr<Interaction> i=proxee->find(id12[0],id12[1]);
- if(i) return i; else { PyErr_SetString(PyExc_IndexError,"No such interaction"); python::throw_error_already_set(); /* make compiler happy; never reached */ return shared_ptr<Interaction>(); }
+ if(i) return i; else { PyErr_SetString(PyExc_IndexError,"No such interaction"); py::throw_error_already_set(); /* make compiler happy; never reached */ return shared_ptr<Interaction>(); }
}
else if(id12.size()==1){ return (*proxee)[id12[0]];}
else throw invalid_argument("2 integers (id1,id2) or 1 integer (nth) required.");
@@ -489,13 +498,13 @@
/* return nth _real_ iteration from the container (0-based index); this is to facilitate picking random interaction */
shared_ptr<Interaction> pyNth(long n){
long i=0; FOREACH(shared_ptr<Interaction> I, *proxee){ if(!I->isReal()) continue; if(i++==n) return I; }
- PyErr_SetString(PyExc_IndexError,(string("Interaction number out of range (")+lexical_cast<string>(n)+">="+lexical_cast<string>(i)+").").c_str());
- python::throw_error_already_set(); /* make compiler happy; never reached */ return shared_ptr<Interaction>();
+ PyErr_SetString(PyExc_IndexError,(string("Interaction number out of range (")+boost::lexical_cast<string>(n)+">="+boost::lexical_cast<string>(i)+").").c_str());
+ py::throw_error_already_set(); /* make compiler happy; never reached */ return shared_ptr<Interaction>();
}
long len(){return proxee->size();}
void clear(){proxee->clear();}
- python::list withBody(long id){ python::list ret; FOREACH(const shared_ptr<Interaction>& I, *proxee){ if(I->isReal() && (I->getId1()==id || I->getId2()==id)) ret.append(I);} return ret;}
- python::list withBodyAll(long id){ python::list ret; FOREACH(const shared_ptr<Interaction>& I, *proxee){ if(I->getId1()==id || I->getId2()==id) ret.append(I);} return ret; }
+ py::list withBody(long id){ py::list ret; FOREACH(const shared_ptr<Interaction>& I, *proxee){ if(I->isReal() && (I->getId1()==id || I->getId2()==id)) ret.append(I);} return ret;}
+ py::list withBodyAll(long id){ py::list ret; FOREACH(const shared_ptr<Interaction>& I, *proxee){ if(I->getId1()==id || I->getId2()==id) ret.append(I);} return ret; }
long countReal(){ long ret=0; FOREACH(const shared_ptr<Interaction>& I, *proxee){ if(I->isReal()) ret++; } return ret; }
bool serializeSorted_get(){return proxee->serializeSorted;}
void serializeSorted_set(bool ss){proxee->serializeSorted=ss;}
@@ -507,7 +516,7 @@
shared_ptr<Scene> scene;
public:
pyForceContainer(shared_ptr<Scene> _scene): scene(_scene) { }
- void checkId(long id){ if(id<0 || (size_t)id>=scene->bodies->size()){ PyErr_SetString(PyExc_IndexError, "Body id out of range."); python::throw_error_already_set(); /* never reached */ throw; } }
+ void checkId(long id){ if(id<0 || (size_t)id>=scene->bodies->size()){ PyErr_SetString(PyExc_IndexError, "Body id out of range."); py::throw_error_already_set(); /* never reached */ throw; } }
Vector3r force_get(long id, bool sync){ checkId(id); if (!sync) return scene->forces.getForceSingle(id); scene->forces.sync(); return scene->forces.getForce(id);}
Vector3r torque_get(long id, bool sync){ checkId(id); if (!sync) return scene->forces.getTorqueSingle(id); scene->forces.sync(); return scene->forces.getTorque(id);}
Vector3r move_get(long id){ checkId(id); return scene->forces.getMoveSingle(id); }
@@ -528,11 +537,11 @@
shared_ptr<Scene> scene;
public:
pyMaterialContainer(shared_ptr<Scene> _scene): scene(_scene) { }
- shared_ptr<Material> getitem_id(int _id){ int id=(_id>=0 ? _id : scene->materials.size()+_id); if(id<0 || (size_t)id>=scene->materials.size()){ PyErr_SetString(PyExc_IndexError, "Material id out of range."); python::throw_error_already_set(); /* never reached */ throw; } return Material::byId(id,scene); }
+ shared_ptr<Material> getitem_id(int _id){ int id=(_id>=0 ? _id : scene->materials.size()+_id); if(id<0 || (size_t)id>=scene->materials.size()){ PyErr_SetString(PyExc_IndexError, "Material id out of range."); py::throw_error_already_set(); /* never reached */ throw; } return Material::byId(id,scene); }
shared_ptr<Material> getitem_label(string label){
// translate runtime_error to KeyError (instead of RuntimeError) if the material doesn't exist
try { return Material::byLabel(label,scene); }
- catch (std::runtime_error& e){ PyErr_SetString(PyExc_KeyError,e.what()); python::throw_error_already_set(); /* never reached; avoids warning */ throw; }
+ catch (std::runtime_error& e){ PyErr_SetString(PyExc_KeyError,e.what()); py::throw_error_already_set(); /* never reached; avoids warning */ throw; }
}
int append(shared_ptr<Material> m){ scene->materials.push_back(m); m->id=scene->materials.size()-1; return m->id; }
vector<int> appendList(vector<shared_ptr<Material> > mm){ vector<int> ret; FOREACH(shared_ptr<Material>& m, mm) ret.push_back(append(m)); return ret; }
@@ -566,7 +575,7 @@
// a call to this functions would have to be added to pyMaterialContainer::append
#if 0
FOREACH(const shared_ptr<Material>& m, OMEGA.getScene()->materials){
- if(!m->label.empty()) { PyGILState_STATE gstate; gstate = PyGILState_Ensure(); PyRun_SimpleString(("__builtins__."+m->label+"=Omega().materials["+lexical_cast<string>(m->id)+"]").c_str()); PyGILState_Release(gstate); }
+ if(!m->label.empty()) { PyGILState_STATE gstate; gstate = PyGILState_Ensure(); PyRun_SimpleString(("__builtins__."+m->label+"=Omega().materials["+boost::lexical_cast<string>(m->id)+"]").c_str()); PyGILState_Release(gstate); }
}
#endif
FOREACH(const shared_ptr<Engine>& e, OMEGA.getScene()->engines){
@@ -588,11 +597,11 @@
#undef _TRY_DISPATCHER
}
}
- python::object labeled_engine_get(string label){
+ py::object labeled_engine_get(string label){
FOREACH(const shared_ptr<Engine>& e, OMEGA.getScene()->engines){
- #define _DO_FUNCTORS(functors,FunctorT){ FOREACH(const shared_ptr<FunctorT>& f, functors){ if(f->label==label) return python::object(f); }}
+ #define _DO_FUNCTORS(functors,FunctorT){ FOREACH(const shared_ptr<FunctorT>& f, functors){ if(f->label==label) return py::object(f); }}
#define _TRY_DISPATCHER(DispatcherT) { DispatcherT* d=dynamic_cast<DispatcherT*>(e.get()); if(d){ _DO_FUNCTORS(d->functors,DispatcherT::FunctorType); } }
- if(e->label==label){ return python::object(e); }
+ if(e->label==label){ return py::object(e); }
_TRY_DISPATCHER(BoundDispatcher); _TRY_DISPATCHER(IGeomDispatcher); _TRY_DISPATCHER(IPhysDispatcher); _TRY_DISPATCHER(LawDispatcher);
InteractionLoop* id=dynamic_cast<InteractionLoop*>(e.get());
if(id){
@@ -644,7 +653,7 @@
OMEGA.run();
// timespec t1,t2; t1.tv_sec=0; t1.tv_nsec=40000000; /* 40 ms */
// while(!OMEGA.isRunning()) nanosleep(&t1,&t2); // wait till we start, so that calling wait() immediately afterwards doesn't return immediately
- LOG_DEBUG("RUN"<<((scene->stopAtIter-scene->iter)>0?string(" ("+lexical_cast<string>(scene->stopAtIter-scene->iter)+" to go)"):string(""))<<"!");
+ LOG_DEBUG("RUN"<<((scene->stopAtIter-scene->iter)>0?string(" ("+boost::lexical_cast<string>(scene->stopAtIter-scene->iter)+" to go)"):string(""))<<"!");
if(doWait) wait();
}
void pause(){Py_BEGIN_ALLOW_THREADS; OMEGA.pause(); Py_END_ALLOW_THREADS; LOG_DEBUG("PAUSE!");}
@@ -656,7 +665,7 @@
LOG_ERROR("Simulation error encountered."); OMEGA.simulationLoop->workerThrew=false; throw OMEGA.simulationLoop->workerException;
}
bool isRunning(){ return OMEGA.isRunning(); }
- python::object get_filename(){ string f=OMEGA.sceneFile; if(f.size()>0) return python::object(f); return python::object();}
+ py::object get_filename(){ string f=OMEGA.sceneFile; if(f.size()>0) return py::object(f); return py::object();}
void load(std::string fileName,bool quiet=false) {
Py_BEGIN_ALLOW_THREADS; OMEGA.stop(); Py_END_ALLOW_THREADS;
OMEGA.loadSimulation(fileName,quiet);
@@ -666,12 +675,12 @@
void reload(bool quiet=false){ load(OMEGA.sceneFile,quiet);}
void saveTmp(string mark="", bool quiet=false){ save(":memory:"+mark,quiet);}
void loadTmp(string mark="", bool quiet=false){ load(":memory:"+mark,quiet);}
- python::list lsTmp(){ python::list ret; typedef pair<std::string,string> strstr; FOREACH(const strstr& sim,OMEGA.memSavedSimulations){ string mark=sim.first; boost::algorithm::replace_first(mark,":memory:",""); ret.append(mark); } return ret; }
+ py::list lsTmp(){ py::list ret; typedef pair<std::string,string> strstr; FOREACH(const strstr& sim,OMEGA.memSavedSimulations){ string mark=sim.first; boost::algorithm::replace_first(mark,":memory:",""); ret.append(mark); } return ret; }
void tmpToFile(string mark, string filename){
if(OMEGA.memSavedSimulations.count(":memory:"+mark)==0) throw runtime_error("No memory-saved simulation named "+mark);
- iostreams::filtering_ostream out;
- if(algorithm::ends_with(filename,".bz2")) out.push(iostreams::bzip2_compressor());
- out.push(iostreams::file_sink(filename));
+ boost::iostreams::filtering_ostream out;
+ if(boost::algorithm::ends_with(filename,".bz2")) out.push(boost::iostreams::bzip2_compressor());
+ out.push(boost::iostreams::file_sink(filename));
if(!out.good()) throw runtime_error("Error while opening file `"+filename+"' for writing.");
LOG_INFO("Saving :memory:"<<mark<<" to "<<filename);
out<<OMEGA.memSavedSimulations[":memory:"+mark];
@@ -710,8 +719,8 @@
// OMEGA.sceneFile=fileName; // done in Omega::saveSimulation;
}
- python::list miscParams_get(){
- python::list ret;
+ py::list miscParams_get(){
+ py::list ret;
FOREACH(shared_ptr<Serializable>& s, OMEGA.getScene()->miscParams){
ret.append(s);
}
@@ -745,8 +754,8 @@
pyMaterialContainer materials_get(void){return pyMaterialContainer(OMEGA.getScene());}
- python::list listChildClassesNonrecursive(const string& base){
- python::list ret;
+ py::list listChildClassesNonrecursive(const string& base){
+ py::list ret;
for(map<string,DynlibDescriptor>::const_iterator di=Omega::instance().getDynlibsDescriptor().begin();di!=Omega::instance().getDynlibsDescriptor().end();++di) if (Omega::instance().isInheritingFrom((*di).first,base)) ret.append(di->first);
return ret;
}
@@ -755,9 +764,9 @@
return (Omega::instance().isInheritingFrom_recursive(child,base));
}
- python::list plugins_get(){
+ py::list plugins_get(){
const map<string,DynlibDescriptor>& plugins=Omega::instance().getDynlibsDescriptor();
- std::pair<string,DynlibDescriptor> p; python::list ret;
+ std::pair<string,DynlibDescriptor> p; py::list ret;
FOREACH(p, plugins) ret.append(p.first);
return ret;
}
@@ -767,7 +776,7 @@
void interactionContainer_set(string clss){
Scene* rb=OMEGA.getScene().get();
if(rb->interactions->size()>0) throw std::runtime_error("Interaction container not empty, will not change its class.");
- shared_ptr<InteractionContainer> ic=dynamic_pointer_cast<InteractionContainer>(ClassFactory::instance().createShared(clss));
+ shared_ptr<InteractionContainer> ic=boost::dynamic_pointer_cast<InteractionContainer>(ClassFactory::instance().createShared(clss));
rb->interactions=ic;
}
string interactionContainer_get(string clss){ return OMEGA.getScene()->interactions->getClassName(); }
@@ -775,7 +784,7 @@
void bodyContainer_set(string clss){
Scene* rb=OMEGA.getScene().get();
if(rb->bodies->size()>0) throw std::runtime_error("Body container not empty, will not change its class.");
- shared_ptr<BodyContainer> bc=dynamic_pointer_cast<BodyContainer>(ClassFactory::instance().createShared(clss));
+ shared_ptr<BodyContainer> bc=boost::dynamic_pointer_cast<BodyContainer>(ClassFactory::instance().createShared(clss));
rb->bodies=bc;
}
string bodyContainer_get(string clss){ return OMEGA.getScene()->bodies->getClassName(); }
@@ -815,18 +824,18 @@
BOOST_PYTHON_MODULE(wrapper)
{
- python::scope().attr("__doc__")="Wrapper for c++ internals of yade.";
+ py::scope().attr("__doc__")="Wrapper for c++ internals of yade.";
YADE_SET_DOCSTRING_OPTS;
- python::enum_<yade::Attr::flags>("AttrFlags")
+ py::enum_<yade::Attr::flags>("AttrFlags")
.value("noSave",yade::Attr::noSave)
.value("readonly",yade::Attr::readonly)
.value("triggerPostLoad",yade::Attr::triggerPostLoad)
.value("noResize",yade::Attr::noResize)
;
- python::class_<pyOmega>("Omega")
+ py::class_<pyOmega>("Omega")
.add_property("iter",&pyOmega::iter,"Get current step number")
.add_property("subStep",&pyOmega::subStep,"Get the current subStep number (only meaningful if O.subStepping==True); -1 when outside the loop, otherwise either 0 (O.subStepping==False) or number of engine to be run (O.subStepping==True)")
.add_property("subStepping",&pyOmega::subStepping_get,&pyOmega::subStepping_set,"Get/set whether subStepping is active.")
@@ -844,9 +853,9 @@
.def("loadTmp",&pyOmega::loadTmp,(py::arg("mark")="",py::arg("quiet")=false),"Load simulation previously stored in memory by saveTmp. *mark* optionally distinguishes multiple saved simulations")
.def("saveTmp",&pyOmega::saveTmp,(py::arg("mark")="",py::arg("quiet")=false),"Save simulation to memory (disappears at shutdown), can be loaded later with loadTmp. *mark* optionally distinguishes different memory-saved simulations.")
.def("lsTmp",&pyOmega::lsTmp,"Return list of all memory-saved simulations.")
- .def("tmpToFile",&pyOmega::tmpToFile,(python::arg("fileName"),python::arg("mark")=""),"Save XML of :yref:`saveTmp<Omega.saveTmp>`'d simulation into *fileName*.")
- .def("tmpToString",&pyOmega::tmpToString,(python::arg("mark")=""),"Return XML of :yref:`saveTmp<Omega.saveTmp>`'d simulation as string.")
- .def("run",&pyOmega::run,(python::arg("nSteps")=-1,python::arg("wait")=false),"Run the simulation. *nSteps* how many steps to run, then stop (if positive); *wait* will cause not returning to python until simulation will have stopped.")
+ .def("tmpToFile",&pyOmega::tmpToFile,(py::arg("fileName"),py::arg("mark")=""),"Save XML of :yref:`saveTmp<Omega.saveTmp>`'d simulation into *fileName*.")
+ .def("tmpToString",&pyOmega::tmpToString,(py::arg("mark")=""),"Return XML of :yref:`saveTmp<Omega.saveTmp>`'d simulation as string.")
+ .def("run",&pyOmega::run,(py::arg("nSteps")=-1,py::arg("wait")=false),"Run the simulation. *nSteps* how many steps to run, then stop (if positive); *wait* will cause not returning to python until simulation will have stopped.")
.def("pause",&pyOmega::pause,"Stop simulation execution. (May be called from within the loop, and it will stop after the current step).")
.def("step",&pyOmega::step,"Advance the simulation by one step. Returns after the step will have finished.")
.def("wait",&pyOmega::wait,"Don't return until the simulation will have been paused. (Returns immediately if not running).")
@@ -860,7 +869,7 @@
.def("switchToScene",&pyOmega::switchToScene,"Switch to defined scene. Default scene has number 0, other scenes have to be created by addScene method.")
.def("switchScene",&pyOmega::switchScene,"Switch to alternative simulation (while keeping the old one). Calling the function again switches back to the first one. Note that most variables from the first simulation will still refer to the first simulation even after the switch\n(e.g. b=O.bodies[4]; O.switchScene(); [b still refers to the body in the first simulation here])")
.def("sceneToString",&pyOmega::sceneToString,"Return the entire scene as a string. Equivalent to using O.save(...) except that the scene goes to a string instead of a file. (see also stringToScene())")
- .def("stringToScene",&pyOmega::stringToScene,(python::arg("mark")=""),"Load simulation from a string passed as argument (see also sceneToString).")
+ .def("stringToScene",&pyOmega::stringToScene,(py::arg("mark")=""),"Load simulation from a string passed as argument (see also sceneToString).")
.def("labeledEngine",&pyOmega::labeled_engine_get,"Return instance of engine/functor with the given label. This function shouldn't be called by the user directly; every ehange in O.engines will assign respective global python variables according to labels.\n\nFor example:\n\n\t *O.engines=[InsertionSortCollider(label='collider')]*\n\n\t *collider.nBins=5 # collider has become a variable after assignment to O.engines automatically*")
.def("resetTime",&pyOmega::resetTime,"Reset simulation time: step number, virtual and real time. (Doesn't touch anything else, including timings).")
.def("plugins",&pyOmega::plugins_get,"Return list of all plugins registered in the class factory.")
@@ -883,35 +892,36 @@
.add_property("numThreads",&pyOmega::numThreads_get /* ,&pyOmega::numThreads_set*/ ,"Get maximum number of threads openMP can use.")
.add_property("cell",&pyOmega::cell_get,"Periodic cell of the current scene (None if the scene is aperiodic).")
.add_property("periodic",&pyOmega::periodic_get,&pyOmega::periodic_set,"Get/set whether the scene is periodic or not (True/False).")
- .def("exitNoBacktrace",&pyOmega::exitNoBacktrace,(python::arg("status")=0),"Disable SEGV handler and exit, optionally with given status number.")
+ .def("exitNoBacktrace",&pyOmega::exitNoBacktrace,(py::arg("status")=0),"Disable SEGV handler and exit, optionally with given status number.")
.def("disableGdb",&pyOmega::disableGdb,"Revert SEGV and ABRT handlers to system defaults.")
.def("runEngine",&pyOmega::runEngine,"Run given engine exactly once; simulation time, step number etc. will not be incremented (use only if you know what you do).")
.def("tmpFilename",&pyOmega::tmpFilename,"Return unique name of file in temporary directory which will be deleted when yade exits.")
;
- python::class_<pyTags>("TagsWrapper","Container emulating dictionary semantics for accessing tags associated with simulation. Tags are accesed by strings.",python::init<pyTags&>())
+ py::class_<pyTags>("TagsWrapper","Container emulating dictionary semantics for accessing tags associated with simulation. Tags are accesed by strings.",py::init<pyTags&>())
.def("__getitem__",&pyTags::getItem)
.def("__setitem__",&pyTags::setItem)
.def("keys",&pyTags::keys)
.def("has_key",&pyTags::hasKey);
- python::class_<pyBodyContainer>("BodyContainer",python::init<pyBodyContainer&>())
+ py::class_<pyBodyContainer>("BodyContainer",py::init<pyBodyContainer&>())
.def("__getitem__",&pyBodyContainer::pyGetitem)
.def("__len__",&pyBodyContainer::length)
.def("__iter__",&pyBodyContainer::pyIter)
.def("append",&pyBodyContainer::append,"Append one Body instance, return its id.")
.def("append",&pyBodyContainer::appendList,"Append list of Body instance, return list of ids")
- .def("appendClumped",&pyBodyContainer::appendClump,(python::arg("discretization")=0),"Append given list of bodies as a clump (rigid aggregate); returns a tuple of ``(clumpId,[memberId1,memberId2,...])``. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`).")
- .def("clump",&pyBodyContainer::clump,(python::arg("discretization")=0),"Clump given bodies together (creating a rigid aggregate); returns ``clumpId``. Clump masses and inertia are adapted automatically when discretization>0. If clump members are overlapping this is done by integration/summation over mass points using a regular grid of cells (number of grid cells in one direction is defined as $R_{min}/discretization$, where $R_{min}$ is minimum clump member radius). For non-overlapping members inertia of the clump is the sum of inertias from members. If discretization<=0 sum of inertias from members is used (faster, but inaccurate).")
- .def("addToClump",&pyBodyContainer::addToClump,(python::arg("discretization")=0),"Add body b (or a list of bodies) to an existing clump c. c must be clump and b may not be a clump member of c. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`).\n\nSee :ysrc:`examples/clumps/addToClump-example.py` for an example script.\n\n.. note:: If b is a clump itself, then all members will be added to c and b will be deleted. If b is a clump member of clump d, then all members from d will be added to c and d will be deleted. If you need to add just clump member b, :yref:`release<BodyContainer.releaseFromClump>` this member from d first.")
- .def("releaseFromClump",&pyBodyContainer::releaseFromClump,(python::arg("discretization")=0),"Release body b from clump c. b must be a clump member of c. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`).\n\nSee :ysrc:`examples/clumps/releaseFromClump-example.py` for an example script.\n\n.. note:: If c contains only 2 members b will not be released and a warning will appear. In this case clump c should be :yref:`erased<BodyContainer.erase>`.")
- .def("replaceByClumps",&pyBodyContainer::replaceByClumps,(python::arg("discretization")=0),"Replace spheres by clumps using a list of clump templates and a list of amounts; returns a list of tuples: ``[(clumpId1,[memberId1,memberId2,...]),(clumpId2,[memberId1,memberId2,...]),...]``. A new clump will have the same volume as the sphere, that was replaced. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`). \n\n\t *O.bodies.replaceByClumps( [utils.clumpTemplate([1,1],[.5,.5])] , [.9] ) #will replace 90 % of all standalone spheres by 'dyads'*\n\nSee :ysrc:`examples/clumps/replaceByClumps-example.py` for an example script.")
- .def("getRoundness",&pyBodyContainer::getRoundness,(python::arg("excludeList")=python::list()),"Returns roundness coefficient RC = R2/R1. R1 is the theoretical radius of a sphere, with same volume as clump. R2 is the minimum radius of a sphere, that imbeds clump. If just spheres are present RC = 1. If clumps are present 0 < RC < 1. Bodies can be excluded from the calculation by giving a list of ids: *O.bodies.getRoundness([ids])*.\n\nSee :ysrc:`examples/clumps/replaceByClumps-example.py` for an example script.")
+ .def("appendClumped",&pyBodyContainer::appendClump,(py::arg("discretization")=0),"Append given list of bodies as a clump (rigid aggregate); returns a tuple of ``(clumpId,[memberId1,memberId2,...])``. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`).")
+ .def("clump",&pyBodyContainer::clump,(py::arg("discretization")=0),"Clump given bodies together (creating a rigid aggregate); returns ``clumpId``. Clump masses and inertia are adapted automatically when discretization>0. If clump members are overlapping this is done by integration/summation over mass points using a regular grid of cells (number of grid cells in one direction is defined as $R_{min}/discretization$, where $R_{min}$ is minimum clump member radius). For non-overlapping members inertia of the clump is the sum of inertias from members. If discretization<=0 sum of inertias from members is used (faster, but inaccurate).")
+ .def("updateClumpProperties",&pyBodyContainer::updateClumpProperties,(py::arg("excludeList")=py::list(),py::arg("discretization")=5),"Update clump properties mass, volume and inertia (for details of 'discretization' value see :yref:`clump()<BodyContainer.clump>`). Clumps can be excluded from the calculation by giving a list of ids: *O.bodies.updateProperties([ids])*.")
+ .def("addToClump",&pyBodyContainer::addToClump,(py::arg("discretization")=0),"Add body b (or a list of bodies) to an existing clump c. c must be clump and b may not be a clump member of c. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`).\n\nSee :ysrc:`examples/clumps/addToClump-example.py` for an example script.\n\n.. note:: If b is a clump itself, then all members will be added to c and b will be deleted. If b is a clump member of clump d, then all members from d will be added to c and d will be deleted. If you need to add just clump member b, :yref:`release<BodyContainer.releaseFromClump>` this member from d first.")
+ .def("releaseFromClump",&pyBodyContainer::releaseFromClump,(py::arg("discretization")=0),"Release body b from clump c. b must be a clump member of c. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`).\n\nSee :ysrc:`examples/clumps/releaseFromClump-example.py` for an example script.\n\n.. note:: If c contains only 2 members b will not be released and a warning will appear. In this case clump c should be :yref:`erased<BodyContainer.erase>`.")
+ .def("replaceByClumps",&pyBodyContainer::replaceByClumps,(py::arg("discretization")=0),"Replace spheres by clumps using a list of clump templates and a list of amounts; returns a list of tuples: ``[(clumpId1,[memberId1,memberId2,...]),(clumpId2,[memberId1,memberId2,...]),...]``. A new clump will have the same volume as the sphere, that was replaced. Clump masses and inertia are adapted automatically (for details see :yref:`clump()<BodyContainer.clump>`). \n\n\t *O.bodies.replaceByClumps( [utils.clumpTemplate([1,1],[.5,.5])] , [.9] ) #will replace 90 % of all standalone spheres by 'dyads'*\n\nSee :ysrc:`examples/clumps/replaceByClumps-example.py` for an example script.")
+ .def("getRoundness",&pyBodyContainer::getRoundness,(py::arg("excludeList")=py::list()),"Returns roundness coefficient RC = R2/R1. R1 is the theoretical radius of a sphere, with same volume as clump. R2 is the minimum radius of a sphere, that imbeds clump. If just spheres are present RC = 1. If clumps are present 0 < RC < 1. Bodies can be excluded from the calculation by giving a list of ids: *O.bodies.getRoundness([ids])*.\n\nSee :ysrc:`examples/clumps/replaceByClumps-example.py` for an example script.")
.def("clear", &pyBodyContainer::clear,"Remove all bodies (interactions not checked)")
- .def("erase", &pyBodyContainer::erase,"Erase body with the given id; all interaction will be deleted by InteractionLoop in the next step.")
+ .def("erase", &pyBodyContainer::erase,(py::arg("eraseClumpMembers")=0),"Erase body with the given id; all interaction will be deleted by InteractionLoop in the next step. If a clump is erased use *O.bodies.erase(clumpId,True)* to erase the clump AND its members.")
.def("replace",&pyBodyContainer::replace);
- python::class_<pyBodyIterator>("BodyIterator",python::init<pyBodyIterator&>())
+ py::class_<pyBodyIterator>("BodyIterator",py::init<pyBodyIterator&>())
.def("__iter__",&pyBodyIterator::pyIter)
.def("next",&pyBodyIterator::pyNext);
- python::class_<pyInteractionContainer>("InteractionContainer","Access to :yref:`interactions<Interaction>` of simulation, by using \n\n#. id's of both :yref:`Bodies<Body>` of the interactions, e.g. ``O.interactions[23,65]``\n#. iteraction over the whole container::\n\n\tfor i in O.interactions: print i.id1,i.id2\n\n.. note::\n\tIteration silently skips interactions that are not :yref:`real<Interaction.isReal>`.",python::init<pyInteractionContainer&>())
+ py::class_<pyInteractionContainer>("InteractionContainer","Access to :yref:`interactions<Interaction>` of simulation, by using \n\n#. id's of both :yref:`Bodies<Body>` of the interactions, e.g. ``O.interactions[23,65]``\n#. iteraction over the whole container::\n\n\tfor i in O.interactions: print i.id1,i.id2\n\n.. note::\n\tIteration silently skips interactions that are not :yref:`real<Interaction.isReal>`.",py::init<pyInteractionContainer&>())
.def("__iter__",&pyInteractionContainer::pyIter)
.def("__getitem__",&pyInteractionContainer::pyGetitem)
.def("__len__",&pyInteractionContainer::len)
@@ -923,28 +933,28 @@
.def("erase",&pyInteractionContainer::erase,"Erase one interaction, given by id1, id2 (internally, ``requestErase`` is called -- the interaction might still exist as potential, if the :yref:`Collider` decides so).")
.add_property("serializeSorted",&pyInteractionContainer::serializeSorted_get,&pyInteractionContainer::serializeSorted_set)
.def("clear",&pyInteractionContainer::clear,"Remove all interactions, and invalidate persistent collider data (if the collider supports it).");
- python::class_<pyInteractionIterator>("InteractionIterator",python::init<pyInteractionIterator&>())
+ py::class_<pyInteractionIterator>("InteractionIterator",py::init<pyInteractionIterator&>())
.def("__iter__",&pyInteractionIterator::pyIter)
.def("next",&pyInteractionIterator::pyNext);
- python::class_<pyForceContainer>("ForceContainer",python::init<pyForceContainer&>())
- .def("f",&pyForceContainer::force_get,(python::arg("id"),python::arg("sync")=false),"Force applied on body. For clumps in openMP, synchronize the force container with sync=True, else the value will be wrong.")
- .def("t",&pyForceContainer::torque_get,(python::arg("id"),python::arg("sync")=false),"Torque applied on body. For clumps in openMP, synchronize the force container with sync=True, else the value will be wrong.")
- .def("m",&pyForceContainer::torque_get,(python::arg("id"),python::arg("sync")=false),"Deprecated alias for t (torque).")
- .def("move",&pyForceContainer::move_get,(python::arg("id")),"Displacement applied on body.")
- .def("rot",&pyForceContainer::rot_get,(python::arg("id")),"Rotation applied on body.")
- .def("addF",&pyForceContainer::force_add,(python::arg("id"),python::arg("f"),python::arg("permanent")=false),"Apply force on body (accumulates).\n\n # If permanent=false (default), the force applies for one iteration, then it is reset by ForceResetter. \n # If permanent=true, it persists over iterations, until it is overwritten by another call to addF(id,f,True) or removed by reset(resetAll=True). The permanent force on a body can be checked with permF(id).")
- .def("addT",&pyForceContainer::torque_add,(python::arg("id"),python::arg("t"),python::arg("permanent")=false),"Apply torque on body (accumulates). \n\n # If permanent=false (default), the torque applies for one iteration, then it is reset by ForceResetter. \n # If permanent=true, it persists over iterations, until it is overwritten by another call to addT(id,f,True) or removed by reset(resetAll=True). The permanent torque on a body can be checked with permT(id).")
- .def("permF",&pyForceContainer::permForce_get,(python::arg("id")),"read the value of permanent force on body (set with setPermF()).")
- .def("permT",&pyForceContainer::permTorque_get,(python::arg("id")),"read the value of permanent torque on body (set with setPermT()).")
- .def("addMove",&pyForceContainer::move_add,(python::arg("id"),python::arg("m")),"Apply displacement on body (accumulates).")
- .def("addRot",&pyForceContainer::rot_add,(python::arg("id"),python::arg("r")),"Apply rotation on body (accumulates).")
- .def("reset",&pyForceContainer::reset,(python::arg("resetAll")=true),"Reset the force container, including user defined permanent forces/torques. resetAll=False will keep permanent forces/torques unchanged.")
+ py::class_<pyForceContainer>("ForceContainer",py::init<pyForceContainer&>())
+ .def("f",&pyForceContainer::force_get,(py::arg("id"),py::arg("sync")=false),"Force applied on body. For clumps in openMP, synchronize the force container with sync=True, else the value will be wrong.")
+ .def("t",&pyForceContainer::torque_get,(py::arg("id"),py::arg("sync")=false),"Torque applied on body. For clumps in openMP, synchronize the force container with sync=True, else the value will be wrong.")
+ .def("m",&pyForceContainer::torque_get,(py::arg("id"),py::arg("sync")=false),"Deprecated alias for t (torque).")
+ .def("move",&pyForceContainer::move_get,(py::arg("id")),"Displacement applied on body.")
+ .def("rot",&pyForceContainer::rot_get,(py::arg("id")),"Rotation applied on body.")
+ .def("addF",&pyForceContainer::force_add,(py::arg("id"),py::arg("f"),py::arg("permanent")=false),"Apply force on body (accumulates).\n\n # If permanent=false (default), the force applies for one iteration, then it is reset by ForceResetter. \n # If permanent=true, it persists over iterations, until it is overwritten by another call to addF(id,f,True) or removed by reset(resetAll=True). The permanent force on a body can be checked with permF(id).")
+ .def("addT",&pyForceContainer::torque_add,(py::arg("id"),py::arg("t"),py::arg("permanent")=false),"Apply torque on body (accumulates). \n\n # If permanent=false (default), the torque applies for one iteration, then it is reset by ForceResetter. \n # If permanent=true, it persists over iterations, until it is overwritten by another call to addT(id,f,True) or removed by reset(resetAll=True). The permanent torque on a body can be checked with permT(id).")
+ .def("permF",&pyForceContainer::permForce_get,(py::arg("id")),"read the value of permanent force on body (set with setPermF()).")
+ .def("permT",&pyForceContainer::permTorque_get,(py::arg("id")),"read the value of permanent torque on body (set with setPermT()).")
+ .def("addMove",&pyForceContainer::move_add,(py::arg("id"),py::arg("m")),"Apply displacement on body (accumulates).")
+ .def("addRot",&pyForceContainer::rot_add,(py::arg("id"),py::arg("r")),"Apply rotation on body (accumulates).")
+ .def("reset",&pyForceContainer::reset,(py::arg("resetAll")=true),"Reset the force container, including user defined permanent forces/torques. resetAll=False will keep permanent forces/torques unchanged.")
.def("getPermForceUsed",&pyForceContainer::getPermForceUsed,"Check wether permanent forces are present.")
.add_property("syncCount",&pyForceContainer::syncCount_get,&pyForceContainer::syncCount_set,"Number of synchronizations of ForceContainer (cummulative); if significantly higher than number of steps, there might be unnecessary syncs hurting performance.")
;
- python::class_<pyMaterialContainer>("MaterialContainer","Container for :yref:`Materials<Material>`. A material can be accessed using \n\n #. numerical index in range(0,len(cont)), like cont[2]; \n #. textual label that was given to the material, like cont['steel']. This etails traversing all materials and should not be used frequently.",python::init<pyMaterialContainer&>())
+ py::class_<pyMaterialContainer>("MaterialContainer","Container for :yref:`Materials<Material>`. A material can be accessed using \n\n #. numerical index in range(0,len(cont)), like cont[2]; \n #. textual label that was given to the material, like cont['steel']. This etails traversing all materials and should not be used frequently.",py::init<pyMaterialContainer&>())
.def("append",&pyMaterialContainer::append,"Add new shared :yref:`Material`; changes its id and return it.")
.def("append",&pyMaterialContainer::appendList,"Append list of :yref:`Material` instances, return list of ids.")
.def("index",&pyMaterialContainer::index,"Return id of material, given its label.")
@@ -952,14 +962,14 @@
.def("__getitem__",&pyMaterialContainer::getitem_label)
.def("__len__",&pyMaterialContainer::len);
- python::class_<STLImporter>("STLImporter").def("ymport",&STLImporter::import);
+ py::class_<STLImporter>("STLImporter").def("ymport",&STLImporter::import);
//////////////////////////////////////////////////////////////
///////////// proxyless wrappers
- Serializable().pyRegisterClass(python::scope());
-
- python::class_<TimingDeltas, shared_ptr<TimingDeltas>, noncopyable >("TimingDeltas").add_property("data",&TimingDeltas::pyData,"Get timing data as list of tuples (label, execTime[nsec], execCount) (one tuple per checkpoint)").def("reset",&TimingDeltas::reset,"Reset timing information");
-
- python::scope().attr("O")=pyOmega();
+ Serializable().pyRegisterClass(py::scope());
+
+ py::class_<TimingDeltas, shared_ptr<TimingDeltas>, boost::noncopyable >("TimingDeltas").add_property("data",&TimingDeltas::pyData,"Get timing data as list of tuples (label, execTime[nsec], execCount) (one tuple per checkpoint)").def("reset",&TimingDeltas::reset,"Reset timing information");
+
+ py::scope().attr("O")=pyOmega();
}
=== modified file 'py/ymport.py'
--- py/ymport.py 2014-01-16 09:59:51 +0000
+++ py/ymport.py 2014-05-20 06:35:16 +0000
@@ -48,11 +48,11 @@
raise RuntimeError("Please, specify a correct format output!");
return ret
-def textClumps(fileName,shift=Vector3.Zero,scale=1.0,**kw):
+def textClumps(fileName,shift=Vector3.Zero,discretization=0,orientation=Quaternion.Identity,scale=1.0,**kw):
"""Load clumps-members from file, insert them to the simulation.
:param str filename: file name
- :param str format: the name of output format. Supported `x_y_z_r`(default), `x_y_z_r_matId`
+ :param str format: the name of output format. Supported `x_y_z_r`(default), `x_y_z_r_clumpId`
:param [float,float,float] shift: [X,Y,Z] parameter moves the specimen.
:param float scale: factor scales the given data.
:param \*\*kw: (unused keyword arguments) is passed to :yref:`yade.utils.sphere`
@@ -71,21 +71,19 @@
for line in lines:
data = line.split()
if (data[0][0] == "#"): continue
- pos = Vector3(float(data[0]),float(data[1]),float(data[2]))
+ pos = orientation*Vector3(float(data[0]),float(data[1]),float(data[2]))
if (newClumpId<0 or newClumpId==int(data[4])):
idD = curClump.append(utils.sphere(shift+scale*pos,scale*float(data[3]),**kw))
newClumpId = int(data[4])
- ret.append(idD)
else:
newClumpId = int(data[4])
- O.bodies.appendClumped(curClump)
+ ret.append(O.bodies.appendClumped(curClump,discretization=discretization))
curClump=[]
idD = curClump.append(utils.sphere(shift+scale*pos,scale*float(data[3]),**kw))
- ret.append(idD)
if (len(curClump)<>0):
- O.bodies.appendClumped(curClump)
+ ret.append(O.bodies.appendClumped(curClump,discretization=discretization))
return ret
def text(fileName,shift=Vector3.Zero,scale=1.0,**kw):