yade-dev team mailing list archive
-
yade-dev team
-
Mailing list archive
-
Message #11447
[Branch ~yade-pkg/yade/git-trunk] Rev 3443: Merge github.com:yade/trunk into chaoUnsat
Merge authors:
Anton Gladky (gladky-anton)
Anton Gladky (gladky-anton)
Bruno Chareyre (bruno-chareyre)
Jan Stránský (honzik)
Kneib François (francois-kneib)
------------------------------------------------------------
revno: 3443 [merge]
committer: Chao Yuan <chaoyuan2012@xxxxxxxxx>
timestamp: Wed 2014-07-09 09:07:14 +0200
message:
Merge github.com:yade/trunk into chaoUnsat
modified:
CMakeLists.txt
ChangeLog
core/Body.cpp
core/Body.hpp
core/BodyContainer.hpp
core/Clump.cpp
core/Clump.hpp
core/Dispatcher.cpp
core/Dispatcher.hpp
core/EnergyTracker.hpp
core/Engine.hpp
core/FileGenerator.cpp
core/ForceContainer.hpp
core/Functor.hpp
core/InteractionContainer.hpp
core/Material.cpp
core/Material.hpp
core/Omega.cpp
core/Omega.hpp
core/Scene.cpp
core/State.cpp
core/ThreadRunner.cpp
core/Timing.hpp
core/corePlugins.cpp
core/main/pyboot.cpp
doc/sphinx/installation.rst
gui/qt4/GLViewer.cpp
gui/qt4/GLViewer.hpp
gui/qt4/GLViewerDisplay.cpp
gui/qt4/GLViewerMouse.cpp
gui/qt4/_GLViewer.cpp
lib/base/Logging.hpp
lib/base/Math.hpp
lib/base/openmp-accu.hpp
lib/factory/ClassFactory.hpp
lib/factory/DynLibManager.cpp
lib/factory/DynLibManager.hpp
lib/import/STLReader.hpp
lib/import/utils.hpp
lib/multimethods/DynLibDispatcher.hpp
lib/multimethods/FunctorWrapper.hpp
lib/opengl/GLUtils.hpp
lib/pyutil/doc_opts.hpp
lib/pyutil/numpy_boost.hpp
lib/pyutil/raw_constructor.hpp
lib/serialization/Serializable.hpp
lib/smoothing/WeightedAverage2d.hpp
lib/triangulation/FlowBoundingSphere.hpp
lib/triangulation/FlowBoundingSphere.ipp
lib/triangulation/FlowBoundingSphereLinSolv.hpp
lib/triangulation/FlowBoundingSphereLinSolv.ipp
lib/triangulation/KinematicLocalisationAnalyser.cpp
lib/triangulation/KinematicLocalisationAnalyser.hpp
lib/triangulation/Network.ipp
lib/triangulation/PeriodicFlowLinSolv.hpp
lib/triangulation/PeriodicFlowLinSolv.ipp
lib/triangulation/Tenseur3.cpp
lib/triangulation/Tenseur3.h
lib/triangulation/Tesselation.ipp
lib/triangulation/Timer.cpp
lib/triangulation/Timer.h
lib/triangulation/TriaxialState.cpp
lib/triangulation/TriaxialState.h
lib/triangulation/basicVTKwritter.cpp
lib/triangulation/basicVTKwritter.hpp
pkg/common/Bo1_Box_Aabb.cpp
pkg/common/BoundaryController.cpp
pkg/common/Callbacks.hpp
pkg/common/Collider.cpp
pkg/common/Cylinder.cpp
pkg/common/Dispatching.cpp
pkg/common/ElastMat.hpp
pkg/common/Gl1_NormPhys.cpp
pkg/common/Gl1_Sphere.cpp
pkg/common/GravityEngines.cpp
pkg/common/Grid.cpp
pkg/common/InsertionSortCollider.cpp
pkg/common/KinematicEngines.cpp
pkg/common/MatchMaker.cpp
pkg/common/MatchMaker.hpp
pkg/common/ParallelEngine.cpp
pkg/common/ParallelEngine.hpp
pkg/common/PersistentTriangulationCollider.cpp
pkg/common/Recorder.hpp
pkg/common/ResetRandomPosition.cpp
pkg/common/ResetRandomPosition.hpp
pkg/common/SpatialQuickSortCollider.cpp
pkg/common/SpatialQuickSortCollider.hpp
pkg/common/Wall.cpp
pkg/common/ZECollider.cpp
pkg/common/ZECollider.hpp
pkg/dem/BubbleMat.cpp
pkg/dem/CapillaryStressRecorder.cpp
pkg/dem/CapillaryTriaxialTest.cpp
pkg/dem/CohesiveFrictionalContactLaw.hpp
pkg/dem/CohesiveTriaxialTest.cpp
pkg/dem/ConcretePM.cpp
pkg/dem/DomainLimiter.cpp
pkg/dem/FacetTopologyAnalyzer.cpp
pkg/dem/FlatGridCollider.cpp
pkg/dem/FlatGridCollider.hpp
pkg/dem/FrictViscoPM.hpp
pkg/dem/GeneralIntegratorInsertionSortCollider.cpp
pkg/dem/Ig2_Box_Sphere_ScGeom.cpp
pkg/dem/Ig2_Facet_Sphere_ScGeom.cpp
pkg/dem/Integrator.cpp
pkg/dem/Integrator.hpp
pkg/dem/JointedCohesiveFrictionalPM.cpp
pkg/dem/KinemSimpleShearBox.cpp
pkg/dem/L3Geom.cpp
pkg/dem/Law2_ScGeom6D_InelastCohFrictPhys_CohesionMoment.cpp
pkg/dem/Law2_ScGeom_CapillaryPhys_Capillarity.cpp
pkg/dem/Law2_ScGeom_CapillaryPhys_Capillarity.hpp
pkg/dem/NewtonIntegrator.cpp
pkg/dem/NormalInelasticityLaw.cpp
pkg/dem/PeriIsoCompressor.cpp
pkg/dem/Polyhedra.cpp
pkg/dem/Polyhedra.hpp
pkg/dem/Polyhedra_splitter.cpp
pkg/dem/Polyhedra_support.cpp
pkg/dem/SampleCapillaryPressureEngine.cpp
pkg/dem/Shop.hpp
pkg/dem/Shop_01.cpp
pkg/dem/Shop_02.cpp
pkg/dem/SimpleShear.cpp
pkg/dem/SimpleShear.hpp
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/Tetra.hpp
pkg/dem/ThreeDTriaxialEngine.cpp
pkg/dem/ThreeDTriaxialEngine.hpp
pkg/dem/TriaxialCompressionEngine.cpp
pkg/dem/TriaxialCompressionEngine.hpp
pkg/dem/TriaxialStateRecorder.cpp
pkg/dem/TriaxialTest.cpp
pkg/dem/UniaxialStrainer.cpp
pkg/dem/UniaxialStrainer.hpp
pkg/dem/VTKRecorder.cpp
pkg/dem/ViscoelasticCapillarPM.hpp
pkg/dem/ViscoelasticPM.cpp
pkg/dem/WirePM.cpp
pkg/lbm/HydrodynamicsLawLBM.cpp
pkg/pfv/FlowEngine.ipp.in
pkg/pfv/PeriodicFlowEngine.cpp
pkg/pfv/SoluteFlowEngine.cpp
py/_polyhedra_utils.cpp
py/_utils.cpp
py/export.py
py/mathWrap/miniEigen.cpp
py/pack/_packObb.cpp
py/pack/_packPredicates.cpp
py/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-06-24 13:22:21 +0000
+++ CMakeLists.txt 2014-07-09 07:07:14 +0000
@@ -62,7 +62,17 @@
ENDIF()
#===========================================================
-ADD_DEFINITIONS(" -DYADE_PTR_CAST=boost::static_pointer_cast -DYADE_CAST=static_cast ")
+
+ADD_DEFINITIONS(" -DYADE_PTR_CAST=boost::static_pointer_cast -DYADE_CAST=static_cast -DYADE_PTR_DYN_CAST=boost::dynamic_pointer_cast ")
+IF (CXX11)
+ SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
+ ADD_DEFINITIONS(" -DCXX11 -DTYPEOF=decltype")
+ELSE (CXX11)
+ ADD_DEFINITIONS(" -DTYPEOF=typeof")
+ENDIF (CXX11)
+
+#===========================================================
+
IF (CMAKE_CXX_FLAGS)
#If flags are set, add only neccessary flags
IF (DEBUG)
@@ -134,9 +144,9 @@
INCLUDE_DIRECTORIES(${EIGEN3_INCLUDE_DIR})
MESSAGE(STATUS "Found Eigen3, version: ${EIGEN3_VERSION}")
- # Minimal recommended version 3.2.1
+ # Minimal required version 3.2.1
IF ((${EIGEN3_MAJOR_VERSION} LESS 2) OR ((${EIGEN3_MAJOR_VERSION} EQUAL 2) AND (${EIGEN3_MINOR_VERSION} LESS 1)))
- MESSAGE(WARNING "Minimal recommended Eigen3 version is 3.2.1")
+ MESSAGE(FATAL_ERROR "Minimal required Eigen3 version is 3.2.1, please update Eigen3!")
ENDIF ((${EIGEN3_MAJOR_VERSION} LESS 2) OR ((${EIGEN3_MAJOR_VERSION} EQUAL 2) AND (${EIGEN3_MINOR_VERSION} LESS 1)))
SET(CONFIGURED_FEATS "${CONFIGURED_FEATS} Eigen3")
@@ -161,8 +171,6 @@
((Boost_MINOR_VERSION EQUAL 53) OR (Boost_MINOR_VERSION GREATER 53)))
SET(DISABLED_FEATS "${DISABLED_FEATS} Odeint")
MESSAGE(STATUS "Boost Odeint can be enabled, only if Boost>=1.53 is used")
- MESSAGE(STATUS ${Boost_MAJOR_VERSION})
- MESSAGE(STATUS ${Boost_MINOR_VERSION})
ENDIF((Boost_MAJOR_VERSION EQUAL 1) OR (Boost_MAJOR_VERSION GREATER 1) AND
((Boost_MINOR_VERSION EQUAL 53) OR (Boost_MINOR_VERSION GREATER 53)))
#===========================================================
=== modified file 'ChangeLog'
--- ChangeLog 2014-05-18 15:33:35 +0000
+++ ChangeLog 2014-06-25 17:41:03 +0000
@@ -1,4 +1,97 @@
==================================================
+yade-1.10.0
+Wed, 25 Jun 2014 19:35:00 +0200
+
+Anton Gladky (47):
+ Delete Release file.
+ Add orientation parameter to ymport.textClumps
+ Resize ForceContainer after each body insert
+ Added assert to get*Unsynced function
+ Better fix for ForceContainer-size-change
+ Remove extra/floating_point_utilities_v3
+ Remove some 'using namespace boost'
+ Remove some more `using namespace boost`.
+ Remove all remaining `using namespace boost`
+ Fix compilation in DEBIG-mode.
+ Link against libboost_date. Fix LP:1322274
+ Set the mask to a clump the same as the first member of it.
+ Revert removal of embedded floating_point_utilities_v3.
+ Add particleconserve parameter to LiqControl.
+ Replace features by CONFIGURED_FEATS.
+ Prevent first empty item in features.
+ Add checkLiquidMigration autotest.
+ Better check for DEM-PFV-check.py
+ Add missing header.
+ Add --as-needed flag to yade-lib.
+ Comment some lines, where defined unused variables.
+ Minor fix in documentation of viscoelastic.
+ At every sync check, whether ForceContainer is large enough.
+ Disable parallel code in conditionalyEraseNonReal
+ Skip interactions, where one of body isClump
+ Fix doc-compilation for IPython >=2
+ Enable vectorization in eigen3-lib
+ Do not use Eigen3 in parallel mode.
+ Recommend minimal Eigen3 version 3.2.1.
+ Set minimal required Eigen3 version 3.2.1
+ Add NOVECTORIZE option
+ Prevent adding liqVol-parameters into VTK-files
+ Prevent crash in liqVolIterBody
+ Disable vectorization by default.
+ Replace Quaternion.Identity by Quaternion((1,0,0),0)
+ In state pos_set and ori_set use passing by value.
+ Add addLiqInter function to set liquid "properly"
+ Liquid migration model, code refactoring.
+ Add script to changes commit`s author`s names.
+ Fix typo in installation.
+ PFV code refactoring.
+ Fix typo in previous commit.
+ Fix templates names.
+ Clean in ymport.stl
+ Remove service-messages in CMakeLists
+ Add missed #pragma once
+ Add RELEASE file.
+
+Bruno Chareyre (11):
+ CohFritMat documentation
+ document Ip2_CohFrictMat more
+ make the parallel collider warning more explicit regarding turning collider.ompThreads=1
+ CohesiveFrictional contacts: make them elastic only if strength<0 (previous condition was <=0) + Lingran's elastic energy of contact moments
+ fix fluidForce=0 after remeshing + allow constant positions for DFNFlowEngine
+ make FlowEngine::setPositionsBuffer virtual
+ missing declaration of function
+ fix default attribute in DFNFlow
+ CohesiveFrictionalContactLaw does not warn about incremental formulation of rolling/twisting moments when the moments are elastic
+ fix bug in FlowEngine::updateBCs() (reported by Luc Scholtes, thanks)
+ Revert "Set minimal required Eigen3 version 3.2.1"
+
+Christian Jakob (2):
+ remove relicts of Dem3Dof and code cleaning
+ increase maximum length of char filename in saveVtk method for FlowEngine
+
+Francois (1):
+ Update the documentation for Law2_ScGridCoGeom_NormalInelasticityPhys. At this moment it's not done, but it will be fixed and come with a reference article during 2014.
+
+Jan Stransky (4):
+ Body::groupMask may be optionally boost::python::long_, subsequently modified code where necessary
+ fixed bug in yade.export.exportFacetsAsMesh (thanks Jan Havelka for reporting)
+ added mask_t type for bitmask variables to be int or optionally std::bitset of fixed (yet arbitrary) size. Added bitset to/from python long conversion. Added MASK_ARBITRARY cmake option. Subsequent changes in other files
+ corrected git warning in CMakeLists.txt
+
+Jerome Duriez (6):
+ Correction of mispelling in example script name of one Law2
+ Minor changes in JCFpm
+ Important change in Kinem.. engines. Both changes in position and velocities of boundary bodies were still existing, while now changes in position should be handled by NewtonIntegrator
+ JCFpm : doc of JCFpmPhys.FnMax precised (minor change). And formulation of kn for onJoint interactions according to JCFpmPhys.crossSection (rather than mean of surfaces) to be consistent with the whole formulation ("major" change : this may impact the results of previous scripts depending on psd and how much the mechanical behaviour of joint is important)
+ Doc of VTKRecorder.skipFacetIntr precised so that it better corresponds to code
+ Extra s in previous commit removed..
+
+Klaus Thoeni (4):
+ remove old code
+ improve output and remove first iteration in calculation velocity estimation
+ add definition for functor order
+ set number of iterations to be run correctly (thanks Alex)
+
+==================================================
yade-1.09.0
Sun, 18 May 2014 17:32:07 +0200
=== modified file 'core/Body.cpp'
--- core/Body.cpp 2014-06-17 10:18:00 +0000
+++ core/Body.cpp 2014-07-03 17:20:40 +0000
@@ -1,6 +1,5 @@
#include<yade/core/Body.hpp>
-#include<limits>
#include<yade/core/Scene.hpp>
#include<yade/core/Omega.hpp>
#include<yade/core/InteractionContainer.hpp>
=== modified file 'core/Body.hpp'
--- core/Body.hpp 2014-06-17 10:18:00 +0000
+++ core/Body.hpp 2014-07-03 17:20:40 +0000
@@ -9,8 +9,6 @@
*************************************************************************/
#pragma once
-#include<iostream>
-#include<map>
#include"Shape.hpp"
#include"Bound.hpp"
#include"State.hpp"
=== modified file 'core/BodyContainer.hpp'
--- core/BodyContainer.hpp 2014-05-15 17:50:26 +0000
+++ core/BodyContainer.hpp 2014-07-03 17:20:40 +0000
@@ -5,12 +5,6 @@
#pragma once
#include<yade/lib/serialization/Serializable.hpp>
-
-#include<boost/foreach.hpp>
-#ifndef FOREACH
-# define FOREACH BOOST_FOREACH
-#endif
-
#include<boost/tuple/tuple.hpp>
class Body;
=== modified file 'core/Clump.cpp'
--- core/Clump.cpp 2014-05-23 13:05:19 +0000
+++ core/Clump.cpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,6 @@
// (c) 2007-2010 Vaclav Smilauer <eudoxos@xxxxxxxx>
#include"Clump.hpp"
-#include<algorithm>
#include<yade/core/Scene.hpp>
#include<yade/core/BodyContainer.hpp>
#include<yade/core/State.hpp>
=== modified file 'core/Clump.hpp'
--- core/Clump.hpp 2014-05-23 13:05:19 +0000
+++ core/Clump.hpp 2014-07-03 17:20:40 +0000
@@ -2,9 +2,6 @@
#pragma once
-#include<vector>
-#include<map>
-#include<stdexcept>
#include<yade/core/Body.hpp>
#include<yade/lib/base/Logging.hpp>
#include<yade/lib/base/Math.hpp>
=== modified file 'core/Dispatcher.cpp'
--- core/Dispatcher.cpp 2010-08-24 12:54:14 +0000
+++ core/Dispatcher.cpp 2014-07-03 17:20:40 +0000
@@ -11,8 +11,5 @@
Functor::~Functor(){}; // vtable
#include "Dispatcher.hpp"
-#include<algorithm>
-#include<vector>
-
Dispatcher::~Dispatcher(){}
=== modified file 'core/Dispatcher.hpp'
--- core/Dispatcher.hpp 2014-05-23 13:05:19 +0000
+++ core/Dispatcher.hpp 2014-07-03 17:20:40 +0000
@@ -8,7 +8,6 @@
#pragma once
-#include<boost/lexical_cast.hpp>
#include<yade/core/Engine.hpp>
#include<yade/core/Functor.hpp>
@@ -40,7 +39,7 @@
#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(boost::static_pointer_cast<FunctorT>(f)); } \
+ void postLoad(DispatcherT&){ clearMatrix(); FOREACH(shared_ptr<FunctorT> f, functors) add(YADE_PTR_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) \
@@ -71,7 +70,7 @@
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=boost::dynamic_pointer_cast<topIndexable>(ClassFactory::instance().createShared(clss.first));
+ shared_ptr<topIndexable> inst=YADE_PTR_DYN_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! ]]");
@@ -107,7 +106,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(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); }
+ FOREACH(const shared_ptr<Functor>& functor, self->functors){ shared_ptr<typename DispatcherT::functorType> functorRightType(YADE_PTR_DYN_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;
}
=== modified file 'core/EnergyTracker.hpp'
--- core/EnergyTracker.hpp 2014-05-23 13:03:50 +0000
+++ core/EnergyTracker.hpp 2014-07-03 17:20:40 +0000
@@ -1,14 +1,7 @@
#pragma once
-#include<boost/python.hpp>
-#include<boost/foreach.hpp>
-#include<string>
#include<yade/lib/base/openmp-accu.hpp>
#include<yade/lib/serialization/Serializable.hpp>
-#ifndef FOREACH
- #define FOREACH BOOST_FOREACH
-#endif
-
namespace py=boost::python;
class EnergyTracker: public Serializable{
=== modified file 'core/Engine.hpp'
--- core/Engine.hpp 2013-05-14 21:24:11 +0000
+++ core/Engine.hpp 2014-07-03 17:20:40 +0000
@@ -14,12 +14,6 @@
#include<yade/core/Omega.hpp>
#include<yade/core/Timing.hpp>
#include<yade/lib/base/Logging.hpp>
-#include<stdexcept>
-
-#include<boost/foreach.hpp>
-#ifndef FOREACH
-#define FOREACH BOOST_FOREACH
-#endif
class Body;
class Scene;
=== modified file 'core/FileGenerator.cpp'
--- core/FileGenerator.cpp 2012-09-21 19:03:18 +0000
+++ core/FileGenerator.cpp 2014-07-03 17:20:40 +0000
@@ -4,7 +4,6 @@
*************************************************************************/
#include<yade/core/Omega.hpp>
-#include<cstdlib>
#include<boost/date_time/posix_time/posix_time.hpp>
#include<yade/lib/pyutil/gil.hpp>
#include<yade/lib/serialization/ObjectIO.hpp>
=== modified file 'core/ForceContainer.hpp'
--- core/ForceContainer.hpp 2014-06-04 08:44:44 +0000
+++ core/ForceContainer.hpp 2014-07-03 17:20:40 +0000
@@ -1,8 +1,6 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
#pragma once
-#include<string.h>
-#include<vector>
#include<yade/lib/base/Math.hpp>
#include<yade/core/Body.hpp>
=== modified file 'core/Functor.hpp'
--- core/Functor.hpp 2014-05-23 13:05:19 +0000
+++ core/Functor.hpp 2014-07-02 16:11:24 +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)boost::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)YADE_PTR_DYN_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(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; }
+ #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(YADE_PTR_DYN_CAST<type1>(arg1)&&YADE_PTR_DYN_CAST<type2>(arg2)) return 1; if(YADE_PTR_DYN_CAST<type1>(arg2)&&YADE_PTR_DYN_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.hpp'
--- core/InteractionContainer.hpp 2014-06-04 08:51:38 +0000
+++ core/InteractionContainer.hpp 2014-07-03 17:20:40 +0000
@@ -14,11 +14,6 @@
#include<yade/core/Interaction.hpp>
#include<yade/core/BodyContainer.hpp>
-#include<boost/foreach.hpp>
-#ifndef FOREACH
-# define FOREACH BOOST_FOREACH
-#endif
-
/* This InteractionContainer implementation has reference to the body container and
stores interactions in 2 places:
=== modified file 'core/Material.cpp'
--- core/Material.cpp 2010-09-27 17:47:59 +0000
+++ core/Material.cpp 2014-07-03 17:20:40 +0000
@@ -1,10 +1,6 @@
#include<stdexcept>
#include<yade/core/Material.hpp>
#include<yade/core/Scene.hpp>
-#include<boost/foreach.hpp>
-#ifndef FOREACH
- #define FOREACH BOOST_FOREACH
-#endif
Material::~Material(){}
=== modified file 'core/Material.hpp'
--- core/Material.hpp 2010-11-07 11:46:20 +0000
+++ core/Material.hpp 2014-07-03 17:20:40 +0000
@@ -1,6 +1,5 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
#pragma once
-#include<string>
#include<yade/lib/serialization/Serializable.hpp>
#include<yade/lib/multimethods/Indexable.hpp>
#include<yade/core/State.hpp>
=== modified file 'core/Omega.cpp'
--- core/Omega.cpp 2014-05-23 13:05:19 +0000
+++ core/Omega.cpp 2014-07-04 17:46:32 +0000
@@ -15,14 +15,11 @@
#include<yade/lib/base/Math.hpp>
#include<yade/lib/multimethods/FunctorWrapper.hpp>
#include<yade/lib/multimethods/Indexable.hpp>
-#include<cstdlib>
#include<boost/filesystem/operations.hpp>
#include<boost/filesystem/convenience.hpp>
#include<boost/filesystem/exception.hpp>
#include<boost/algorithm/string.hpp>
#include<boost/thread/mutex.hpp>
-#include<boost/version.hpp>
-#include<boost/python.hpp>
#include<yade/lib/serialization/ObjectIO.hpp>
@@ -71,8 +68,8 @@
-Real Omega::getRealTime(){ return (microsec_clock::local_time()-startupLocalTime).total_milliseconds()/1e3; }
-time_duration Omega::getRealTime_duration(){return microsec_clock::local_time()-startupLocalTime;}
+Real Omega::getRealTime(){ return (boost::posix_time::microsec_clock::local_time()-startupLocalTime).total_milliseconds()/1e3; }
+boost::posix_time::time_duration Omega::getRealTime_duration(){return boost::posix_time::microsec_clock::local_time()-startupLocalTime;}
void Omega::initTemps(){
@@ -107,7 +104,7 @@
}
void Omega::timeInit(){
- startupLocalTime=microsec_clock::local_time();
+ startupLocalTime=boost::posix_time::microsec_clock::local_time();
}
void Omega::createSimulationLoop(){ simulationLoop=shared_ptr<ThreadRunner>(new ThreadRunner(&simulationFlow_));}
@@ -145,9 +142,7 @@
try {
LOG_DEBUG("Factoring plugin "<<name);
f = ClassFactory::instance().createShared(name);
- 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);
+ dynlibs[name].isSerializable = ((YADE_PTR_DYN_CAST<Serializable>(f)).get()!=0);
for(int i=0;i<f->getBaseClassNumber();i++){
dynlibs[name].baseClasses.insert(f->getBaseClassName(i));
}
@@ -250,7 +245,7 @@
RenderMutexLock lock;
if(isMem){
istringstream iss(memSavedSimulations[f]);
- yade::ObjectIO::load<typeof(scene),boost::archive::binary_iarchive>(iss,"scene",scene);
+ yade::ObjectIO::load<TYPEOF(scene),boost::archive::binary_iarchive>(iss,"scene",scene);
} else {
yade::ObjectIO::load(f,"scene",scene);
}
@@ -272,7 +267,7 @@
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);
+ yade::ObjectIO::save<TYPEOF(scene),boost::archive::binary_oarchive>(oss,"scene",scene);
memSavedSimulations[f]=oss.str();
}
else {
=== modified file 'core/Omega.hpp'
--- core/Omega.hpp 2014-05-23 13:03:50 +0000
+++ core/Omega.hpp 2014-07-04 17:46:32 +0000
@@ -10,21 +10,7 @@
#pragma once
-// qt3 sucks
-#ifdef QT_MOC_CPP
- #undef slots
- #include<Python.h>
- #define slots slots
-#else
- #ifdef slots
- #undef slots
- #include<Python.h>
- #define slots
- #else
- #include<Python.h>
- #endif
-#endif
-
+#include <Python.h>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <fstream>
#include <set>
@@ -48,12 +34,9 @@
class Scene;
class ThreadRunner;
-using namespace boost::posix_time;
-using namespace std;
-
struct DynlibDescriptor{
set<string> baseClasses;
- bool isIndexable, isFactorable, isSerializable;
+ bool isSerializable;
};
class Omega: public Singleton<Omega>{
@@ -66,7 +49,7 @@
int currentSceneNb;
shared_ptr<Scene> sceneAnother; // used for temporarily running different simulation, in Omega().switchscene()
- ptime startupLocalTime;
+ boost::posix_time::ptime startupLocalTime;
map<string,string> memSavedSimulations;
@@ -117,7 +100,7 @@
//! Return unique temporary filename. May be deleted by the user; if not, will be deleted at shutdown.
string tmpFilename();
Real getRealTime();
- time_duration getRealTime_duration();
+ boost::posix_time::time_duration getRealTime_duration();
// configuration directory used for logging config and possibly other things
std::string confDir;
=== modified file 'core/Scene.cpp'
--- core/Scene.cpp 2014-05-23 13:05:19 +0000
+++ core/Scene.cpp 2014-07-03 17:20:40 +0000
@@ -14,7 +14,6 @@
#include<yade/core/TimeStepper.hpp>
#include<yade/lib/base/Math.hpp>
-#include<boost/foreach.hpp>
#include<boost/date_time/posix_time/posix_time.hpp>
#include<boost/algorithm/string.hpp>
@@ -194,8 +193,8 @@
if(!b) continue;
if(b->bound){
for(int i=0; i<3; i++){
- if(!isinf(b->bound->max[i])) mx[i]=max(mx[i],b->bound->max[i]);
- if(!isinf(b->bound->min[i])) mn[i]=min(mn[i],b->bound->min[i]);
+ if(!std::isinf(b->bound->max[i])) mx[i]=max(mx[i],b->bound->max[i]);
+ if(!std::isinf(b->bound->min[i])) mn[i]=min(mn[i],b->bound->min[i]);
}
} else {
mx=mx.cwiseMax(b->state->pos);
=== modified file 'core/State.cpp'
--- core/State.cpp 2014-05-23 13:05:19 +0000
+++ core/State.cpp 2014-07-03 17:20:40 +0000
@@ -1,10 +1,5 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
#include<yade/core/State.hpp>
-#include<boost/foreach.hpp>
-#include<stdexcept>
-#ifndef FOREACH
- #define FOREACH BOOST_FOREACH
-#endif
CREATE_LOGGER(State);
=== modified file 'core/ThreadRunner.cpp'
--- core/ThreadRunner.cpp 2012-05-07 17:27:44 +0000
+++ core/ThreadRunner.cpp 2014-07-03 17:20:40 +0000
@@ -14,8 +14,6 @@
#include <boost/function.hpp>
#include <boost/bind.hpp>
-#include<iostream>
-
CREATE_LOGGER(ThreadRunner);
void ThreadRunner::run()
=== modified file 'core/Timing.hpp'
--- core/Timing.hpp 2009-12-18 20:55:02 +0000
+++ core/Timing.hpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,6 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
#pragma once
#include<time.h>
-#include<boost/python.hpp>
struct TimingInfo{
typedef unsigned long long delta;
=== modified file 'core/corePlugins.cpp'
--- core/corePlugins.cpp 2010-11-07 11:46:20 +0000
+++ core/corePlugins.cpp 2014-07-03 17:20:40 +0000
@@ -20,7 +20,6 @@
#include<yade/core/State.hpp>
#include<yade/core/TimeStepper.hpp>
-#include<boost/version.hpp>
// these two are not accessible from python directly (though they should be in the future, perhaps)
=== modified file 'core/main/pyboot.cpp'
--- core/main/pyboot.cpp 2014-05-23 13:20:43 +0000
+++ core/main/pyboot.cpp 2014-07-03 17:20:40 +0000
@@ -2,13 +2,7 @@
#include<yade/lib/base/Logging.hpp>
#include<signal.h>
-#include<cstdlib>
-#include<cstdio>
-#include<iostream>
-#include<string>
-#include<stdexcept>
-#include<boost/python.hpp>
#include<boost/filesystem/convenience.hpp>
#ifdef YADE_DEBUG
=== modified file 'doc/sphinx/installation.rst'
--- doc/sphinx/installation.rst 2014-06-23 16:21:06 +0000
+++ doc/sphinx/installation.rst 2014-06-25 18:18:39 +0000
@@ -115,7 +115,7 @@
* `libQGLViewer <http://www.libqglviewer.com>`_
* `python <http://www.python.org>`_, `numpy <http://numpy.scipy.org>`_, `ipython <http://ipython.scipy.org>`_
* `matplotlib <http://matplotlib.sf.net>`_
-* `eigen3 <http://eigen.tuxfamily.org>`_ algebra library (minimal recommended version 3.2.1)
+* `eigen3 <http://eigen.tuxfamily.org>`_ algebra library (minimal required version 3.2.1)
* `gdb <http://www.gnu.org/software/gdb>`_ debugger
* `sqlite3 <http://www.sqlite.org>`_ database engine
* `Loki <http://loki-lib.sf.net>`_ library
=== modified file 'gui/qt4/GLViewer.cpp'
--- gui/qt4/GLViewer.cpp 2014-05-23 13:05:19 +0000
+++ gui/qt4/GLViewer.cpp 2014-07-03 17:20:40 +0000
@@ -18,8 +18,6 @@
#include<yade/core/DisplayParameters.hpp>
#include<boost/filesystem/operations.hpp>
#include<boost/algorithm/string.hpp>
-#include<boost/version.hpp>
-#include<boost/python.hpp>
#include<sstream>
#include<iomanip>
#include<boost/algorithm/string/case_conv.hpp>
@@ -425,7 +423,7 @@
string GLViewer::getRealTimeString(){
ostringstream oss;
- time_duration t=Omega::instance().getRealTime_duration();
+ boost::posix_time::time_duration t=Omega::instance().getRealTime_duration();
unsigned d=t.hours()/24,h=t.hours()%24,m=t.minutes(),s=t.seconds();
oss<<"clock ";
if(d>0) oss<<d<<"days "<<_W2<<h<<":"<<_W2<<m<<":"<<_W2<<s;
=== modified file 'gui/qt4/GLViewer.hpp'
--- gui/qt4/GLViewer.hpp 2014-05-23 13:05:19 +0000
+++ gui/qt4/GLViewer.hpp 2014-07-03 07:15:45 +0000
@@ -14,6 +14,10 @@
#include<QGLViewer/constraint.h>
#include<set>
+using std::setw;
+using std::setfill;
+using std::setprecision;
+
/*! Class handling user interaction with the openGL rendering of simulation.
*
* Clipping planes:
=== modified file 'gui/qt4/GLViewerDisplay.cpp'
--- gui/qt4/GLViewerDisplay.cpp 2014-05-23 13:05:19 +0000
+++ gui/qt4/GLViewerDisplay.cpp 2014-07-03 17:24:54 +0000
@@ -18,8 +18,6 @@
#include<yade/core/DisplayParameters.hpp>
#include<boost/filesystem/operations.hpp>
#include<boost/algorithm/string.hpp>
-#include<boost/version.hpp>
-#include<boost/python.hpp>
#include<sstream>
#include<iomanip>
#include<boost/algorithm/string/case_conv.hpp>
@@ -42,7 +40,7 @@
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);
+ 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 #"+boost::lexical_cast<string>(n)); }
@@ -55,7 +53,7 @@
if(dispParams.size()<=n){while(dispParams.size()<=n) dispParams.push_back(shared_ptr<DisplayParameters>(new DisplayParameters));} assert(n<dispParams.size());
shared_ptr<DisplayParameters>& dp=dispParams[n];
ostringstream oglre;
- yade::ObjectIO::save<typeof(renderer),boost::archive::xml_oarchive>(oglre,"renderer",renderer);
+ 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 #"+boost::lexical_cast<string>(n));
@@ -183,7 +181,7 @@
}
//LOG_DEBUG("Screen offsets for axes: "<<" x("<<screenDxDy[0][0]<<","<<screenDxDy[0][1]<<") y("<<screenDxDy[1][0]<<","<<screenDxDy[1][1]<<") z("<<screenDxDy[2][0]<<","<<screenDxDy[2][1]<<")");
int margin=10; // screen pixels
- int scaleCenter[2]; scaleCenter[0]=abs(extremalDxDy[0])+margin; scaleCenter[1]=abs(extremalDxDy[1])+margin;
+ int scaleCenter[2]; scaleCenter[0]=std::abs(extremalDxDy[0])+margin; scaleCenter[1]=std::abs(extremalDxDy[1])+margin;
//LOG_DEBUG("Center of scale "<<scaleCenter[0]<<","<<scaleCenter[1]);
//displayMessage(QString().sprintf("displayed scene radius %g",displayedSceneRadius()));
startScreenCoordinatesSystem();
=== modified file 'gui/qt4/GLViewerMouse.cpp'
--- gui/qt4/GLViewerMouse.cpp 2014-05-23 13:03:50 +0000
+++ gui/qt4/GLViewerMouse.cpp 2014-07-03 17:20:40 +0000
@@ -18,8 +18,6 @@
#include<yade/core/DisplayParameters.hpp>
#include<boost/filesystem/operations.hpp>
#include<boost/algorithm/string.hpp>
-#include<boost/version.hpp>
-#include<boost/python.hpp>
#include<sstream>
#include<iomanip>
#include<boost/algorithm/string/case_conv.hpp>
=== modified file 'gui/qt4/_GLViewer.cpp'
--- gui/qt4/_GLViewer.cpp 2014-05-23 13:05:19 +0000
+++ gui/qt4/_GLViewer.cpp 2014-07-03 17:20:40 +0000
@@ -1,6 +1,5 @@
#include"GLViewer.hpp"
#include"OpenGLManager.hpp"
-#include<boost/python.hpp>
#include<yade/pkg/common/OpenGLRenderer.hpp>
#include<yade/lib/pyutil/doc_opts.hpp>
=== modified file 'lib/base/Logging.hpp'
--- lib/base/Logging.hpp 2014-02-28 11:14:59 +0000
+++ lib/base/Logging.hpp 2014-07-03 19:08:46 +0000
@@ -14,6 +14,8 @@
*
*/
+#include <iostream>
+
# define _POOR_MANS_LOG(level,msg) {std::cerr<<level " "<<_LOG_HEAD<<msg<<std::endl;}
# define _LOG_HEAD __FILE__ ":"<<__LINE__<<" "<<__FUNCTION__<<": "
=== modified file 'lib/base/Math.hpp'
--- lib/base/Math.hpp 2014-06-17 10:18:00 +0000
+++ lib/base/Math.hpp 2014-07-04 17:46:32 +0000
@@ -8,21 +8,81 @@
typedef double Real;
#endif
+#include <algorithm>
+#include <cassert>
+#include <cmath>
+#include <cstdlib>
+#include <cstdio>
+#include <fstream>
+#include <iostream>
+#include <limits>
+#include <list>
+#include <map>
+#include <set>
+#include <sstream>
+#include <stdexcept>
+#include <string>
+#include <typeinfo>
+#include <utility>
+#include <vector>
+
+using std::endl;
+using std::cout;
+using std::cerr;
+using std::vector;
+using std::string;
+using std::list;
+using std::pair;
+using std::min;
+using std::max;
+using std::set;
+using std::map;
+using std::type_info;
+using std::ifstream;
+using std::ofstream;
+using std::runtime_error;
+using std::logic_error;
+using std::invalid_argument;
+using std::ios;
+using std::ios_base;
+using std::fstream;
+using std::ostream;
+using std::ostringstream;
+using std::istringstream;
+using std::swap;
+using std::make_pair;
+
+#include <boost/lexical_cast.hpp>
+#include <boost/python.hpp>
+#include <boost/python/object.hpp>
+#include <boost/version.hpp>
+#include <boost/any.hpp>
+#include <boost/type_traits.hpp>
+#include <boost/preprocessor.hpp>
+#include <boost/python/module.hpp>
+#include <boost/python/class.hpp>
+#include <boost/shared_ptr.hpp>
+#include <boost/foreach.hpp>
+
+using boost::shared_ptr;
+
+#ifndef FOREACH
+ #define FOREACH BOOST_FOREACH
+#endif
+
#define EIGEN_DONT_PARALLELIZE
-#include<limits>
-#include<cstdlib>
#ifdef YADE_MASK_ARBITRARY
-#include<bitset>
+ #include <bitset>
#endif
-#include<Eigen/Core>
-#include<Eigen/Geometry>
-#include<Eigen/QR>
-#include<Eigen/LU>
-#include<Eigen/SVD>
-#include<Eigen/Eigenvalues>
-#include<float.h>
+#include <Eigen/Core>
+#include <Eigen/Geometry>
+#include <Eigen/QR>
+#include <Eigen/LU>
+#include <Eigen/SVD>
+#include <Eigen/Eigenvalues>
+#include <float.h>
// templates of those types with single parameter are not possible, use macros for now
#define VECTOR2_TEMPLATE(Scalar) Eigen::Matrix<Scalar,2,1>
@@ -234,8 +294,6 @@
*/
typedef Se3<Real> Se3r;
-
-
/*
* Serialization of math classes
*/
=== modified file 'lib/base/openmp-accu.hpp'
--- lib/base/openmp-accu.hpp 2014-05-08 08:11:40 +0000
+++ lib/base/openmp-accu.hpp 2014-07-03 17:20:40 +0000
@@ -5,14 +5,8 @@
#include <yade/lib/base/Math.hpp>
#include <boost/serialization/split_free.hpp>
-#include <boost/lexical_cast.hpp>
-#include <string>
-#include <vector>
#include <cstdlib>
#include <unistd.h>
-#include <stdexcept>
-#include <iostream>
-
#ifdef YADE_OPENMP
#include "omp.h"
=== modified file 'lib/factory/ClassFactory.hpp'
--- lib/factory/ClassFactory.hpp 2010-11-19 12:30:08 +0000
+++ lib/factory/ClassFactory.hpp 2014-07-03 17:20:40 +0000
@@ -10,27 +10,8 @@
#pragma once
-
-#include<map>
-#include<string>
-#include<list>
-#include<iostream>
-#include<cstdio>
-
-#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/Singleton.hpp>
-
-#include<boost/preprocessor.hpp>
-
-
+#include <yade/lib/base/Math.hpp>
+#include <yade/lib/base/Singleton.hpp>
#include "DynLibManager.hpp"
/*! define the following macro to enable experimenta boost::serialization support
@@ -38,7 +19,6 @@
Python wrapper defines O.saveXML('file.xml') to try it out.
Loading is not yet implemented (should be easy)
*/
-#include<boost/version.hpp>
#include<boost/archive/binary_oarchive.hpp>
#include<boost/archive/binary_iarchive.hpp>
@@ -47,7 +27,6 @@
#include<boost/serialization/export.hpp> // must come after all supported archive types
-#include<boost/serialization/base_object.hpp>
#include<boost/serialization/shared_ptr.hpp>
#include<boost/serialization/list.hpp>
#include<boost/serialization/vector.hpp>
=== modified file 'lib/factory/DynLibManager.cpp'
--- lib/factory/DynLibManager.cpp 2014-05-23 13:03:50 +0000
+++ lib/factory/DynLibManager.cpp 2014-07-03 17:20:40 +0000
@@ -9,18 +9,11 @@
#include "DynLibManager.hpp"
-
-#include<fstream>
-#include<stdexcept>
#include<boost/filesystem/operations.hpp>
#include<boost/filesystem/convenience.hpp>
-#include<string.h>
#include "ClassFactory.hpp"
-
-//using namespace std;
-
CREATE_LOGGER(DynLibManager);
=== modified file 'lib/factory/DynLibManager.hpp'
--- lib/factory/DynLibManager.hpp 2010-11-07 11:46:20 +0000
+++ lib/factory/DynLibManager.hpp 2014-07-03 17:20:40 +0000
@@ -11,15 +11,8 @@
#include <dlfcn.h>
-#include <string>
-#include <iostream>
-#include <map>
-#include <vector>
-
#include<yade/lib/base/Logging.hpp>
-
-using namespace std;
-
+#include<yade/lib/base/Math.hpp>
class DynLibManager
{
@@ -34,18 +27,18 @@
bool load(const std::string& libName);
- bool unload (const string& libName);
- bool isLoaded (const string& libName);
+ bool unload (const std::string& libName);
+ bool isLoaded (const std::string& libName);
bool unloadAll ();
void setAutoUnload ( bool enabled );
- string lastError();
+ std::string lastError();
DECLARE_LOGGER;
private :
- bool closeLib(const string libName);
+ bool closeLib(const std::string libName);
bool error();
- string lastError_;
+ std::string lastError_;
};
=== modified file 'lib/import/STLReader.hpp'
--- lib/import/STLReader.hpp 2013-09-23 17:39:59 +0000
+++ lib/import/STLReader.hpp 2014-07-02 16:18:24 +0000
@@ -14,8 +14,6 @@
#include <cmath>
#include "utils.hpp"
-using namespace std;
-
class STLReader {
public:
=== modified file 'lib/import/utils.hpp'
--- lib/import/utils.hpp 2009-01-27 02:19:40 +0000
+++ lib/import/utils.hpp 2014-07-02 16:18:24 +0000
@@ -1,12 +1,11 @@
#pragma once
#include<utility>
-using namespace std;
template<class T>
-pair<T,T> minmax(const T &a, const T &b)
+std::pair<T,T> minmax(const T &a, const T &b)
{
- return (a<b) ? pair<T,T>(a,b) : pair<T,T>(b,a);
+ return (a<b) ? std::pair<T,T>(a,b) : std::pair<T,T>(b,a);
}
template<class T>
=== modified file 'lib/multimethods/DynLibDispatcher.hpp'
--- lib/multimethods/DynLibDispatcher.hpp 2014-05-23 13:05:19 +0000
+++ lib/multimethods/DynLibDispatcher.hpp 2014-07-02 16:18:24 +0000
@@ -35,9 +35,6 @@
#include<string>
#include<ostream>
-
-using namespace std;
-
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){}; };
///
=== modified file 'lib/multimethods/FunctorWrapper.hpp'
--- lib/multimethods/FunctorWrapper.hpp 2010-11-07 11:46:20 +0000
+++ lib/multimethods/FunctorWrapper.hpp 2014-07-03 17:20:40 +0000
@@ -26,7 +26,6 @@
#include <string>
-#include <boost/lexical_cast.hpp>
///////////////////////////////////////////////////////////////////////////////////////////////////
/// base template for classes that provide virtual functions for multiple dispatch, ///
=== modified file 'lib/opengl/GLUtils.hpp'
--- lib/opengl/GLUtils.hpp 2010-11-07 11:46:20 +0000
+++ lib/opengl/GLUtils.hpp 2014-07-03 17:20:40 +0000
@@ -5,7 +5,6 @@
#pragma once
#include<yade/lib/opengl/OpenGLWrapper.hpp>
-#include<boost/lexical_cast.hpp>
#include<sstream>
#include<iomanip>
#include<string>
=== modified file 'lib/pyutil/doc_opts.hpp'
--- lib/pyutil/doc_opts.hpp 2010-05-05 21:36:25 +0000
+++ lib/pyutil/doc_opts.hpp 2014-07-03 17:20:40 +0000
@@ -1,5 +1,4 @@
#pragma once
-#include<boost/version.hpp>
// macro to set the same docstring generation options in all modules
// disable_cpp_signatures apparently appeared after 1.35 or 1.34
=== modified file 'lib/pyutil/numpy_boost.hpp'
--- lib/pyutil/numpy_boost.hpp 2013-10-16 05:58:05 +0000
+++ lib/pyutil/numpy_boost.hpp 2014-07-03 17:20:40 +0000
@@ -40,7 +40,6 @@
#include <numpy/arrayobject.h>
#include <boost/multi_array.hpp>
#include <boost/cstdint.hpp>
-#include <boost/python.hpp>
#include <complex>
#include <algorithm>
=== modified file 'lib/pyutil/raw_constructor.hpp'
--- lib/pyutil/raw_constructor.hpp 2010-01-21 07:53:17 +0000
+++ lib/pyutil/raw_constructor.hpp 2014-07-03 17:20:40 +0000
@@ -1,5 +1,4 @@
#pragma once
-#include<boost/python.hpp>
#include<boost/python/raw_function.hpp>
// many thanks to http://markmail.org/message/s4ksg6nfspw2wxwd
namespace boost { namespace python { namespace detail {
=== modified file 'lib/serialization/Serializable.hpp'
--- lib/serialization/Serializable.hpp 2014-05-23 13:03:50 +0000
+++ lib/serialization/Serializable.hpp 2014-07-03 17:24:54 +0000
@@ -10,33 +10,13 @@
#pragma once
-#include <boost/any.hpp>
-#include <boost/foreach.hpp>
-#ifndef __GXX_EXPERIMENTAL_CXX0X__
-# include<boost/shared_ptr.hpp>
- using boost::shared_ptr;
-#else
-# include<memory>
- using std::shared_ptr;
-#endif
-#include<boost/version.hpp>
-#include<boost/python.hpp>
-#include<boost/type_traits.hpp>
-#include<boost/lexical_cast.hpp>
-#include<boost/preprocessor.hpp>
-#include<boost/type_traits/integral_constant.hpp>
-#include<list>
-#include<map>
-#include<string>
-#include<vector>
-#include<iostream>
-#include<yade/lib/factory/Factorable.hpp>
-#include<yade/lib/pyutil/raw_constructor.hpp>
-#include<yade/lib/pyutil/doc_opts.hpp>
-
-#include<yade/lib/base/Math.hpp>
-
-using namespace std;
+#include <boost/type_traits/integral_constant.hpp>
+
+#include <yade/lib/base/Math.hpp>
+#include <yade/lib/factory/Factorable.hpp>
+#include <yade/lib/pyutil/raw_constructor.hpp>
+#include <yade/lib/pyutil/doc_opts.hpp>
+
// 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; */ }
@@ -95,15 +75,15 @@
#define _DEF_READWRITE_BY_VALUE(thisClass,attr,doc) add_property(/*attr name*/BOOST_PP_STRINGIZE(attr),/*read access*/boost::python::make_getter(&thisClass::attr,boost::python::return_value_policy<boost::python::return_by_value>()),/*write access*/boost::python::make_setter(&thisClass::attr,boost::python::return_value_policy<boost::python::return_by_value>()),/*docstring*/doc)
// not sure if this is correct: the getter works by value, the setter by reference (the default)...?
-#define _DEF_READWRITE_BY_VALUE_POSTLOAD(thisClass,attr,doc) add_property(/*attr name*/BOOST_PP_STRINGIZE(attr),/*read access*/boost::python::make_getter(&thisClass::attr,boost::python::return_value_policy<boost::python::return_by_value>()),/*write access*/ make_setter_postLoad<thisClass,typeof(thisClass::attr),&thisClass::attr>,/*docstring*/doc)
+#define _DEF_READWRITE_BY_VALUE_POSTLOAD(thisClass,attr,doc) add_property(/*attr name*/BOOST_PP_STRINGIZE(attr),/*read access*/boost::python::make_getter(&thisClass::attr,boost::python::return_value_policy<boost::python::return_by_value>()),/*write access*/ make_setter_postLoad<thisClass,TYPEOF(thisClass::attr),&thisClass::attr>,/*docstring*/doc)
#define _DEF_READONLY_BY_VALUE(thisClass,attr,doc) add_property(/*attr name*/BOOST_PP_STRINGIZE(attr),/*read access*/boost::python::make_getter(&thisClass::attr,boost::python::return_value_policy<boost::python::return_by_value>()),/*docstring*/doc)
/* Huh, add_static_property does not support doc argument (add_property does); if so, use add_property for now at least... */
#define _DEF_READWRITE_BY_VALUE_STATIC(thisClass,attr,doc) _DEF_READWRITE_BY_VALUE(thisClass,attr,doc)
// the conditional yade::py_wrap_ref should be eliminated by compiler at compile-time, as it depends only on types, not their values
// most of this could be written with templates, including flags (ints can be template args)
-#define _DEF_READWRITE_CUSTOM(thisClass,attr) if(!(_ATTR_FLG(attr) & yade::Attr::hidden)){ bool _ro(_ATTR_FLG(attr) & Attr::readonly), _post(_ATTR_FLG(attr) & Attr::triggerPostLoad), _ref(yade::py_wrap_ref<typeof(thisClass::_ATTR_NAM(attr))>::value); std::string docStr(_ATTR_DOC(attr)); docStr+=" :yattrflags:`"+boost::lexical_cast<string>(_ATTR_FLG(attr))+"` "; \
+#define _DEF_READWRITE_CUSTOM(thisClass,attr) if(!(_ATTR_FLG(attr) & yade::Attr::hidden)){ bool _ro(_ATTR_FLG(attr) & Attr::readonly), _post(_ATTR_FLG(attr) & Attr::triggerPostLoad), _ref(yade::py_wrap_ref<TYPEOF(thisClass::_ATTR_NAM(attr))>::value); std::string docStr(_ATTR_DOC(attr)); docStr+=" :yattrflags:`"+boost::lexical_cast<string>(_ATTR_FLG(attr))+"` "; \
if ( _ref && !_ro && !_post) _classObj.def_readwrite(_ATTR_NAM_STR(attr),&thisClass::_ATTR_NAM(attr),docStr.c_str()); \
- else if ( _ref && !_ro && _post) _classObj.add_property(_ATTR_NAM_STR(attr),boost::python::make_getter(&thisClass::_ATTR_NAM(attr)),make_setter_postLoad<thisClass,typeof(thisClass::_ATTR_NAM(attr)),&thisClass::_ATTR_NAM(attr)>,docStr.c_str()); \
+ else if ( _ref && !_ro && _post) _classObj.add_property(_ATTR_NAM_STR(attr),boost::python::make_getter(&thisClass::_ATTR_NAM(attr)),make_setter_postLoad<thisClass,TYPEOF(thisClass::_ATTR_NAM(attr)),&thisClass::_ATTR_NAM(attr)>,docStr.c_str()); \
else if ( _ref && _ro) _classObj.def_readonly(_ATTR_NAM_STR(attr),&thisClass::_ATTR_NAM(attr),docStr.c_str()); \
else if (!_ref && !_ro && !_post) _classObj._DEF_READWRITE_BY_VALUE(thisClass,_ATTR_NAM(attr),docStr.c_str()); \
else if (!_ref && !_ro && _post) _classObj._DEF_READWRITE_BY_VALUE_POSTLOAD(thisClass,_ATTR_NAM(attr),docStr.c_str()); \
@@ -118,11 +98,11 @@
// gcc<=4.3 is not able to compile this code; we will just not generate any code for deprecated attributes in such case
#if !defined(__GNUG__) || (defined(__GNUG__) && (__GNUC__ > 4 || (__GNUC__==4 && __GNUC_MINOR__ > 3)))
// gcc > 4.3 && non-gcc compilers
- #define _PYSET_ATTR_DEPREC(x,thisClass,z) if(key==BOOST_PP_STRINGIZE(_DEPREC_OLDNAME(z))){ _DEPREC_WARN(thisClass,z); _DEPREC_NEWNAME(z)=boost::python::extract<typeof(_DEPREC_NEWNAME(z))>(value); return; }
+ #define _PYSET_ATTR_DEPREC(x,thisClass,z) if(key==BOOST_PP_STRINGIZE(_DEPREC_OLDNAME(z))){ _DEPREC_WARN(thisClass,z); _DEPREC_NEWNAME(z)=boost::python::extract<TYPEOF(_DEPREC_NEWNAME(z))>(value); return; }
#define _PYATTR_DEPREC_DEF(x,thisClass,z) .add_property(BOOST_PP_STRINGIZE(_DEPREC_OLDNAME(z)),&thisClass::BOOST_PP_CAT(_getDeprec_,_DEPREC_OLDNAME(z)),&thisClass::BOOST_PP_CAT(_setDeprec_,_DEPREC_OLDNAME(z)),"|ydeprecated| alias for :yref:`" BOOST_PP_STRINGIZE(_DEPREC_NEWNAME(z)) "<" BOOST_PP_STRINGIZE(thisClass) "." BOOST_PP_STRINGIZE(_DEPREC_NEWNAME(z)) ">` (" _DEPREC_COMMENT(z) ")")
#define _PYHASKEY_ATTR_DEPREC(x,thisClass,z) if(key==BOOST_PP_STRINGIZE(_DEPREC_OLDNAME(z))) return true;
/* accessors functions ussing warning */
- #define _ACCESS_DEPREC(x,thisClass,z) /*getter*/ typeof(_DEPREC_NEWNAME(z)) BOOST_PP_CAT(_getDeprec_,_DEPREC_OLDNAME(z))(){_DEPREC_WARN(thisClass,z); return _DEPREC_NEWNAME(z); } /*setter*/ void BOOST_PP_CAT(_setDeprec_,_DEPREC_OLDNAME(z))(const typeof(_DEPREC_NEWNAME(z))& val){_DEPREC_WARN(thisClass,z); _DEPREC_NEWNAME(z)=val; }
+ #define _ACCESS_DEPREC(x,thisClass,z) /*getter*/ TYPEOF(_DEPREC_NEWNAME(z)) BOOST_PP_CAT(_getDeprec_,_DEPREC_OLDNAME(z))(){_DEPREC_WARN(thisClass,z); return _DEPREC_NEWNAME(z); } /*setter*/ void BOOST_PP_CAT(_setDeprec_,_DEPREC_OLDNAME(z))(const TYPEOF(_DEPREC_NEWNAME(z))& val){_DEPREC_WARN(thisClass,z); _DEPREC_NEWNAME(z)=val; }
#else
#define _PYSET_ATTR_DEPREC(x,y,z)
#define _PYATTR_DEPREC_DEF(x,y,z)
@@ -134,7 +114,7 @@
// loop bodies for attribute access
#define _PYGET_ATTR(x,y,z) if(key==_ATTR_NAM_STR(z)) return boost::python::object(_ATTR_NAM(z));
//#define _PYSET_ATTR(x,y,z) if(key==_ATTR_NAM_STR(z)) { _ATTR_NAM(z)=boost::python::extract<typeof(_ATTR_NAM(z))>(t[1]); boost::python::delitem(d,boost::python::object(_ATTR_NAM(z))); continue; }
-#define _PYSET_ATTR(x,y,z) if(key==_ATTR_NAM_STR(z)) { _ATTR_NAM(z)=boost::python::extract<typeof(_ATTR_NAM(z))>(value); return; }
+#define _PYSET_ATTR(x,y,z) if(key==_ATTR_NAM_STR(z)) { _ATTR_NAM(z)=boost::python::extract<TYPEOF(_ATTR_NAM(z))>(value); return; }
#define _PYKEYS_ATTR(x,y,z) ret.append(_ATTR_NAM_STR(z));
#define _PYHASKEY_ATTR(x,y,z) if(key==_ATTR_NAM_STR(z)) return true;
#define _PYDICT_ATTR(x,y,z) if(!(_ATTR_FLG(z) & yade::Attr::hidden)) ret[_ATTR_NAM_STR(z)]=boost::python::object(_ATTR_NAM(z));
=== modified file 'lib/smoothing/WeightedAverage2d.hpp'
--- lib/smoothing/WeightedAverage2d.hpp 2014-05-23 13:03:50 +0000
+++ lib/smoothing/WeightedAverage2d.hpp 2014-07-03 17:20:40 +0000
@@ -2,35 +2,12 @@
#pragma once
-#include<iostream>
-#include<vector>
-#include<cstdlib>
-#include<algorithm>
-#include<cassert>
-#include<cmath>
-#include<stdexcept>
-#include<boost/foreach.hpp>
-#include<boost/lexical_cast.hpp>
-#include<boost/python.hpp>
-#include<boost/python/object.hpp>
-#include<boost/version.hpp>
+#include<yade/lib/base/Math.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;
-
-#include<yade/lib/base/Math.hpp>
-
+using std::vector;
+using std::string;
template<typename T>
struct GridContainer{
=== modified file 'lib/triangulation/FlowBoundingSphere.hpp'
--- lib/triangulation/FlowBoundingSphere.hpp 2014-06-04 17:19:50 +0000
+++ lib/triangulation/FlowBoundingSphere.hpp 2014-07-02 16:18:24 +0000
@@ -17,7 +17,6 @@
typedef pair<pair<int,int>, vector<double> > Constriction;
-using namespace std;
namespace CGT {
template<class _Tesselation>
=== modified file 'lib/triangulation/FlowBoundingSphere.ipp'
--- lib/triangulation/FlowBoundingSphere.ipp 2014-06-16 14:02:20 +0000
+++ lib/triangulation/FlowBoundingSphere.ipp 2014-07-02 16:18:24 +0000
@@ -31,8 +31,6 @@
// #define USE_FAST_MATH 1
-
-using namespace std;
namespace CGT
{
=== modified file 'lib/triangulation/FlowBoundingSphereLinSolv.hpp'
--- lib/triangulation/FlowBoundingSphereLinSolv.hpp 2014-06-04 17:19:50 +0000
+++ lib/triangulation/FlowBoundingSphereLinSolv.hpp 2014-07-02 16:18:24 +0000
@@ -30,8 +30,6 @@
///_____ Declaration ____
-using namespace std;
-
namespace CGT {
template<class _Tesselation, class FlowType=FlowBoundingSphere<_Tesselation> >
=== modified file 'lib/triangulation/FlowBoundingSphereLinSolv.ipp'
--- lib/triangulation/FlowBoundingSphereLinSolv.ipp 2014-03-21 18:47:45 +0000
+++ lib/triangulation/FlowBoundingSphereLinSolv.ipp 2014-07-02 16:18:24 +0000
@@ -39,8 +39,6 @@
namespace CGT
{
-using namespace std;
-
#ifdef PARDISO
#ifdef AIX
#define F77_FUNC(func) func
@@ -989,4 +987,4 @@
} //namespace CGT
-#endif //FLOW_ENGINE
\ No newline at end of file
+#endif //FLOW_ENGINE
=== modified file 'lib/triangulation/KinematicLocalisationAnalyser.cpp'
--- lib/triangulation/KinematicLocalisationAnalyser.cpp 2014-03-21 18:47:45 +0000
+++ lib/triangulation/KinematicLocalisationAnalyser.cpp 2014-07-03 17:20:40 +0000
@@ -13,8 +13,6 @@
#include "KinematicLocalisationAnalyser.hpp" //This one first, because it defines the info types
// #include "Tesselation.h"
// #include "TriaxialState.h"
-#include <iostream>
-#include <fstream>
#include <sstream>
#include "basicVTKwritter.hpp"
//#include <utility>
@@ -173,7 +171,7 @@
&& TS1->inside(T.segment(*ed_it).target())) {
Segment s = T.segment(*ed_it);
CVector v = s.to_vector();
- Real ny = abs(v.y()/sqrt(s.squared_length()));
+ Real ny = std::abs(v.y()/sqrt(s.squared_length()));
if (Nymin < ny && ny <= Nymax) filteredList.push_back(ed_it);
}
@@ -273,7 +271,7 @@
if (!T.is_infinite(*ed_it)) {
Segment s = T.segment(*ed_it);
CVector v = s.to_vector();
- Real xx = abs(v.z()/sqrt(s.squared_length()));
+ Real xx = std::abs(v.z()/sqrt(s.squared_length()));
if (xx>0.95) edges.push_back(ed_it);
}
@@ -285,7 +283,7 @@
if (!T.is_infinite(*ed_it)) {
Segment s = T.segment(*ed_it);
CVector v = s.to_vector();
- Real xx = abs(v.z()/sqrt(s.squared_length()));
+ Real xx = std::abs(v.z()/sqrt(s.squared_length()));
if (xx<0.05) edges.push_back(ed_it);
}
@@ -297,7 +295,7 @@
if (!T.is_infinite(*ed_it)) {
Segment s = T.segment(*ed_it);
CVector v = s.to_vector();
- Real xx = abs(v.z()/sqrt(s.squared_length()));
+ Real xx = std::abs(v.z()/sqrt(s.squared_length()));
if (xx>0.65 && xx<0.75) edges.push_back(ed_it);
}
@@ -540,11 +538,11 @@
for (TriaxialState::ContactIterator cit = (*TS1).contacts_begin(); cit!=cend; ++cit) {
if ((*TS1).inside((*cit)->grain1->sphere.point()) && (*TS1).inside((*cit)->grain2->sphere.point())) {
- row[(int)(abs((*cit)->normal.z()) /DZ)].second += 2;
+ row[(int)(std::abs((*cit)->normal.z()) /DZ)].second += 2;
nc1 += 2;
} else {
if ((*TS1).inside((*cit)->grain1->sphere.point()) || (*TS1).inside((*cit)->grain2->sphere.point())) {
- row[(int)(abs((*cit)->normal.z()) /DZ)].second += 1;
+ row[(int)(std::abs((*cit)->normal.z()) /DZ)].second += 1;
++nc1;
}
//cerr << "(*cit)->normal.z(),DZ : " << (*cit)->normal.z() << " " << DZ << endl;}
@@ -604,12 +602,12 @@
s = T.segment(*ed_it);
if ((*TS1).inside(s.source()) && (*TS1).inside(s.target())) {
v = s.to_vector();
- row[(int)(abs(v.z() /sqrt(s.squared_length())) /DZ)].second += 2;
+ row[(int)(std::abs(v.z() /sqrt(s.squared_length())) /DZ)].second += 2;
nv1 += 2;
} else {
if ((*TS1).inside(s.source()) || (*TS1).inside(s.target())) {
v = s.to_vector();
- row[(int)(abs(v.z() /sqrt(s.squared_length())) /DZ)].second += 1;
+ row[(int)(std::abs(v.z() /sqrt(s.squared_length())) /DZ)].second += 1;
++nv1;
} else ++nv2;
}
=== modified file 'lib/triangulation/KinematicLocalisationAnalyser.hpp'
--- lib/triangulation/KinematicLocalisationAnalyser.hpp 2014-03-21 18:47:45 +0000
+++ lib/triangulation/KinematicLocalisationAnalyser.hpp 2014-07-02 16:18:24 +0000
@@ -16,6 +16,10 @@
#include "Tenseur3.h"
namespace CGT {
+
+using std::pair;
+using std::ofstream;
+
#define SPHERE_DISCRETISATION 20; //number of "teta" intervals on the unit sphere
#define LINEAR_DISCRETISATION 200; //number of intervals on segments like [UNmin,UNmax]
=== modified file 'lib/triangulation/Network.ipp'
--- lib/triangulation/Network.ipp 2014-05-23 14:06:21 +0000
+++ lib/triangulation/Network.ipp 2014-07-09 07:07:14 +0000
@@ -14,8 +14,6 @@
#define FAST
-
-using namespace std;
namespace CGT {
// template<class Tesselation> const double Network<Tesselation>::FAR = 50000;
=== modified file 'lib/triangulation/PeriodicFlowLinSolv.hpp'
--- lib/triangulation/PeriodicFlowLinSolv.hpp 2014-03-21 18:47:45 +0000
+++ lib/triangulation/PeriodicFlowLinSolv.hpp 2014-07-02 16:18:24 +0000
@@ -11,8 +11,6 @@
#ifdef FLOW_ENGINE
-using namespace std;
-
namespace CGT {
template<class _Tesselation>
=== modified file 'lib/triangulation/PeriodicFlowLinSolv.ipp'
--- lib/triangulation/PeriodicFlowLinSolv.ipp 2014-03-21 18:47:45 +0000
+++ lib/triangulation/PeriodicFlowLinSolv.ipp 2014-07-02 16:18:24 +0000
@@ -24,8 +24,6 @@
namespace CGT
{
-using namespace std;
-
#ifdef PARDISO
#ifdef AIX
#define F77_FUNC(func) func
@@ -251,4 +249,4 @@
} //namespace CGT
-#endif //FLOW_ENGINE
\ No newline at end of file
+#endif //FLOW_ENGINE
=== modified file 'lib/triangulation/Tenseur3.cpp'
--- lib/triangulation/Tenseur3.cpp 2014-03-21 18:45:24 +0000
+++ lib/triangulation/Tenseur3.cpp 2014-07-02 16:18:24 +0000
@@ -1,8 +1,6 @@
-
#include "Tenseur3.h"
#include "RegularTriangulation.h"
-using namespace std;
namespace CGT {
Real Tens::Norme2(void)
=== modified file 'lib/triangulation/Tenseur3.h'
--- lib/triangulation/Tenseur3.h 2014-03-21 18:45:24 +0000
+++ lib/triangulation/Tenseur3.h 2014-07-02 16:18:24 +0000
@@ -6,6 +6,11 @@
namespace CGT {
+using std::endl;
+using std::cout;
+using std::cerr;
+using std::string;
+
#define NORMALIZE(vecteur) ((vecteur) = (vecteur)*(1.0/sqrt(pow((vecteur)[0],2)+pow((vecteur)[1],2)+pow((vecteur)[2],2))))
class Tens;
=== modified file 'lib/triangulation/Tesselation.ipp'
--- lib/triangulation/Tesselation.ipp 2014-03-21 18:47:45 +0000
+++ lib/triangulation/Tesselation.ipp 2014-07-02 16:18:24 +0000
@@ -6,13 +6,18 @@
* GNU General Public License v2 or later. See file LICENSE for details. *
*************************************************************************/
-using namespace std;
-
//FIXME: handle that a better way
#define MAX_ID 200000
namespace CGT {
+using std::cerr;
+using std::cout;
+using std::endl;
+using std::max;
+using std::vector;
+using std::ifstream;
+
template<class TT>
_Tesselation<TT>::_Tesselation ( void )
{
@@ -322,4 +327,4 @@
return true;
}
-} //namespace CGT
\ No newline at end of file
+} //namespace CGT
=== modified file 'lib/triangulation/Timer.cpp'
--- lib/triangulation/Timer.cpp 2010-08-15 04:19:57 +0000
+++ lib/triangulation/Timer.cpp 2014-07-02 16:18:24 +0000
@@ -1,8 +1,6 @@
#include <string.h>
#include "Timer.h"
-using namespace std;
-
Real_timer::Real_timer() : T1(0), T2(0), elapsed(0.0), started(0.0), interv(0), running(true)
{
T1 = clock();
=== modified file 'lib/triangulation/Timer.h'
--- lib/triangulation/Timer.h 2012-01-20 17:31:56 +0000
+++ lib/triangulation/Timer.h 2014-07-02 16:18:24 +0000
@@ -4,6 +4,8 @@
#include <iostream>
#include <time.h>
+using std::string;
+
// SECTION: A Timer Measuring Real-Time
// ========================================================================
//
=== modified file 'lib/triangulation/TriaxialState.cpp'
--- lib/triangulation/TriaxialState.cpp 2014-03-21 18:45:24 +0000
+++ lib/triangulation/TriaxialState.cpp 2014-07-02 18:26:05 +0000
@@ -9,7 +9,7 @@
/// The info types that will be used and the namespace in which the types will be defined (a unique namespace with different info types would give name conflicts)
#include "TriaxialState.h"
-#include <math.h>
+#include <cmath>
#include<boost/iostreams/filtering_stream.hpp>
#include<boost/iostreams/filter/bzip2.hpp>
#include<boost/iostreams/device/file.hpp>
=== modified file 'lib/triangulation/TriaxialState.h'
--- lib/triangulation/TriaxialState.h 2014-03-21 18:45:24 +0000
+++ lib/triangulation/TriaxialState.h 2014-07-02 16:18:24 +0000
@@ -21,7 +21,9 @@
*/
namespace CGT {
-using namespace std;
+
+using std::string;
+using std::min;
class TriaxialState
{
=== modified file 'lib/triangulation/basicVTKwritter.cpp'
--- lib/triangulation/basicVTKwritter.cpp 2012-01-11 21:30:18 +0000
+++ lib/triangulation/basicVTKwritter.cpp 2014-07-02 16:18:24 +0000
@@ -1,7 +1,5 @@
#include "basicVTKwritter.hpp"
-using namespace std;
-
bool basicVTKwritter::open(const char * filename, const char * comment)
{
file.open(filename,ios_base::out);
=== modified file 'lib/triangulation/basicVTKwritter.hpp'
--- lib/triangulation/basicVTKwritter.hpp 2012-01-11 21:30:18 +0000
+++ lib/triangulation/basicVTKwritter.hpp 2014-07-02 16:18:24 +0000
@@ -6,6 +6,11 @@
enum DataName {SCALARS,VECTORS,TENSORS};
enum DataType {INT,FLOAT};
+using std::ios_base;
+using std::endl;
+using std::cout;
+using std::cerr;
+
// Really simplistic struct for vtk file creation
struct basicVTKwritter
{
=== modified file 'pkg/common/Bo1_Box_Aabb.cpp'
--- pkg/common/Bo1_Box_Aabb.cpp 2010-11-07 11:46:20 +0000
+++ pkg/common/Bo1_Box_Aabb.cpp 2014-07-03 07:16:58 +0000
@@ -26,7 +26,7 @@
Vector3r halfSize(Vector3r::Zero());
for( int i=0; i<3; ++i )
for( int j=0; j<3; ++j )
- halfSize[i] += fabs( r(i,j) * box->extents[j] );
+ halfSize[i] += std::abs( r(i,j) * box->extents[j] );
aabb->min = se3.position-halfSize;
aabb->max = se3.position+halfSize;
=== modified file 'pkg/common/BoundaryController.cpp'
--- pkg/common/BoundaryController.cpp 2010-11-07 11:46:20 +0000
+++ pkg/common/BoundaryController.cpp 2014-07-03 17:20:40 +0000
@@ -1,4 +1,3 @@
#include<yade/pkg/common/BoundaryController.hpp>
-#include<stdexcept>
void BoundaryController::action(){ throw std::runtime_error("BoundaryController must not be used in simulations directly (BoundaryController::action called)."); }
YADE_PLUGIN((BoundaryController));
=== modified file 'pkg/common/Callbacks.hpp'
--- pkg/common/Callbacks.hpp 2011-01-09 16:34:50 +0000
+++ pkg/common/Callbacks.hpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,6 @@
// 2010 © Václav Šmilauer <eudoxos@xxxxxxxx>
#pragma once
-#include<stdexcept>
#include<yade/lib/serialization/Serializable.hpp>
class Interaction;
=== modified file 'pkg/common/Collider.cpp'
--- pkg/common/Collider.cpp 2014-06-05 13:19:44 +0000
+++ pkg/common/Collider.cpp 2014-07-02 16:11:24 +0000
@@ -38,7 +38,7 @@
void Collider::findBoundDispatcherInEnginesIfNoFunctorsAndWarn(){
if(boundDispatcher->functors.size()>0) return;
shared_ptr<BoundDispatcher> bd;
- FOREACH(shared_ptr<Engine>& e, scene->engines){ bd=boost::dynamic_pointer_cast<BoundDispatcher>(e); if(bd) break; }
+ FOREACH(shared_ptr<Engine>& e, scene->engines){ bd=YADE_PTR_DYN_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/Cylinder.cpp'
--- pkg/common/Cylinder.cpp 2014-05-06 15:32:52 +0000
+++ pkg/common/Cylinder.cpp 2014-07-03 07:16:58 +0000
@@ -396,17 +396,17 @@
Vector3r N=a.cross(b);
Vector3r normal;
if(N.norm()>1e-14){
- dist=abs(N.dot(B-A)/(N.norm())); //distance between the two LINES.
+ dist=std::abs(N.dot(B-A)/(N.norm())); //distance between the two LINES.
//But we need to check that the intersection point is inside the two SEGMENTS ...
//Projection of B to have a common plan between the two segments.
Vector3r projB1=B+dist*(N/(N.norm())) , projB2=B-dist*(N/(N.norm()));
Real distB1A=(projB1-A).norm() , distB2A=(projB2-A).norm() ;
Vector3r projB=(distB1A<=distB2A)*projB1 + (distB1A>distB2A)*projB2;
int b1=0, b2=1; //base vectors used to compute the segment intersection (if N is aligned with an axis, we can't use this axis)
- if(abs(N[1])<1e-14 && abs(N[2])<1e-14){b1=1;b2=2;}
- if(abs(N[0])<1e-14 && abs(N[2])<1e-14){b1=0;b2=2;}
+ if(std::abs(N[1])<1e-14 && std::abs(N[2])<1e-14){b1=1;b2=2;}
+ if(std::abs(N[0])<1e-14 && std::abs(N[2])<1e-14){b1=0;b2=2;}
Real det=a[b1]*b[b2]-a[b2]*b[b1];
- if(abs(det)>1e-14){ //Check if the two segments are intersected (using k and m)
+ if(std::abs(det)>1e-14){ //Check if the two segments are intersected (using k and m)
k = (b[b2]*(projB[b1]-A[b1])+b[b1]*(A[b2]-projB[b2]))/det;
m = (a[b1]*(-projB[b2]+A[b2])+a[b2]*(projB[b1]-A[b1]))/det;
if( k<0.0 || k>=1.0 || m<0.0 || m>=1.0 ) { //so they are not intersected
=== modified file 'pkg/common/Dispatching.cpp'
--- pkg/common/Dispatching.cpp 2014-04-16 10:30:23 +0000
+++ pkg/common/Dispatching.cpp 2014-07-04 17:46:32 +0000
@@ -36,7 +36,7 @@
Real& sweepLength = b->bound->sweepLength;
if (targetInterv>=0) {
Vector3r disp = b->state->pos-b->bound->refPos;
- Real dist = max(abs(disp[0]),max(abs(disp[1]),abs(disp[2])));
+ Real dist = max(std::abs(disp[0]),max(std::abs(disp[1]),std::abs(disp[2])));
if (dist){
Real newLength = dist*targetInterv/(scene->iter-b->bound->lastUpdateIter);
newLength = max(0.9*sweepLength,newLength);//don't decrease size too fast to prevent time consuming oscillations
@@ -168,7 +168,7 @@
if(interaction->geom){
shared_ptr<Body>& b1 = (*bodies)[interaction->getId1()];
shared_ptr<Body>& b2 = (*bodies)[interaction->getId2()];
- bool hadPhys=interaction->phys;
+ bool hadPhys=(interaction->phys.get() != 0);
operator()(b1->material, b2->material, interaction);
assert(interaction->phys);
if(!hadPhys) interaction->iterMadeReal=scene->iter;
=== modified file 'pkg/common/ElastMat.hpp'
--- pkg/common/ElastMat.hpp 2012-02-14 16:51:38 +0000
+++ pkg/common/ElastMat.hpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,7 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
#pragma once
#include<yade/core/Material.hpp>
-#include<limits>
+
/*! Elastic material */
class ElastMat: public Material{
public:
=== modified file 'pkg/common/Gl1_NormPhys.cpp'
--- pkg/common/Gl1_NormPhys.cpp 2014-05-22 15:26:55 +0000
+++ pkg/common/Gl1_NormPhys.cpp 2014-07-03 07:16:58 +0000
@@ -31,7 +31,7 @@
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);
+ fnNorm=std::abs(fnNorm);
Real radiusScale=1.;
// weak/strong fabric, only used if maxWeakFn is set
if(!isnan(maxWeakFn)){
=== modified file 'pkg/common/Gl1_Sphere.cpp'
--- pkg/common/Gl1_Sphere.cpp 2013-08-23 15:21:20 +0000
+++ pkg/common/Gl1_Sphere.cpp 2014-07-03 07:16:58 +0000
@@ -34,7 +34,7 @@
if (wire || wire2) glutWireSphere(r,quality*glutSlices,quality*glutStacks);
else {
//Check if quality has been modified or if previous lists are invalidated (e.g. by creating a new qt view), then regenerate lists
- bool somethingChanged = (abs(quality-prevQuality)>0.001 || glIsList(glStripedSphereList)!=GL_TRUE);
+ bool somethingChanged = (std::abs(quality-prevQuality)>0.001 || glIsList(glStripedSphereList)!=GL_TRUE);
if (somethingChanged) {initStripedGlList(); initGlutGlList(); prevQuality=quality;}
glScalef(r,r,r);
if(stripes) glCallList(glStripedSphereList);
=== modified file 'pkg/common/GravityEngines.cpp'
--- pkg/common/GravityEngines.cpp 2014-06-05 13:19:44 +0000
+++ pkg/common/GravityEngines.cpp 2014-07-03 07:16:58 +0000
@@ -77,8 +77,8 @@
Vector2i a=readSysfsFile(hdapsDir+"/position");
lastReading=now;
a-=calibrate;
- if(abs(a[0]-accel[0])>updateThreshold) accel[0]=a[0];
- if(abs(a[1]-accel[1])>updateThreshold) accel[1]=a[1];
+ if(std::abs(a[0]-accel[0])>updateThreshold) accel[0]=a[0];
+ if(std::abs(a[1]-accel[1])>updateThreshold) accel[1]=a[1];
Quaternionr trsf(AngleAxisr(.5*accel[0]*M_PI/180.,-Vector3r::UnitY())*AngleAxisr(.5*accel[1]*M_PI/180.,-Vector3r::UnitX()));
gravity=trsf*zeroGravity;
}
=== modified file 'pkg/common/Grid.cpp'
--- pkg/common/Grid.cpp 2014-02-12 13:18:59 +0000
+++ pkg/common/Grid.cpp 2014-07-03 11:31:29 +0000
@@ -90,16 +90,17 @@
Vector3r A=stNode11->pos, a=stNode12->pos-A; //"A" is an extremity of conn1, "a" is the connection's segment.
Vector3r B=stNode21->pos, b=stNode22->pos-B; //"B" is an extremity of conn2, "b" is the connection's segment.
B+=shift2;//periodicity.
+ /* NOW STARTS THE OLD VERSION. IT SHOULD BE REMOVED LATER.
Vector3r N=a.cross(b); //"N" is orthogonal to "a" and "b". It means that "N" describes the common plan between a and b.
if(N.norm()>1e-14){ //If "a" and "b" are colinear, "N==0" and this is a special case.
Real dist=N.dot(B-A)/(N.norm()); //here "dist" is oriented, so it's sign depends on the orientation of "N" against "AB".
Vector3r pB=B-dist*(N/(N.norm())); //"pB" is the projection of the point "B" in the plane defined by his normal vector "N".
//Now we have pB, so we will compute the intersection of two segments into a plane.
int b0, b1; //2 base vectors used to compute the segment intersection. For more accuracy and to avoid det==0, don't choose the axis where N is max.
- if(abs(N[0])<abs(N[1]) || abs(N[0])<abs(N[2])){b0=0 ; b1=abs(N[1])<abs(N[2])?1:2;}
+ if(std::abs(N[0])<std::abs(N[1]) || std::abs(N[0])<std::abs(N[2])){b0=0 ; b1=std::abs(N[1])<std::abs(N[2])?1:2;}
else { b0=1;b1=2;}
Real det=a[b0]*b[b1]-a[b1]*b[b0];
- if (abs(det)>1e-14){
+ if (std::abs(det)>1e-14){
//Now compute k and m, who are the parameters (relative position on the connections) of the intersection on conn1 ("A" and "a") and conn2 ("B" and "b") respectively.
k = (b[b1]*(pB[b0]-A[b0])+b[b0]*(A[b1]-pB[b1]))/det;
m = (a[b0]*(-pB[b1]+A[b1])+a[b1]*(pB[b0]-A[b0]))/det;
@@ -122,7 +123,26 @@
Real PB=(B-A).dot(a)/(a.norm()*a.norm()); PB=min((Real)1.0,max((Real)0.0,PB));
Real Pb=(B+b-A).dot(a)/(a.norm()*a.norm()); Pb=min((Real)1.0,max((Real)0.0,Pb));
k=(PB+Pb)/2. ; m=(PA+Pa)/2.;
- }
+ } OLD VERSION END*/
+
+ /* NOW STARTS THE NEW VERSION */
+ Real denom=a.dot(a)*b.dot(b)-pow(a.dot(b),2);
+ if(denom!=0){
+ k = (a.dot(B-A)*b.dot(b)-a.dot(b)*b.dot(B-A))/denom;
+// m = (a.dot(b)*a.dot(B-A)-b.dot(B-A)*a.dot(a))/denom; //USELESS BECAUSE DETERMINED FROM k
+ k = max(min( k,(Real)1.0),(Real)0.0);
+ m = max(min( (A+a*k-B).dot(b)/(pow(b.norm(),2.0)) ,(Real)1.0),(Real)0.0);
+ k = max(min( (B+b*m-A).dot(a)/(pow(a.norm(),2.0)) ,(Real)1.0),(Real)0.0);
+// cout<<"k="<<k<<" m="<<m<<"\n"<<"kc="<<kc<<" mc="<<mc<<"\n\n"<<endl;//}
+ }
+ else{
+ Real PA=(A-B).dot(b)/(b.norm()*b.norm()); PA=min((Real)1.0,max((Real)0.0,PA));
+ Real Pa=(A+a-B).dot(b)/(b.norm()*b.norm()); Pa=min((Real)1.0,max((Real)0.0,Pa));
+ Real PB=(B-A).dot(a)/(a.norm()*a.norm()); PB=min((Real)1.0,max((Real)0.0,PB));
+ Real Pb=(B+b-A).dot(a)/(a.norm()*a.norm()); Pb=min((Real)1.0,max((Real)0.0,Pb));
+ k=(PB+Pb)/2. ; m=(PA+Pa)/2.;
+ }
+ /*NEW VERSION END*/
//Compute the geometry if "penetrationDepth" is positive.
double penetrationDepth = conn1->radius + conn2->radius - (A+k*a - (B+m*b)).norm();
@@ -183,8 +203,8 @@
Vector3r branch = spherePos - gridNo1St->pos;
Vector3r branchN = spherePos - gridNo2St->pos;
for(int i=0;i<3;i++){
- if(abs(branch[i])<1e-14) branch[i]=0.0;
- if(abs(branchN[i])<1e-14) branchN[i]=0.0;
+ if(std::abs(branch[i])<1e-14) branch[i]=0.0;
+ if(std::abs(branchN[i])<1e-14) branchN[i]=0.0;
}
Real relPos = branch.dot(segt)/(len*len);
if(scm->isDuplicate==2 && scm->trueInt!=c->id2)return true; //the contact will be deleted into the Law, no need to compute here.
@@ -213,7 +233,7 @@
Vector3r segtCandidate2 = GC->node2->state->pos - gridNo1St->pos;
Vector3r segtPrev = segtCandidate1.norm()>segtCandidate2.norm() ? segtCandidate1:segtCandidate2;
for(int j=0;j<3;j++){
- if(abs(segtPrev[j])<1e-14) segtPrev[j]=0.0;
+ if(std::abs(segtPrev[j])<1e-14) segtPrev[j]=0.0;
}
Real relPosPrev = (branch.dot(segtPrev))/(segtPrev.norm()*segtPrev.norm());
// ... and check whether the sphere projection is before the neighbours connections too.
@@ -250,7 +270,7 @@
Vector3r segtCandidate2 = GC->node2->state->pos - gridNo2St->pos;
Vector3r segtNext = segtCandidate1.norm()>segtCandidate2.norm() ? segtCandidate1:segtCandidate2;
for(int j=0;j<3;j++){
- if(abs(segtNext[j])<1e-14) segtNext[j]=0.0;
+ if(std::abs(segtNext[j])<1e-14) segtNext[j]=0.0;
}
Real relPosNext = (branchN.dot(segtNext))/(segtNext.norm()*segtNext.norm());
if(relPosNext<=0){ //if the sphere projection is outside both the current Connection AND this neighbouring connection, then create the interaction if the neighbour did not already do it before.
@@ -283,7 +303,7 @@
Vector3r segtCandidate2 = GC->node2->state->pos - gridNo1St->pos;
Vector3r segtPrev = segtCandidate1.norm()>segtCandidate2.norm() ? segtCandidate1:segtCandidate2;
for(int j=0;j<3;j++){
- if(abs(segtPrev[j])<1e-14) segtPrev[j]=0.0;
+ if(std::abs(segtPrev[j])<1e-14) segtPrev[j]=0.0;
}
Real relPosPrev = (branch.dot(segtPrev))/(segtPrev.norm()*segtPrev.norm());
if(relPosPrev<=0){ //the sphere projection is inside the current Connection and outide this neighbour connection.
@@ -313,7 +333,7 @@
Vector3r segtCandidate2 = GC->node2->state->pos - gridNo2St->pos;
Vector3r segtNext = segtCandidate1.norm()>segtCandidate2.norm() ? segtCandidate1:segtCandidate2;
for(int j=0;j<3;j++){
- if(abs(segtNext[j])<1e-14) segtNext[j]=0.0;
+ if(std::abs(segtNext[j])<1e-14) segtNext[j]=0.0;
}
Real relPosNext = (branchN.dot(segtNext))/(segtNext.norm()*segtNext.norm());
if(relPosNext<=0){ //the sphere projection is inside the current Connection and outide this neighbour connection.
=== modified file 'pkg/common/InsertionSortCollider.cpp'
--- pkg/common/InsertionSortCollider.cpp 2014-05-23 13:05:19 +0000
+++ pkg/common/InsertionSortCollider.cpp 2014-07-03 17:20:40 +0000
@@ -9,15 +9,11 @@
#include<yade/pkg/dem/NewtonIntegrator.hpp>
#include<yade/pkg/common/Sphere.hpp>
-#include<algorithm>
-#include<vector>
#include<boost/static_assert.hpp>
#ifdef YADE_OPENMP
#include<omp.h>
#endif
-using namespace std;
-
YADE_PLUGIN((InsertionSortCollider))
CREATE_LOGGER(InsertionSortCollider);
@@ -252,7 +248,7 @@
}
if (isinf(minR)) LOG_ERROR("verletDist is set to 0 because no spheres were found. It will result in suboptimal performances, consider setting a positive verletDist in your script.");
// if no spheres, disable stride
- verletDist=isinf(minR) ? 0 : abs(verletDist)*minR;
+ verletDist=isinf(minR) ? 0 : std::abs(verletDist)*minR;
}
// if interactions are dirty, force reinitialization
if(scene->interactions->dirty){
@@ -274,7 +270,7 @@
if(verletDist>0){
// get NewtonIntegrator, to ask for the maximum velocity value
if(!newton){
- FOREACH(shared_ptr<Engine>& e, scene->engines){ newton=boost::dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) break; }
+ FOREACH(shared_ptr<Engine>& e, scene->engines){ newton=YADE_PTR_DYN_CAST<NewtonIntegrator>(e); if(newton) break; }
if(!newton){ throw runtime_error("InsertionSortCollider.verletDist>0, but unable to locate NewtonIntegrator within O.engines."); }
}
}
=== modified file 'pkg/common/KinematicEngines.cpp'
--- pkg/common/KinematicEngines.cpp 2014-04-23 13:38:24 +0000
+++ pkg/common/KinematicEngines.cpp 2014-07-03 07:16:58 +0000
@@ -169,8 +169,8 @@
curVel = (pTerm + iTerm + dTerm); // Calculate current velocity
- if (fabs(curVel) > fabs(maxVelocity)) {
- curVel*=fabs(maxVelocity)/fabs(curVel);
+ if (std::abs(curVel) > std::abs(maxVelocity)) {
+ curVel*=std::abs(maxVelocity)/std::abs(curVel);
}
iterPrevStart = scene->iter;
=== modified file 'pkg/common/MatchMaker.cpp'
--- pkg/common/MatchMaker.cpp 2014-05-23 13:03:50 +0000
+++ pkg/common/MatchMaker.cpp 2014-07-03 17:20:40 +0000
@@ -1,10 +1,6 @@
// 2010 © Václav Šmilauer <eudoxos@xxxxxxxx>
#include<yade/pkg/common/MatchMaker.hpp>
-#include<boost/foreach.hpp>
-#ifndef FOREACH
- #define FOREACH BOOST_FOREACH
-#endif
YADE_PLUGIN((MatchMaker));
MatchMaker::~MatchMaker(){}
=== modified file 'pkg/common/MatchMaker.hpp'
--- pkg/common/MatchMaker.hpp 2010-12-09 15:02:38 +0000
+++ pkg/common/MatchMaker.hpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,6 @@
// 2010 © Václav Šmilauer <eudoxos@xxxxxxxx>
#pragma once
#include<yade/lib/serialization/Serializable.hpp>
-#include<string>
namespace py = boost::python;
=== modified file 'pkg/common/ParallelEngine.cpp'
--- pkg/common/ParallelEngine.cpp 2014-05-23 13:03:50 +0000
+++ pkg/common/ParallelEngine.cpp 2014-07-03 17:20:40 +0000
@@ -1,5 +1,4 @@
#include"ParallelEngine.hpp"
-#include<boost/python.hpp>
#ifdef YADE_OPENMP
#include<omp.h>
=== modified file 'pkg/common/ParallelEngine.hpp'
--- pkg/common/ParallelEngine.hpp 2014-05-23 13:03:50 +0000
+++ pkg/common/ParallelEngine.hpp 2014-07-03 17:20:40 +0000
@@ -1,6 +1,5 @@
#pragma once
#include<yade/core/GlobalEngine.hpp>
-#include<boost/python.hpp>
class ParallelEngine;
shared_ptr<ParallelEngine> ParallelEngine_ctor_list(const boost::python::list& slaves);
=== modified file 'pkg/common/PersistentTriangulationCollider.cpp'
--- pkg/common/PersistentTriangulationCollider.cpp 2014-03-21 18:45:24 +0000
+++ pkg/common/PersistentTriangulationCollider.cpp 2014-07-03 17:20:40 +0000
@@ -10,15 +10,9 @@
#include<yade/core/Body.hpp>
#include<yade/core/Scene.hpp>
#include<yade/core/BodyContainer.hpp>
-#include<limits>
-#include<utility>
-#include<vector>
#include<yade/pkg/common/Sphere.hpp>
#include<yade/pkg/common/ElastMat.hpp>
-
-using namespace std;
-
// PersistentTriangulationCollider::PersistentTriangulationCollider() : Collider()
// {
// haveDistantTransient=false;
=== modified file 'pkg/common/Recorder.hpp'
--- pkg/common/Recorder.hpp 2010-11-07 11:46:20 +0000
+++ pkg/common/Recorder.hpp 2014-07-03 17:20:40 +0000
@@ -1,8 +1,6 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
#pragma once
#include<yade/pkg/common/PeriodicEngines.hpp>
-#include<fstream>
-#include<string>
class Recorder: public PeriodicEngine{
void openAndCheck();
protected:
=== modified file 'pkg/common/ResetRandomPosition.cpp'
--- pkg/common/ResetRandomPosition.cpp 2011-01-21 08:14:28 +0000
+++ pkg/common/ResetRandomPosition.cpp 2014-07-03 17:20:40 +0000
@@ -18,7 +18,6 @@
#include<yade/pkg/common/InteractionLoop.hpp>
//#include<yade/pkg/dem/BodyMacroParameters.hpp>
#include"ResetRandomPosition.hpp"
-#include<sstream>
YADE_PLUGIN((ResetRandomPosition));
CREATE_LOGGER(ResetRandomPosition);
=== modified file 'pkg/common/ResetRandomPosition.hpp'
--- pkg/common/ResetRandomPosition.hpp 2012-03-21 08:38:49 +0000
+++ pkg/common/ResetRandomPosition.hpp 2014-07-02 16:18:24 +0000
@@ -14,8 +14,6 @@
#include <vector>
#include <string>
-using namespace std;
-
/// @brief Produces spheres over the course of a simulation.
class ResetRandomPosition : public PeriodicEngine {
public:
=== modified file 'pkg/common/SpatialQuickSortCollider.cpp'
--- pkg/common/SpatialQuickSortCollider.cpp 2014-02-03 11:21:42 +0000
+++ pkg/common/SpatialQuickSortCollider.cpp 2014-07-02 18:26:05 +0000
@@ -8,7 +8,7 @@
#include "SpatialQuickSortCollider.hpp"
#include <yade/core/Scene.hpp>
#include <yade/core/BodyContainer.hpp>
-#include <math.h>
+#include <cmath>
#include <algorithm>
YADE_PLUGIN((SpatialQuickSortCollider));
=== modified file 'pkg/common/SpatialQuickSortCollider.hpp'
--- pkg/common/SpatialQuickSortCollider.hpp 2010-11-12 08:03:16 +0000
+++ pkg/common/SpatialQuickSortCollider.hpp 2014-07-02 16:18:24 +0000
@@ -11,8 +11,6 @@
#include <yade/core/InteractionContainer.hpp>
#include <vector>
-using namespace std;
-
class SpatialQuickSortCollider : public Collider {
protected:
=== modified file 'pkg/common/Wall.cpp'
--- pkg/common/Wall.cpp 2014-01-13 09:23:51 +0000
+++ pkg/common/Wall.cpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,6 @@
// © 2009 Václav Šmilauer <eudoxos@xxxxxxxx>
#include<yade/pkg/common/Wall.hpp>
#include<yade/pkg/common/Aabb.hpp>
-#include<limits>
YADE_PLUGIN((Wall)(Bo1_Wall_Aabb)
#ifdef YADE_OPENGL
=== modified file 'pkg/common/ZECollider.cpp'
--- pkg/common/ZECollider.cpp 2014-05-23 13:05:19 +0000
+++ pkg/common/ZECollider.cpp 2014-07-03 17:20:40 +0000
@@ -10,12 +10,8 @@
#include<yade/pkg/dem/NewtonIntegrator.hpp>
#include<yade/pkg/common/Sphere.hpp>
-#include<algorithm>
-#include<vector>
#include<boost/static_assert.hpp>
-using namespace std;
-
YADE_PLUGIN((ZECollider))
CREATE_LOGGER(ZECollider);
@@ -72,7 +68,7 @@
minR=min(s->radius,minR);
}
// if no spheres, disable stride
- verletDist=isinf(minR) ? 0 : abs(verletDist)*minR;
+ verletDist=isinf(minR) ? 0 : std::abs(verletDist)*minR;
}
// update bounds via boundDispatcher
@@ -92,7 +88,7 @@
if(verletDist>0){
// get NewtonIntegrator, to ask for the maximum velocity value
if(!newton){
- FOREACH(shared_ptr<Engine>& e, scene->engines){ newton=boost::dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) break; }
+ FOREACH(shared_ptr<Engine>& e, scene->engines){ newton=YADE_PTR_DYN_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/common/ZECollider.hpp'
--- pkg/common/ZECollider.hpp 2012-09-08 01:19:45 +0000
+++ pkg/common/ZECollider.hpp 2014-07-03 17:20:40 +0000
@@ -5,8 +5,6 @@
#include<yade/core/Scene.hpp>
class InteractionContainer;
-
-
// #define this macro to enable timing within this engine
#define ISC_TIMING
@@ -18,11 +16,8 @@
class NewtonIntegrator;
-
-
#include <CGAL/box_intersection_d.h>
#include <CGAL/Bbox_2.h>
-#include <iostream>
#include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
#include <CGAL/intersections.h>
#include <CGAL/point_generators_3.h>
@@ -31,7 +26,6 @@
#include <CGAL/function_objects.h>
#include <CGAL/Join_input_iterator.h>
#include <CGAL/algorithm.h>
-#include <vector>
typedef CGAL::Bbox_3 CGBbox;
// typedef CGAL::Box_intersection_d::Box_with_handle_d<double,3,shared_ptr<Body> > CGBox;
=== modified file 'pkg/dem/BubbleMat.cpp'
--- pkg/dem/BubbleMat.cpp 2013-06-15 19:17:48 +0000
+++ pkg/dem/BubbleMat.cpp 2014-07-03 07:16:58 +0000
@@ -37,7 +37,7 @@
f = penetrationDepth - ret*c1*ll;
df = -c1*(ll + 1);
ret -= f/df;
- residual = fabs(ret - retOld)/retOld;
+ residual = std::abs(ret - retOld)/retOld;
if (i++ > newtonIter) {
throw runtime_error("BubblePhys::computeForce: no convergence\n");
}
=== modified file 'pkg/dem/CapillaryStressRecorder.cpp'
--- pkg/dem/CapillaryStressRecorder.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/CapillaryStressRecorder.cpp 2014-07-03 17:20:40 +0000
@@ -15,7 +15,6 @@
#include <yade/core/Omega.hpp>
#include <yade/core/Scene.hpp>
-#include <boost/lexical_cast.hpp>
YADE_PLUGIN((CapillaryStressRecorder));
CREATE_LOGGER(CapillaryStressRecorder);
=== modified file 'pkg/dem/CapillaryTriaxialTest.cpp'
--- pkg/dem/CapillaryTriaxialTest.cpp 2014-06-17 10:18:00 +0000
+++ pkg/dem/CapillaryTriaxialTest.cpp 2014-07-03 17:20:40 +0000
@@ -43,7 +43,6 @@
#include<yade/pkg/dem/Shop.hpp>
#include <boost/filesystem/convenience.hpp>
-#include <boost/lexical_cast.hpp>
#include <boost/numeric/conversion/bounds.hpp>
#include <boost/limits.hpp>
@@ -53,8 +52,6 @@
#include <boost/random/variate_generator.hpp>
#include <boost/random/normal_distribution.hpp>
-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);
@@ -80,9 +77,9 @@
lowerCorner[1]-thickness/2.0,
(lowerCorner[2]+upperCorner[2])/2);
Vector3r halfSize = Vector3r(
- wallOversizeFactor*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
thickness/2.0,
- wallOversizeFactor*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ wallOversizeFactor*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,wall_bottom_wire);
if(wall_bottom) {
@@ -98,9 +95,9 @@
upperCorner[1]+thickness/2.0,
(lowerCorner[2]+upperCorner[2])/2);
halfSize = Vector3r(
- wallOversizeFactor*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
thickness/2.0,
- wallOversizeFactor*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ wallOversizeFactor*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,wall_top_wire);
if(wall_top) {
@@ -116,8 +113,8 @@
(lowerCorner[2]+upperCorner[2])/2);
halfSize = Vector3r(
thickness/2.0,
- wallOversizeFactor*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
- wallOversizeFactor*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ wallOversizeFactor*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,wall_1_wire);
if(wall_1) {
scene->bodies->insert(body);
@@ -131,8 +128,8 @@
(lowerCorner[2]+upperCorner[2])/2);
halfSize = Vector3r(
thickness/2.0,
- wallOversizeFactor*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
- wallOversizeFactor*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ wallOversizeFactor*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,wall_2_wire);
if(wall_2) {
@@ -146,8 +143,8 @@
(lowerCorner[1]+upperCorner[1])/2,
lowerCorner[2]-thickness/2.0);
halfSize = Vector3r(
- wallOversizeFactor*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
- wallOversizeFactor*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
thickness/2.0);
createBox(body,center,halfSize,wall_3_wire);
if(wall_3) {
@@ -162,8 +159,8 @@
(lowerCorner[1]+upperCorner[1])/2,
upperCorner[2]+thickness/2.0);
halfSize = Vector3r(
- wallOversizeFactor*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
- wallOversizeFactor*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
thickness/2.0);
createBox(body,center,halfSize,wall_3_wire);
if(wall_4) {
=== modified file 'pkg/dem/CohesiveFrictionalContactLaw.hpp'
--- pkg/dem/CohesiveFrictionalContactLaw.hpp 2014-05-26 16:49:23 +0000
+++ pkg/dem/CohesiveFrictionalContactLaw.hpp 2014-07-03 17:20:40 +0000
@@ -12,7 +12,6 @@
#include<yade/pkg/dem/ScGeom.hpp>
#include<yade/pkg/dem/CohFrictPhys.hpp>
#include<yade/pkg/common/Dispatching.hpp>
-#include<set>
#include<boost/tuple/tuple.hpp>
class Law2_ScGeom6D_CohFrictPhys_CohesionMoment: public LawFunctor{
=== modified file 'pkg/dem/CohesiveTriaxialTest.cpp'
--- pkg/dem/CohesiveTriaxialTest.cpp 2014-06-17 10:18:00 +0000
+++ pkg/dem/CohesiveTriaxialTest.cpp 2014-07-03 17:20:40 +0000
@@ -39,7 +39,6 @@
#include<yade/pkg/dem/Shop.hpp>
#include <boost/filesystem/convenience.hpp>
-#include <boost/lexical_cast.hpp>
#include <boost/numeric/conversion/bounds.hpp>
#include <boost/limits.hpp>
@@ -49,9 +48,6 @@
#include <boost/random/variate_generator.hpp>
#include <boost/random/normal_distribution.hpp>
-using namespace std;
-
-
typedef pair<Vector3r, Real> BasicSphere;
//! make a list of spheres non-overlapping sphere
string GenerateCloud_cohesive(vector<BasicSphere>& sphere_list, Vector3r lowerCorner, Vector3r upperCorner, long number, Real rad_std_dev, Real porosity);
@@ -76,9 +72,9 @@
lowerCorner[1]-thickness/2.0,
(lowerCorner[2]+upperCorner[2])/2);
Vector3r halfSize = Vector3r(
- 1.5*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ 1.5*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
thickness/2.0,
- 1.5*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ 1.5*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,wall_bottom_wire);
if(wall_bottom) {
@@ -96,9 +92,9 @@
upperCorner[1]+thickness/2.0,
(lowerCorner[2]+upperCorner[2])/2);
halfSize = Vector3r(
- 1.5*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ 1.5*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
thickness/2.0,
- 1.5*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ 1.5*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,wall_top_wire);
if(wall_top) {
@@ -114,8 +110,8 @@
(lowerCorner[2]+upperCorner[2])/2);
halfSize = Vector3r(
thickness/2.0,
- 1.5*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
- 1.5*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ 1.5*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ 1.5*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,wall_1_wire);
if(wall_1) {
scene->bodies->insert(body);
@@ -129,8 +125,8 @@
(lowerCorner[2]+upperCorner[2])/2);
halfSize = Vector3r(
thickness/2.0,
- 1.5*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
- 1.5*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ 1.5*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ 1.5*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,wall_2_wire);
if(wall_2) {
@@ -144,8 +140,8 @@
(lowerCorner[1]+upperCorner[1])/2,
lowerCorner[2]-thickness/2.0);
halfSize = Vector3r(
- 1.5*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
- 1.5*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ 1.5*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ 1.5*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
thickness/2.0);
createBox(body,center,halfSize,wall_3_wire);
if(wall_3) {
@@ -160,8 +156,8 @@
(lowerCorner[1]+upperCorner[1])/2,
upperCorner[2]+thickness/2.0);
halfSize = Vector3r(
- 1.5*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
- 1.5*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ 1.5*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ 1.5*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
thickness/2.0);
createBox(body,center,halfSize,wall_3_wire);
if(wall_4) {
=== modified file 'pkg/dem/ConcretePM.cpp'
--- pkg/dem/ConcretePM.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/ConcretePM.cpp 2014-07-03 07:16:58 +0000
@@ -118,7 +118,7 @@
#endif
Real aux = c*exp(N*ret)+exp(ret);
f = log(aux);
- if (fabs(f) < maxError) return ret;
+ if (std::abs(f) < maxError) return ret;
Real df = (c*N*exp(N*ret)+exp(ret))/aux;
ret -= f/df;
}
@@ -185,7 +185,7 @@
dfg = CpmPhys::funcGDKappa(ret,epsCrackOnset,epsFracture,neverDamage,damLaw);
decr = fg/dfg;
ret -= decr;
- if (fabs(decr/epsCrackOnset) < tol) {
+ if (std::abs(decr/epsCrackOnset) < tol) {
return ret;
}
}
@@ -218,7 +218,7 @@
df = e0i*(1-g-k*dg);
decr = f/df;
k -= decr;
- if (fabs(decr) < tol) {
+ if (std::abs(decr) < tol) {
kappaD = k;
omega = CpmPhys::funcG(k,epsCrackOnset,epsFracture,neverDamage,damLaw);
relResidualStrength = r;
@@ -564,7 +564,7 @@
FOREACH(const shared_ptr<Interaction>& I, *scene->interactions){
if (!I) continue;
if (!I->isReal()) continue;
- shared_ptr<CpmPhys> phys = boost::dynamic_pointer_cast<CpmPhys>(I->phys);
+ shared_ptr<CpmPhys> phys = YADE_PTR_DYN_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/DomainLimiter.cpp'
--- pkg/dem/DomainLimiter.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/DomainLimiter.cpp 2014-07-03 07:16:58 +0000
@@ -110,7 +110,7 @@
axX=gsc->normal; /* just in case */ axX.normalize();
if(doInit){ // initialization of the new interaction -- define local axes
// take vector in the y or z direction, depending on its length; arbitrary, but one of them is sure to be non-zero
- axY=axX.cross(abs(axX[1])<abs(axX[2])?Vector3r::UnitY():Vector3r::UnitZ());
+ axY=axX.cross(std::abs(axX[1])<std::abs(axX[2])?Vector3r::UnitY():Vector3r::UnitZ());
axY.normalize();
axZ=axX.cross(axY);
LOG_DEBUG("Initial axes x="<<axX<<", y="<<axY<<", z="<<axZ);
@@ -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=boost::dynamic_pointer_cast<LawTester>(e); if(tester) break; } }
+ if(!tester){ FOREACH(shared_ptr<Engine> e, scene->engines){ tester=YADE_PTR_DYN_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 2014-05-23 13:05:19 +0000
+++ pkg/dem/FacetTopologyAnalyzer.cpp 2014-07-03 07:16:58 +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=boost::dynamic_pointer_cast<Facet>(b->shape);
+ shared_ptr<Facet> f=YADE_PTR_DYN_CAST<Facet>(b->shape);
if(!f) continue;
const Vector3r& pos=b->state->pos;
for(size_t i=0; i<3; i++){
@@ -34,9 +34,9 @@
j=i;
while(++j<nVertices && (vv[j]->coord-vv[i]->coord)<=tolerance){
shared_ptr<VertexData> &vi=vv[i], &vj=vv[j];
- if(abs(vi->pos[0]-vj->pos[0])<=tolerance &&
- abs(vi->pos[1]-vj->pos[1])<=tolerance &&
- abs(vi->pos[2]-vj->pos[2])<=tolerance &&
+ if(std::abs(vi->pos[0]-vj->pos[0])<=tolerance &&
+ std::abs(vi->pos[1]-vj->pos[1])<=tolerance &&
+ std::abs(vi->pos[2]-vj->pos[2])<=tolerance &&
(vi->pos-vj->pos).squaredNorm()<=tolerance*tolerance){
// OK, these two vertices touch
// LOG_TRACE("Vertices "<<vi->id<<"/"<<vi->vertexNo<<" and "<<vj->id<<"/"<<vj->vertexNo<<" close enough.");
=== modified file 'pkg/dem/FlatGridCollider.cpp'
--- pkg/dem/FlatGridCollider.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/FlatGridCollider.cpp 2014-07-01 18:14:18 +0000
@@ -21,7 +21,7 @@
void FlatGridCollider::action(){
if(!newton){
- FOREACH(const shared_ptr<Engine>& e, scene->engines){ newton=boost::dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) break; }
+ FOREACH(const shared_ptr<Engine>& e, scene->engines){ newton=YADE_PTR_DYN_CAST<NewtonIntegrator>(e); if(newton) break; }
if(!newton){ throw runtime_error("FlatGridCollider: Unable to find NewtonIntegrator in engines."); }
}
fastestBodyMaxDist=0;
=== modified file 'pkg/dem/FlatGridCollider.hpp'
--- pkg/dem/FlatGridCollider.hpp 2012-09-08 01:19:45 +0000
+++ pkg/dem/FlatGridCollider.hpp 2014-07-03 17:20:40 +0000
@@ -1,5 +1,4 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
-#include<vector>
#include<yade/pkg/common/Collider.hpp>
class NewtonIntegrator;
class FlatGridCollider: public Collider{
=== modified file 'pkg/dem/FrictViscoPM.hpp'
--- pkg/dem/FrictViscoPM.hpp 2014-06-10 03:36:47 +0000
+++ pkg/dem/FrictViscoPM.hpp 2014-07-03 17:20:40 +0000
@@ -26,7 +26,6 @@
#include<yade/pkg/dem/ScGeom.hpp>
#include<yade/lib/base/openmp-accu.hpp>
-#include<set>
#include<boost/tuple/tuple.hpp>
/** This class holds information associated with each body */
=== modified file 'pkg/dem/GeneralIntegratorInsertionSortCollider.cpp'
--- pkg/dem/GeneralIntegratorInsertionSortCollider.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/GeneralIntegratorInsertionSortCollider.cpp 2014-07-03 07:16:58 +0000
@@ -12,8 +12,6 @@
#include<vector>
#include<boost/static_assert.hpp>
-using namespace std;
-
YADE_PLUGIN((GeneralIntegratorInsertionSortCollider))
CREATE_LOGGER(GeneralIntegratorInsertionSortCollider);
@@ -90,7 +88,7 @@
}
if (isinf(minR)) LOG_ERROR("verletDist is set to 0 because no spheres were found. It will result in suboptimal performances, consider setting a positive verletDist in your script.");
// if no spheres, disable stride
- verletDist=isinf(minR) ? 0 : abs(verletDist)*minR;
+ verletDist=isinf(minR) ? 0 : std::abs(verletDist)*minR;
}
// update bounds via boundDispatcher
@@ -111,7 +109,7 @@
if(verletDist>0){
// get the Integrator, to ask for the maximum velocity value
if(!integrator){
- FOREACH(shared_ptr<Engine>& e, scene->engines){ integrator=boost::dynamic_pointer_cast<Integrator>(e); if(integrator) break; }
+ FOREACH(shared_ptr<Engine>& e, scene->engines){ integrator=YADE_PTR_DYN_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/Ig2_Box_Sphere_ScGeom.cpp'
--- pkg/dem/Ig2_Box_Sphere_ScGeom.cpp 2012-02-29 19:07:56 +0000
+++ pkg/dem/Ig2_Box_Sphere_ScGeom.cpp 2014-07-03 07:16:58 +0000
@@ -52,10 +52,10 @@
shared_ptr<ScGeom> scm;
if (inside){
// sphere center inside box. find largest `cOnBox_boxLocal' value:
- // minCBoxDist_index is the coordinate index that minimizes extents[minCBoxDist_index]-abs(cOnBox_boxLocal[minCBoxDist_index] (sphere center closest to box boundary)
+ // minCBoxDist_index is the coordinate index that minimizes extents[minCBoxDist_index]-std::abs(cOnBox_boxLocal[minCBoxDist_index] (sphere center closest to box boundary)
// where cOnBox_boxLocal is minimal (i.e. where sphere center is closest perpendicularly to the box)
- Real minCBoxDist=extents[0]-fabs(cOnBox_boxLocal[0]); int minCBoxDist_index=0;
- for (int i=1; i<3; i++){Real tt=extents[i]-fabs(cOnBox_boxLocal[i]); if (tt<minCBoxDist){minCBoxDist=tt; minCBoxDist_index=i;}}
+ Real minCBoxDist=extents[0]-std::abs(cOnBox_boxLocal[0]); int minCBoxDist_index=0;
+ for (int i=1; i<3; i++){Real tt=extents[i]-std::abs(cOnBox_boxLocal[i]); if (tt<minCBoxDist){minCBoxDist=tt; minCBoxDist_index=i;}}
// contact normal aligned with box edge along largest `cOnBox_boxLocal' value
Vector3r normal_boxLocal = Vector3r(0,0,0);
=== modified file 'pkg/dem/Ig2_Facet_Sphere_ScGeom.cpp'
--- pkg/dem/Ig2_Facet_Sphere_ScGeom.cpp 2013-04-25 11:35:51 +0000
+++ pkg/dem/Ig2_Facet_Sphere_ScGeom.cpp 2014-07-03 07:16:58 +0000
@@ -180,7 +180,7 @@
const Real radius=static_cast<Sphere*>(cm2.get())->radius;
const int& ax(wall->axis);
Real dist=(state2.pos)[ax]+shift2[ax]-state1.pos[ax]; // signed "distance" between centers
- if(!c->isReal() && abs(dist)>radius && !force) { return false; }// wall and sphere too far from each other
+ if(!c->isReal() && std::abs(dist)>radius && !force) { return false; }// wall and sphere too far from each other
// contact point is sphere center projected onto the wall
Vector3r contPt=state2.pos+shift2; contPt[ax]=state1.pos[ax];
@@ -195,7 +195,7 @@
const shared_ptr<ScGeom>& ws=YADE_PTR_CAST<ScGeom>(c->geom);
ws->radius1=ws->radius2=radius; // do the same as for facet-sphere: wall's "radius" is the same as the sphere's radius
ws->contactPoint=contPt;
- ws->penetrationDepth=-(abs(dist)-radius);
+ ws->penetrationDepth=-(std::abs(dist)-radius);
// ws->normal is assigned by precompute
ws->precompute(state1,state2,scene,c,normal,isNew,shift2,noRatch);
return true;
=== modified file 'pkg/dem/Integrator.cpp'
--- pkg/dem/Integrator.cpp 2014-05-23 13:03:50 +0000
+++ pkg/dem/Integrator.cpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,6 @@
#include<yade/core/Clump.hpp>
#include<yade/core/Scene.hpp>
#include<yade/pkg/dem/Integrator.hpp>
-#include<boost/python.hpp>
#ifdef YADE_OPENMP
#include<omp.h>
@@ -316,7 +315,7 @@
void Integrator::saveMaximaDisplacement(const shared_ptr<Body>& b){
if (!b->bound) return;//clumps for instance, have no bounds, hence not saved
Vector3r disp=b->state->pos-b->bound->refPos;
- Real maxDisp=max(abs(disp[0]),max(abs(disp[1]),abs(disp[2])));
+ Real maxDisp=max(std::abs(disp[0]),max(std::abs(disp[1]),std::abs(disp[2])));
if (!maxDisp || maxDisp<b->bound->sweepLength) {/*b->bound->isBounding = (updatingDispFactor>0 && (updatingDispFactor*maxDisp)<b->bound->sweepLength);*/
maxDisp=0.5;//not 0, else it will be seen as "not updated" by the collider, but less than 1 means no colliding
}
=== modified file 'pkg/dem/Integrator.hpp'
--- pkg/dem/Integrator.hpp 2014-02-17 14:31:35 +0000
+++ pkg/dem/Integrator.hpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,6 @@
#pragma once
#include<yade/core/TimeStepper.hpp>
-#include<boost/python.hpp>
class Integrator;
=== modified file 'pkg/dem/JointedCohesiveFrictionalPM.cpp'
--- pkg/dem/JointedCohesiveFrictionalPM.cpp 2014-06-10 14:27:43 +0000
+++ pkg/dem/JointedCohesiveFrictionalPM.cpp 2014-07-03 07:16:58 +0000
@@ -34,7 +34,7 @@
if ((smoothJoint) && (phys->isOnJoint)) {
phys->jointNormal = geom->normal.dot(phys->jointNormal)*phys->jointNormal; //to set the joint normal colinear with the interaction normal
phys->jointNormal.normalize();
- phys->initD = abs((b1->state->pos - b2->state->pos).dot(phys->jointNormal)); // to set the initial gap as the equilibrium gap
+ phys->initD = std::abs((b1->state->pos - b2->state->pos).dot(phys->jointNormal)); // to set the initial gap as the equilibrium gap
} else {
phys->initD = geom->penetrationDepth;
}
@@ -44,7 +44,7 @@
if ( phys->more || ( phys->jointCumulativeSliding > (2*min(geom->radius1,geom->radius2)) ) ) {
scene->interactions->requestErase(contact); return;
} else {
- D = phys->initD - abs((b1->state->pos - b2->state->pos).dot(phys->jointNormal));
+ D = phys->initD - std::abs((b1->state->pos - b2->state->pos).dot(phys->jointNormal));
}
} else {
D = geom->penetrationDepth - phys->initD;
@@ -57,7 +57,7 @@
scene->interactions->requestErase(contact); return;
}
- if ( phys->isCohesive && (phys->FnMax>0) && (abs(D)>Dtensile) ) {
+ if ( phys->isCohesive && (phys->FnMax>0) && (std::abs(D)>Dtensile) ) {
// update body state with the number of broken bonds
JCFpmState* st1=dynamic_cast<JCFpmState*>(b1->state.get());
=== modified file 'pkg/dem/KinemSimpleShearBox.cpp'
--- pkg/dem/KinemSimpleShearBox.cpp 2014-05-28 08:55:24 +0000
+++ pkg/dem/KinemSimpleShearBox.cpp 2014-07-03 07:16:58 +0000
@@ -199,9 +199,9 @@
deltaH = (1-wallDamping)*deltaH;
if(LOG) cout << "deltaH apres amortissement :" << deltaH << endl;
- if(abs(deltaH) > max_vel*scene->dt)
+ if(std::abs(deltaH) > max_vel*scene->dt)
{
- deltaH=deltaH/abs(deltaH)*max_vel*scene->dt;
+ deltaH=deltaH/std::abs(deltaH)*max_vel*scene->dt;
if(LOG) cout << "Correction appliquee pour ne pas depasser vmax(comp)" << endl;
}
=== modified file 'pkg/dem/L3Geom.cpp'
--- pkg/dem/L3Geom.cpp 2013-08-23 15:21:20 +0000
+++ pkg/dem/L3Geom.cpp 2014-07-03 17:20:40 +0000
@@ -4,8 +4,6 @@
#include<yade/pkg/common/Wall.hpp>
#include<yade/pkg/common/Facet.hpp>
-#include<sstream>
-
#ifdef YADE_OPENGL
#include<yade/lib/opengl/OpenGLWrapper.hpp>
#include<yade/lib/opengl/GLUtils.hpp>
@@ -66,7 +64,7 @@
const Real& r1=s1->cast<Sphere>().radius; const Real& r2=s2->cast<Sphere>().radius;
Vector3r relPos=state2.pos+shift2-state1.pos;
- Real unDistSq=relPos.squaredNorm()-pow(abs(distFactor)*(r1+r2),2);
+ Real unDistSq=relPos.squaredNorm()-pow(std::abs(distFactor)*(r1+r2),2);
if (unDistSq>0 && !I->isReal() && !force) return false;
// contact exists, go ahead
@@ -97,7 +95,7 @@
// g.trsf.setFromTwoVectors(Vector3r::UnitX(),g.normal); // quaternion just from the X-axis; does not seem to work for some reason?!
const Vector3r& locX(g.normal);
// initial local y-axis orientation, in the xz or xy plane, depending on which component is larger to avoid singularities
- Vector3r locY=normal.cross(abs(normal[1])<abs(normal[2])?Vector3r::UnitY():Vector3r::UnitZ()); locY-=locX*locY.dot(locX); locY.normalize();
+ Vector3r locY=normal.cross(std::abs(normal[1])<std::abs(normal[2])?Vector3r::UnitY():Vector3r::UnitZ()); locY-=locX*locY.dot(locX); locY.normalize();
Vector3r locZ=normal.cross(locY);
#ifdef L3_TRSF_QUATERNION
Matrix3r trsf; trsf.row(0)=locX; trsf.row(1)=locY; trsf.row(2)=locZ;
@@ -177,7 +175,7 @@
currTrsf=Matrix3r(Quaternionr(currTrsf).normalized());
#endif
#ifdef YADE_DEBUG
- if(abs(currTrsf.determinant()-1)>.05){
+ if(std::abs(currTrsf.determinant()-1)>.05){
LOG_ERROR("##"<<I->getId1()<<"+"<<I->getId2()<<", |trsf|="<<currTrsf.determinant());
g.trsf=currTrsf;
throw runtime_error("Transformation matrix far from orthonormal.");
@@ -234,7 +232,7 @@
if(scene->isPeriodic) throw std::logic_error("Ig2_Wall_Sphere_L3Geom does not handle periodic boundary conditions.");
const Real& radius=s2->cast<Sphere>().radius; const int& ax(s1->cast<Wall>().axis); const int& sense(s1->cast<Wall>().sense);
Real dist=state2.pos[ax]+shift2[ax]-state1.pos[ax]; // signed "distance" between centers
- if(!I->isReal() && abs(dist)>radius && !force) { return false; }// wall and sphere too far from each other
+ if(!I->isReal() && std::abs(dist)>radius && !force) { return false; }// wall and sphere too far from each other
// contact point is sphere center projected onto the wall
Vector3r contPt=state2.pos+shift2; contPt[ax]=state1.pos[ax];
Vector3r normal=Vector3r::Zero();
@@ -259,7 +257,7 @@
Vector3r cogLine=state1.ori.conjugate()*(state2.pos+shift2-state1.pos); // connect centers of gravity
Vector3r normal=facet.normal; // trial contact normal
Real planeDist=normal.dot(cogLine);
- if(abs(planeDist)>radius && !I->isReal() && !force) return false; // sphere too far
+ if(std::abs(planeDist)>radius && !I->isReal() && !force) return false; // sphere too far
if(planeDist<0){normal*=-1; planeDist*=-1; }
Vector3r planarPt=cogLine-planeDist*normal; // project sphere center to the facet plane
Vector3r contactPt; // facet's point closes to the sphere
=== modified file 'pkg/dem/Law2_ScGeom6D_InelastCohFrictPhys_CohesionMoment.cpp'
--- pkg/dem/Law2_ScGeom6D_InelastCohFrictPhys_CohesionMoment.cpp 2013-06-25 08:02:13 +0000
+++ pkg/dem/Law2_ScGeom6D_InelastCohFrictPhys_CohesionMoment.cpp 2014-07-03 07:16:58 +0000
@@ -144,14 +144,14 @@
Real twistM=twist*phys->ktw; //elastic twist moment.
bool sgnChanged=0; //whether the twist moment just passed the equilibrium state.
if(!contact->isFresh(scene) && phys->moment_twist.dot(twistM*geom->normal)<0)sgnChanged=1;
- if(abs(twist)>phys->maxTwist){
+ if(std::abs(twist)>phys->maxTwist){
phys->cohesionBroken=1;
twistM=0;
}
else{
- if(abs(twistM)>phys->maxElTw || phys->onPlastTw){ //plastic deformation.
+ if(std::abs(twistM)>phys->maxElTw || phys->onPlastTw){ //plastic deformation.
phys->onPlastTw=1;
- if(abs(phys->maxCrpRchdTw[0])>abs(twist)){ //unloading/reloading
+ if(std::abs(phys->maxCrpRchdTw[0])>std::abs(twist)){ //unloading/reloading
twistM = phys->kTwUnld*(twist-phys->maxCrpRchdTw[0])+phys->maxCrpRchdTw[1];
}
else{//creep loading.
=== modified file 'pkg/dem/Law2_ScGeom_CapillaryPhys_Capillarity.cpp'
--- pkg/dem/Law2_ScGeom_CapillaryPhys_Capillarity.cpp 2014-03-21 18:45:24 +0000
+++ pkg/dem/Law2_ScGeom_CapillaryPhys_Capillarity.cpp 2014-07-03 17:20:40 +0000
@@ -21,14 +21,8 @@
#include <yade/core/Scene.hpp>
#include <yade/lib/base/Math.hpp>
-
-#include <iostream>
-#include <fstream>
-
YADE_PLUGIN((Law2_ScGeom_CapillaryPhys_Capillarity));
-using namespace std;
-
void Law2_ScGeom_CapillaryPhys_Capillarity::postLoad(Law2_ScGeom_CapillaryPhys_Capillarity&){
capillary = shared_ptr<capillarylaw>(new capillarylaw);
=== modified file 'pkg/dem/Law2_ScGeom_CapillaryPhys_Capillarity.hpp'
--- pkg/dem/Law2_ScGeom_CapillaryPhys_Capillarity.hpp 2014-04-16 09:32:47 +0000
+++ pkg/dem/Law2_ScGeom_CapillaryPhys_Capillarity.hpp 2014-07-03 17:20:40 +0000
@@ -11,14 +11,8 @@
#pragma once
#include <yade/core/GlobalEngine.hpp>
-#include <set>
#include <boost/tuple/tuple.hpp>
-#include <vector>
-#include <list>
#include <utility>
-#include <iostream>
-#include <fstream>
-#include <string>
/**
This law allows one to take into account capillary forces/effects between spheres coming from the presence of interparticular liquid bridges (menisci).
=== modified file 'pkg/dem/NewtonIntegrator.cpp'
--- pkg/dem/NewtonIntegrator.cpp 2014-06-05 13:19:44 +0000
+++ pkg/dem/NewtonIntegrator.cpp 2014-07-03 07:16:58 +0000
@@ -72,7 +72,7 @@
void NewtonIntegrator::saveMaximaDisplacement(const shared_ptr<Body>& b){
if (!b->bound) return;//clumps for instance, have no bounds, hence not saved
Vector3r disp=b->state->pos-b->bound->refPos;
- Real maxDisp=max(abs(disp[0]),max(abs(disp[1]),abs(disp[2])));
+ Real maxDisp=max(std::abs(disp[0]),max(std::abs(disp[1]),std::abs(disp[2])));
if (!maxDisp || maxDisp<b->bound->sweepLength) {/*b->bound->isBounding = (updatingDispFactor>0 && (updatingDispFactor*maxDisp)<b->bound->sweepLength);*/
maxDisp=0.5;//not 0, else it will be seen as "not updated" by the collider, but less than 1 means no colliding
}
=== modified file 'pkg/dem/NormalInelasticityLaw.cpp'
--- pkg/dem/NormalInelasticityLaw.cpp 2014-02-03 11:21:42 +0000
+++ pkg/dem/NormalInelasticityLaw.cpp 2014-07-03 07:16:58 +0000
@@ -136,7 +136,7 @@
// Limitation by plastic threshold of this part of the moment caused by relative twist and bending
if (!momentAlwaysElastic)
{
- Real normeMomentMax = currentContactPhysics->forMaxMoment * std::fabs(Fn);
+ Real normeMomentMax = currentContactPhysics->forMaxMoment * std::abs(Fn);
if(moment.norm()>normeMomentMax)
{
moment *= normeMomentMax/moment.norm();
=== modified file 'pkg/dem/PeriIsoCompressor.cpp'
--- pkg/dem/PeriIsoCompressor.cpp 2014-05-22 15:26:55 +0000
+++ pkg/dem/PeriIsoCompressor.cpp 2014-07-03 07:16:58 +0000
@@ -8,8 +8,6 @@
#include<yade/pkg/dem/DemXDofGeom.hpp>
#include<yade/lib/pyutil/gil.hpp>
-using namespace std;
-
YADE_PLUGIN((PeriIsoCompressor)(PeriTriaxController)(Peri3dController))
CREATE_LOGGER(PeriIsoCompressor);
@@ -50,12 +48,12 @@
Real sigAvg=(sigma[0]+sigma[1]+sigma[2])/3., avgArea=(cellArea[0]+cellArea[1]+cellArea[2])/3., avgSize=(cellSize[0]+cellSize[1]+cellSize[2])/3.;
Real avgGrow=1e-4*(sigmaGoal-sigAvg)*avgArea/(avgStiffness>0?avgStiffness:1);
Real maxToAvg=maxSize/avgSize;
- if(abs(maxToAvg*avgGrow)>maxDisplPerStep) avgGrow=Mathr::Sign(avgGrow)*maxDisplPerStep/maxToAvg;
+ if(std::abs(maxToAvg*avgGrow)>maxDisplPerStep) avgGrow=Mathr::Sign(avgGrow)*maxDisplPerStep/maxToAvg;
Real okGrow=-(minSize-2.1*maxSpan)/maxToAvg;
if(avgGrow<okGrow) throw runtime_error("Unable to shring cell due to maximum body size (although required by stress condition). Increase particle rigidity, increase total sample dimensions, or decrease goal stress.");
// avgGrow=max(avgGrow,-(minSize-2.1*maxSpan)/maxToAvg);
if(avgStiffness>0) { sigma+=(avgGrow*avgStiffness)*Vector3r::Ones(); sigAvg+=avgGrow*avgStiffness; }
- if(abs((sigAvg-sigmaGoal)/sigmaGoal)>5e-3) allStressesOK=false;
+ if(std::abs((sigAvg-sigmaGoal)/sigmaGoal)>5e-3) allStressesOK=false;
cellGrow=(avgGrow/avgSize)*cellSize;
}
else{ // handle each dimension separately
@@ -65,11 +63,11 @@
// FIXME: that is why the fixup 1e-4 is needed here
// FIXME: or perhaps maxDisplaPerStep=1e-2*charLen is too big??
cellGrow[axis]=1e-4*(sigmaGoal-sigma[axis])*cellArea[axis]/(avgStiffness>0?avgStiffness:1); // FIXME: wrong dimensions? See PeriTriaxController
- if(abs(cellGrow[axis])>maxDisplPerStep) cellGrow[axis]=Mathr::Sign(cellGrow[axis])*maxDisplPerStep;
+ if(std::abs(cellGrow[axis])>maxDisplPerStep) cellGrow[axis]=Mathr::Sign(cellGrow[axis])*maxDisplPerStep;
cellGrow[axis]=max(cellGrow[axis],-(cellSize[axis]-2.1*maxSpan));
// crude way of predicting sigma, for steps when it is not computed from intrs
if(avgStiffness>0) sigma[axis]+=cellGrow[axis]*avgStiffness; // FIXME: dimensions
- if(abs((sigma[axis]-sigmaGoal)/sigmaGoal)>5e-3) allStressesOK=false;
+ if(std::abs((sigma[axis]-sigmaGoal)/sigmaGoal)>5e-3) allStressesOK=false;
}
}
TRVAR4(cellGrow,sigma,sigmaGoal,avgStiffness);
@@ -115,7 +113,7 @@
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 ){
- for ( int i=0; i<3; i++ ) sumStiff[i]+=abs ( gsc->normal[i] ) *nsi->kn+ ( 1-abs ( gsc->normal[i] ) ) *nsi->ks;
+ for ( int i=0; i<3; i++ ) sumStiff[i]+=std::abs ( gsc->normal[i] ) *nsi->kn+ ( 1-std::abs ( gsc->normal[i] ) ) *nsi->ks;
n++;}
}
// Divide by volume as in stressTensor=sum(fi*lj)/Volume (Love equation)
@@ -184,7 +182,7 @@
// steady evolution with fluctuations; see TriaxialStressController
if (!dynCell) strain_rate=(1-growDamping)*strain_rate+.8*prevGrow[axis];
// limit maximum strain rate
- if (abs(strain_rate)>maxStrainRate[axis]) strain_rate = Mathr::Sign(strain_rate)*maxStrainRate[axis];
+ if (std::abs(strain_rate)>maxStrainRate[axis]) strain_rate = Mathr::Sign(strain_rate)*maxStrainRate[axis];
// do not shrink below minimum cell size (periodic collider condition), although it is suboptimal WRT resulting stress
strain_rate=max(strain_rate,-(cellSize[axis]-2.1*maxBodySpan[axis])/scene->dt);
@@ -195,13 +193,13 @@
// signal if condition not satisfied
if(stressMask&(1<<axis)){
Real curr=stress[axis];
- if((goal[axis]!=0 && abs((curr-goal[axis])/goal[axis])>relStressTol) || abs(curr-goal[axis])>absStressTol) allOk=false;
+ if((goal[axis]!=0 && std::abs((curr-goal[axis])/goal[axis])>relStressTol) || std::abs(curr-goal[axis])>absStressTol) allOk=false;
}else{
Real curr=strain[axis];
// since strain is prescribed exactly, tolerances need just to accomodate rounding issues
- if((goal[axis]!=0 && abs((curr-goal[axis])/goal[axis])>1e-6) || abs(curr-goal[axis])>1e-6){
+ if((goal[axis]!=0 && std::abs((curr-goal[axis])/goal[axis])>1e-6) || std::abs(curr-goal[axis])>1e-6){
allOk=false;
- if(doUpdate) LOG_DEBUG("Strain not OK; "<<abs(curr-goal[axis])<<">1e-6");}
+ if(doUpdate) LOG_DEBUG("Strain not OK; "<<std::abs(curr-goal[axis])<<">1e-6");}
}
}
// update stress and strain
@@ -286,7 +284,7 @@
// convert relative progress values of ##Path to absolute values
PATH_OP_OP(i,j,0) *= 1./PATH_OP_OP(i,pathSizes[i]-1,0);
// convert relative stress/strain values of ##Path to absolute stress strain values
- if (abs(PATH_OP_OP(i,pathSizes[i]-1,1)) >= 1e-9) { // the final value is not 0 (otherwise always absolute values are considered)
+ if (std::abs(PATH_OP_OP(i,pathSizes[i]-1,1)) >= 1e-9) { // the final value is not 0 (otherwise always absolute values are considered)
PATH_OP_OP(i,j,1) *= goal(i)/PATH_OP_OP(i,pathSizes[i]-1,1);
}
}
@@ -387,7 +385,7 @@
}
}
- // correction coefficient ix strainRate.maxabs() > maxStrainRate
+ // correction coefficient ix strainRate.maxstd::abs() > maxStrainRate
Real srCorr = (strainRate.cwiseAbs().maxCoeff() > maxStrainRate)? (maxStrainRate/strainRate.cwiseAbs().maxCoeff()):1.;
strainRate *= srCorr;
=== modified file 'pkg/dem/Polyhedra.cpp'
--- pkg/dem/Polyhedra.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/Polyhedra.cpp 2014-07-03 07:16:58 +0000
@@ -113,7 +113,7 @@
inertia_tensor = inertia_tensor + Itet1 + Itet2*vtet;
}
- if(abs(inertia_tensor(0,1))+abs(inertia_tensor(0,2))+abs(inertia_tensor(1,2)) < 1E-13){
+ if(std::abs(inertia_tensor(0,1))+std::abs(inertia_tensor(0,2))+std::abs(inertia_tensor(1,2)) < 1E-13){
// no need to rotate, inertia already diagonal
orientation = Quaternionr::Identity();
inertia = Vector3r(inertia_tensor(0,0),inertia_tensor(1,1),inertia_tensor(2,2));
@@ -127,14 +127,14 @@
// set positove direction of vectors - otherwise reloading does not work
Matrix3r sign(Matrix3r::Zero());
double max_v_signed = I_rot(0,0);
- double max_v = abs(I_rot(0,0));
- if (max_v < abs(I_rot(1,0))) {max_v_signed = I_rot(1,0); max_v = abs(I_rot(1,0));}
- if (max_v < abs(I_rot(2,0))) {max_v_signed = I_rot(2,0); max_v = abs(I_rot(2,0));}
+ double max_v = std::abs(I_rot(0,0));
+ if (max_v < std::abs(I_rot(1,0))) {max_v_signed = I_rot(1,0); max_v = std::abs(I_rot(1,0));}
+ if (max_v < std::abs(I_rot(2,0))) {max_v_signed = I_rot(2,0); max_v = std::abs(I_rot(2,0));}
sign(0,0) = max_v_signed/max_v;
max_v_signed = I_rot(0,1);
- max_v = abs(I_rot(0,1));
- if (max_v < abs(I_rot(1,1))) {max_v_signed = I_rot(1,1); max_v = abs(I_rot(1,1));}
- if (max_v < abs(I_rot(2,1))) {max_v_signed = I_rot(2,1); max_v = abs(I_rot(2,1));}
+ max_v = std::abs(I_rot(0,1));
+ if (max_v < std::abs(I_rot(1,1))) {max_v_signed = I_rot(1,1); max_v = std::abs(I_rot(1,1));}
+ if (max_v < std::abs(I_rot(2,1))) {max_v_signed = I_rot(2,1); max_v = std::abs(I_rot(2,1));}
sign(1,1) = max_v_signed/max_v;
sign(2,2) = 1.;
I_rot = I_rot*sign;
@@ -307,7 +307,7 @@
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);
+ fnNorm=std::abs(fnNorm);
Real radiusScale=1.;
maxFn=max(fnNorm,maxFn);
Real realMaxRadius;
@@ -416,7 +416,7 @@
void PolyhedraVolumetricLaw::go(shared_ptr<IGeom>& ig, shared_ptr<IPhys>& ip, Interaction* I){
if (!I->geom) {return;}
- const shared_ptr<PolyhedraGeom>& contactGeom(boost::dynamic_pointer_cast<PolyhedraGeom>(I->geom));
+ const shared_ptr<PolyhedraGeom>& contactGeom(YADE_PTR_DYN_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);
=== modified file 'pkg/dem/Polyhedra.hpp'
--- pkg/dem/Polyhedra.hpp 2014-05-16 11:58:59 +0000
+++ pkg/dem/Polyhedra.hpp 2014-07-03 17:20:40 +0000
@@ -6,7 +6,6 @@
#ifdef YADE_CGAL
-#include<vector>
#include<yade/core/Shape.hpp>
#include<yade/core/IGeom.hpp>
#include<yade/core/GlobalEngine.hpp>
=== modified file 'pkg/dem/Polyhedra_splitter.cpp'
--- pkg/dem/Polyhedra_splitter.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/Polyhedra_splitter.cpp 2014-07-01 18:14:18 +0000
@@ -83,8 +83,8 @@
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
if(!b || !b->material || !b->shape) continue;
- shared_ptr<Polyhedra> p=boost::dynamic_pointer_cast<Polyhedra>(b->shape);
- shared_ptr<PolyhedraMat> m=boost::dynamic_pointer_cast<PolyhedraMat>(b->material);
+ shared_ptr<Polyhedra> p=YADE_PTR_DYN_CAST<Polyhedra>(b->shape);
+ shared_ptr<PolyhedraMat> m=YADE_PTR_DYN_CAST<PolyhedraMat>(b->material);
if(p && m->IsSplitable){
//not real strees, to get real one, it has to be divided by body volume
=== modified file 'pkg/dem/Polyhedra_support.cpp'
--- pkg/dem/Polyhedra_support.cpp 2014-05-16 11:58:59 +0000
+++ pkg/dem/Polyhedra_support.cpp 2014-07-03 07:16:58 +0000
@@ -79,7 +79,7 @@
// Jacobian of transformation to the reference 4hedron
double detJ=(x2-x1)*(y3-y1)*(z4-z1)+(x3-x1)*(y4-y1)*(z2-z1)+(x4-x1)*(y2-y1)*(z3-z1)
-(x2-x1)*(y4-y1)*(z3-z1)-(x3-x1)*(y2-y1)*(z4-z1)-(x4-x1)*(y3-y1)*(z2-z1);
- detJ=fabs(detJ);
+ detJ=std::abs(detJ);
double a=detJ*(y1*y1+y1*y2+y2*y2+y1*y3+y2*y3+
y3*y3+y1*y4+y2*y4+y3*y4+y4*y4+z1*z1+z1*z2+
z2*z2+z1*z3+z2*z3+z3*z3+z1*z4+z2*z4+z3*z4+z4*z4)/60.;
@@ -470,7 +470,7 @@
if(norm2 < 1E-20) continue;
abs_size = 0.5*sqrt((cross_product(CGALvector(hfc0->vertex()->point(),hfc0->next()->vertex()->point()),CGALvector(hfc0->vertex()->point(),hfc0->next()->next()->vertex()->point()))).squared_length());
// factor 0.5 because this procedure returnes doubles projected area
- if (abs_size>0) area += 0.5*abs_size*abs(CGALnormal*normal2/sqrt(norm2));
+ if (abs_size>0) area += 0.5*abs_size*std::abs(CGALnormal*normal2/sqrt(norm2));
}
return area;
}
@@ -625,8 +625,8 @@
for (Polyhedron::Facet_iterator fIter = B.facets_begin(); fIter != B.facets_end() && !intersection_found; fIter++){
dist_S = Oriented_squared_distance(fIter->plane(), eIter->vertex()->point());
dist_T = Oriented_squared_distance(fIter->plane(), eIter->opposite()->vertex()->point());
- if (dist_S*dist_T >= 0 || abs(dist_S)<lim2 || abs(dist_T)<lim2) continue;
- inside = eIter->vertex()->point() + (eIter->opposite()->vertex()->point()-eIter->vertex()->point())*sqrt(abs(dist_S))/(sqrt(abs(dist_S))+sqrt(abs(dist_T)));
+ if (dist_S*dist_T >= 0 || std::abs(dist_S)<lim2 || std::abs(dist_T)<lim2) continue;
+ inside = eIter->vertex()->point() + (eIter->opposite()->vertex()->point()-eIter->vertex()->point())*sqrt(std::abs(dist_S))/(sqrt(std::abs(dist_S))+sqrt(std::abs(dist_T)));
// the fact that edge intersects the facet (not only its plane) is not explicitely checked, it sufices to check that the resulting point is inside both polyhedras
Plane p1 = fIter->plane();
Plane p2 = eIter->facet()->plane();
=== modified file 'pkg/dem/SampleCapillaryPressureEngine.cpp'
--- pkg/dem/SampleCapillaryPressureEngine.cpp 2014-05-23 13:03:50 +0000
+++ pkg/dem/SampleCapillaryPressureEngine.cpp 2014-07-03 17:20:40 +0000
@@ -14,9 +14,6 @@
#include<yade/core/Omega.hpp>
#include<yade/pkg/dem/FrictPhys.hpp>
#include<yade/lib/base/Math.hpp>
-#include <boost/lexical_cast.hpp>
-
-using namespace std;
YADE_PLUGIN((SampleCapillaryPressureEngine));
CREATE_LOGGER(SampleCapillaryPressureEngine);
=== modified file 'pkg/dem/Shop.hpp'
--- pkg/dem/Shop.hpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/Shop.hpp 2014-07-03 17:20:40 +0000
@@ -2,11 +2,6 @@
#pragma once
-#include<string>
-#include<map>
-#include<iostream>
-#include<typeinfo>
-#include<boost/any.hpp>
#include<boost/lambda/lambda.hpp>
#include "yade/lib/base/Math.hpp"
@@ -23,7 +18,6 @@
class FrictMat;
class Interaction;
-using namespace std;
using boost::shared_ptr;
namespace py = boost::python;
=== modified file 'pkg/dem/Shop_01.cpp'
--- pkg/dem/Shop_01.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/Shop_01.cpp 2014-07-03 17:20:40 +0000
@@ -46,11 +46,6 @@
#include"yade/pkg/common/Gl1_NormPhys.hpp"
#endif
-#include<boost/foreach.hpp>
-#ifndef FOREACH
- #define FOREACH BOOST_FOREACH
-#endif
-
CREATE_LOGGER(Shop);
/*! Flip periodic cell by given number of cells.
@@ -146,7 +141,7 @@
FOREACH(const shared_ptr<Interaction>&I, *rb->interactions){
if(!I->isReal()) continue;
NormShearPhys* nsi=YADE_CAST<NormShearPhys*>(I->phys.get());
- force+=Vector3r(abs(nsi->normalForce[0]+nsi->shearForce[0]),abs(nsi->normalForce[1]+nsi->shearForce[1]),abs(nsi->normalForce[2]+nsi->shearForce[2]));
+ force+=Vector3r(std::abs(nsi->normalForce[0]+nsi->shearForce[0]),std::abs(nsi->normalForce[1]+nsi->shearForce[1]),std::abs(nsi->normalForce[2]+nsi->shearForce[2]));
stiff+=(1/3.)*nsi->kn+(2/3.)*nsi->ks; // count kn in one direction and ks in the other two
n++;
}
@@ -159,7 +154,7 @@
rb->forces.sync();
shared_ptr<NewtonIntegrator> newton;
Vector3r gravity = Vector3r::Zero();
- FOREACH(shared_ptr<Engine>& e, rb->engines){ newton=boost::dynamic_pointer_cast<NewtonIntegrator>(e); if(newton) {gravity=newton->gravity; break;} }
+ FOREACH(shared_ptr<Engine>& e, rb->engines){ newton=YADE_PTR_DYN_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){
@@ -293,7 +288,7 @@
FOREACH(shared_ptr<Body> b, *scene->bodies){
if (!b->isDynamic()) continue;
- shared_ptr<Sphere> intSph=boost::dynamic_pointer_cast<Sphere>(b->shape);
+ shared_ptr<Sphere> intSph=YADE_PTR_DYN_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;
@@ -441,8 +436,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=boost::dynamic_pointer_cast<ElastMat>(b->material);
- shared_ptr<Sphere> s=boost::dynamic_pointer_cast<Sphere>(b->shape);
+ shared_ptr<ElastMat> ebp=YADE_PTR_DYN_CAST<ElastMat>(b->material);
+ shared_ptr<Sphere> s=YADE_PTR_DYN_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-05-23 13:05:19 +0000
+++ pkg/dem/Shop_02.cpp 2014-07-03 17:20:40 +0000
@@ -48,11 +48,6 @@
#include<yade/pkg/common/Gl1_NormPhys.hpp>
#endif
-#include<boost/foreach.hpp>
-#ifndef FOREACH
- #define FOREACH BOOST_FOREACH
-#endif
-
CREATE_LOGGER(Shop);
/*! Flip periodic cell by given number of cells.
@@ -67,8 +62,8 @@
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
if(!b || !b->material || !b->shape) continue;
- shared_ptr<ElastMat> ebp=boost::dynamic_pointer_cast<ElastMat>(b->material);
- shared_ptr<Sphere> s=boost::dynamic_pointer_cast<Sphere>(b->shape);
+ shared_ptr<ElastMat> ebp=YADE_PTR_DYN_CAST<ElastMat>(b->material);
+ shared_ptr<Sphere> s=YADE_PTR_DYN_CAST<Sphere>(b->shape);
if(!ebp || !s) continue;
Real density=b->state->mass/((4/3.)*Mathr::PI*pow(s->radius,3));
=== modified file 'pkg/dem/SimpleShear.cpp'
--- pkg/dem/SimpleShear.cpp 2014-06-17 10:18:00 +0000
+++ pkg/dem/SimpleShear.cpp 2014-07-02 16:18:24 +0000
@@ -41,8 +41,6 @@
#include <boost/filesystem/convenience.hpp>
#include <utility>
-using namespace std;
-
YADE_PLUGIN((SimpleShear))
CREATE_LOGGER(SimpleShear);
=== modified file 'pkg/dem/SimpleShear.hpp'
--- pkg/dem/SimpleShear.hpp 2012-11-22 14:32:53 +0000
+++ pkg/dem/SimpleShear.hpp 2014-07-02 16:18:24 +0000
@@ -14,9 +14,6 @@
typedef pair<Vector3r, Real> BasicSphere;
//! make a list of spheres non-overlapping sphere
-using namespace std;
-
-
class SimpleShear : public FileGenerator
{
void createBox(shared_ptr<Body>& body, Vector3r position, Vector3r extents);
=== modified file 'pkg/dem/SpherePack.cpp'
--- pkg/dem/SpherePack.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/SpherePack.cpp 2014-07-03 07:16:58 +0000
@@ -17,8 +17,6 @@
CREATE_LOGGER(SpherePack);
-using namespace std;
-
namespace py=boost::python;
@@ -75,7 +73,7 @@
Scene* scene=Omega::instance().getScene().get();
FOREACH(const shared_ptr<Body>& b, *scene->bodies){
if(!b) continue;
- shared_ptr<Sphere> intSph=boost::dynamic_pointer_cast<Sphere>(b->shape);
+ shared_ptr<Sphere> intSph=YADE_PTR_DYN_CAST<Sphere>(b->shape);
if(!intSph) continue;
pack.push_back(Sph(b->state->pos,intSph->radius,(b->isClumpMember()?b->clumpId:-1)));
}
@@ -98,7 +96,7 @@
if (hSizeFound && !periodic) LOG_WARN("hSize can be defined only for periodic cells.");
Real volume=hSize.determinant();
Matrix3r invHsize =hSize.inverse();
- Real area=abs(size[0]*size[2]+size[0]*size[1]+size[1]*size[2]);//2 terms will be null if one coordinate is 0, the other is the area
+ Real area=std::abs(size[0]*size[2]+size[0]*size[1]+size[1]*size[2]);//2 terms will be null if one coordinate is 0, the other is the area
if (!volume) {
if (hSizeFound) throw invalid_argument("The period defined by hSize has null length in at least one direction, this is not supported. Define flat boxes via min-max and keep hSize undefined if you want a 2D packing.");
else LOG_WARN("The volume of the min-max box is null, we will assume that the packing is 2D. If it is not what you want then you defined wrong input values; check that min and max corners are defined correctly.");}
@@ -193,7 +191,7 @@
} else {//not aligned, find closest neighbor in a cube of size 1, then transform distance to cartesian coordinates
Vector3r c1c2=invHsize*(pack[j].c-c);
for(int axis=0; axis<3; axis++){
- if (abs(c1c2[axis])<abs(c1c2[axis] - Mathr::Sign(c1c2[axis]))) dr[axis]=c1c2[axis];
+ if (std::abs(c1c2[axis])<std::abs(c1c2[axis] - Mathr::Sign(c1c2[axis]))) dr[axis]=c1c2[axis];
else dr[axis] = c1c2[axis] - Mathr::Sign(c1c2[axis]);}
dr=hSize*dr;//now in cartesian coordinates
}
=== modified file 'pkg/dem/SpherePack.hpp'
--- pkg/dem/SpherePack.hpp 2014-05-23 13:03:50 +0000
+++ pkg/dem/SpherePack.hpp 2014-07-03 17:20:40 +0000
@@ -2,28 +2,6 @@
#pragma once
-#include<vector>
-#include<string>
-#include<limits>
-#include<iostream>
-using namespace std; // sorry
-
-#include<boost/python.hpp>
-#include<boost/python/object.hpp>
-#include<boost/version.hpp>
-
-#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>
=== modified file 'pkg/dem/SpheresFactory.cpp'
--- pkg/dem/SpheresFactory.cpp 2014-06-17 10:18:00 +0000
+++ pkg/dem/SpheresFactory.cpp 2014-07-01 18:14:18 +0000
@@ -24,7 +24,7 @@
void SpheresFactory::action(){
if(!collider){
- FOREACH(const shared_ptr<Engine>& e, scene->engines){ collider=boost::dynamic_pointer_cast<Collider>(e); if(collider) break; }
+ FOREACH(const shared_ptr<Engine>& e, scene->engines){ collider=YADE_PTR_DYN_CAST<Collider>(e); if(collider) break; }
if(!collider) throw runtime_error("SpheresFactory: No Collider instance found in engines (needed for collision detection).");
}
=== modified file 'pkg/dem/TesselationWrapper.cpp'
--- pkg/dem/TesselationWrapper.cpp 2014-06-17 10:18:00 +0000
+++ pkg/dem/TesselationWrapper.cpp 2014-07-03 17:20:40 +0000
@@ -8,14 +8,11 @@
#ifdef YADE_CGAL
-#include<yade/lib/pyutil/numpy.hpp>
-#include<boost/python.hpp>
-#include<boost/python/object.hpp>
-#include<boost/version.hpp>
#include<yade/pkg/dem/Shop.hpp>
#include"TesselationWrapper.hpp"
#include<yade/lib/triangulation/Timer.h>
#include<yade/pkg/dem/SpherePack.hpp>
+#include<yade/lib/pyutil/numpy.hpp>
YADE_PLUGIN((TesselationWrapper));
CREATE_LOGGER(TesselationWrapper);
@@ -163,7 +160,6 @@
bool TesselationWrapper::insert(double x, double y, double z, double rad, unsigned int id)
{
- using namespace std;
checkMinMax(x,y,z,rad);
mean_radius += rad;
++n_spheres;
@@ -172,7 +168,8 @@
void TesselationWrapper::checkMinMax(double x, double y, double z, double rad)
{
- using namespace std;
+ using std::min;
+ using std::max;
Pmin = CGT::Point(min(Pmin.x(), x-rad), min(Pmin.y(), y-rad), min(Pmin.z(), z-rad));
Pmax = CGT::Point(max(Pmax.x(), x+rad), max(Pmax.y(), y+rad), max(Pmax.z(), z+rad));
}
@@ -180,12 +177,11 @@
bool TesselationWrapper::move(double x, double y, double z, double rad, unsigned int id)
{
- using namespace std;
checkMinMax(x,y,z,rad);
if (Tes->move(x,y,z,rad,id)!=NULL)
return true;
else {
- cerr << "Tes->move(x,y,z,rad,id)==NULL" << endl; return false;
+ std::cerr << "Tes->move(x,y,z,rad,id)==NULL" << std::endl; return false;
}
}
=== modified file 'pkg/dem/TesselationWrapper.hpp'
--- pkg/dem/TesselationWrapper.hpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/TesselationWrapper.hpp 2014-07-03 17:20:40 +0000
@@ -9,12 +9,8 @@
#include<yade/core/GlobalEngine.hpp>
#include<yade/pkg/common/Sphere.hpp>
#include<yade/core/Omega.hpp>
-#include <utility>
#include<yade/core/Scene.hpp>
#include<yade/lib/triangulation/Tesselation.h>
-#include<boost/python.hpp>
-#include<boost/python/object.hpp>
-#include<boost/version.hpp>
#include<yade/pkg/dem/MicroMacroAnalyser.hpp>
/*! \class TesselationWrapper
=== modified file 'pkg/dem/Tetra.cpp'
--- pkg/dem/Tetra.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/Tetra.cpp 2014-07-03 07:16:58 +0000
@@ -659,7 +659,7 @@
#define v1 iABinfo[i].V[1]
#define v2 iABinfo[i].V[2]
#define v3 iABinfo[i].V[3]
- Real dV=fabs(Vector3r(v1-v0).Dot((v2-v0).Cross(v3-v0)))/6.;
+ Real dV=std::abs(Vector3r(v1-v0).Dot((v2-v0).Cross(v3-v0)))/6.;
V+=dV;
Sg+=dV*(v0+v1+v2+v3)*.25;
vector<Vector3r> t; t.push_back(v0); t.push_back(v1); t.push_back(v2); t.push_back(v3);
@@ -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(boost::dynamic_pointer_cast<TTetraGeom>(I->geom));
+ const shared_ptr<TTetraGeom>& contactGeom(YADE_PTR_DYN_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(boost::dynamic_pointer_cast<ElastMat>(A->material));
- const shared_ptr<ElastMat>& physB(boost::dynamic_pointer_cast<ElastMat>(B->material));
+ const shared_ptr<ElastMat>& physA(YADE_PTR_DYN_CAST<ElastMat>(A->material));
+ const shared_ptr<ElastMat>& physB(YADE_PTR_DYN_CAST<ElastMat>(B->material));
/* Cross-section is volumetrically equivalent to the penetration configuration */
@@ -1073,7 +1073,7 @@
// Jacobian of transformation to the reference 4hedron
double detJ=(x2-x1)*(y3-y1)*(z4-z1)+(x3-x1)*(y4-y1)*(z2-z1)+(x4-x1)*(y2-y1)*(z3-z1)
-(x2-x1)*(y4-y1)*(z3-z1)-(x3-x1)*(y2-y1)*(z4-z1)-(x4-x1)*(y3-y1)*(z2-z1);
- detJ=fabs(detJ);
+ detJ=std::abs(detJ);
double a=detJ*(y1*y1+y1*y2+y2*y2+y1*y3+y2*y3+
y3*y3+y1*y4+y2*y4+y3*y4+y4*y4+z1*z1+z1*z2+
z2*z2+z1*z3+z2*z3+z3*z3+z1*z4+z2*z4+z3*z4+z4*z4)/60.;
@@ -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(boost::dynamic_pointer_cast<Tetra>(tetraBody->shape));
+ const shared_ptr<Tetra>& tMold(YADE_PTR_DYN_CAST<Tetra>(tetraBody->shape));
#define v0 tMold->v[0]
#define v1 tMold->v[1]
@@ -1181,9 +1181,9 @@
Real TetrahedronSignedVolume(const Vector3r v[4]) { return (Vector3r(v[3])-Vector3r(v[0])).dot((Vector3r(v[3])-Vector3r(v[1])).cross(Vector3r(v[3])-Vector3r(v[2])))/6.; }
-Real TetrahedronVolume(const Vector3r v[4]) { return fabs(TetrahedronSignedVolume(v)); }
+Real TetrahedronVolume(const Vector3r v[4]) { return std::abs(TetrahedronSignedVolume(v)); }
Real TetrahedronSignedVolume(const vector<Vector3r>& v) { return Vector3r(v[1]-v[0]).dot(Vector3r(v[2]-v[0]).cross(v[3]-v[0]))/6.; }
-Real TetrahedronVolume(const vector<Vector3r>& v) { return fabs(TetrahedronSignedVolume(v)); }
+Real TetrahedronVolume(const vector<Vector3r>& v) { return std::abs(TetrahedronSignedVolume(v)); }
#ifdef YADE_CGAL
Real TetrahedronVolume(const CGAL::Point_3<CGAL::Cartesian<Real> >* v[4]) {
Vector3r vv[4];
=== modified file 'pkg/dem/Tetra.hpp'
--- pkg/dem/Tetra.hpp 2013-09-11 21:43:09 +0000
+++ pkg/dem/Tetra.hpp 2014-07-03 17:20:40 +0000
@@ -3,8 +3,6 @@
#pragma once
-#include<vector>
-
#include<yade/core/Shape.hpp>
#include<yade/core/IGeom.hpp>
#include<yade/core/GlobalEngine.hpp>
=== modified file 'pkg/dem/ThreeDTriaxialEngine.cpp'
--- pkg/dem/ThreeDTriaxialEngine.cpp 2013-02-26 19:28:47 +0000
+++ pkg/dem/ThreeDTriaxialEngine.cpp 2014-07-03 17:20:40 +0000
@@ -11,7 +11,6 @@
#include<yade/core/Omega.hpp>
#include<yade/lib/base/Math.hpp>
-#include<boost/lexical_cast.hpp>
#include<boost/lambda/lambda.hpp>
#include<yade/pkg/dem/Shop.hpp>
#include<yade/core/Interaction.hpp>
=== modified file 'pkg/dem/ThreeDTriaxialEngine.hpp'
--- pkg/dem/ThreeDTriaxialEngine.hpp 2012-11-22 14:32:53 +0000
+++ pkg/dem/ThreeDTriaxialEngine.hpp 2014-07-03 17:20:40 +0000
@@ -12,9 +12,6 @@
#include<yade/core/PartialEngine.hpp>
#include<yade/lib/base/Math.hpp>
#include<yade/pkg/dem/TriaxialStressController.hpp>
-#include<string>
-
-
/** \brief Class for controlling in stress or in strain with respect to each spatial direction a cubical assembly of particles.
*
=== modified file 'pkg/dem/TriaxialCompressionEngine.cpp'
--- pkg/dem/TriaxialCompressionEngine.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/TriaxialCompressionEngine.cpp 2014-07-03 17:20:40 +0000
@@ -10,7 +10,6 @@
#include<yade/core/Scene.hpp>
#include<yade/core/Omega.hpp>
#include<yade/lib/base/Math.hpp>
-#include<boost/lexical_cast.hpp>
#include<boost/lambda/lambda.hpp>
#include<yade/pkg/dem/Shop.hpp>
#include<yade/core/Interaction.hpp>
@@ -84,7 +83,7 @@
if ( (currentState!=STATE_TRIAX_LOADING && currentState==STATE_ISO_COMPACTION) || currentState==STATE_ISO_UNLOADING || currentState==STATE_FIXED_POROSITY_COMPACTION || autoCompressionActivation)
{
- if (UnbalancedForce<=StabilityCriterion && abs ( ( meanStress-sigma_iso ) /sigma_iso ) <0.005 && fixedPoroCompaction==false )
+ if (UnbalancedForce<=StabilityCriterion && std::abs ( ( meanStress-sigma_iso ) /sigma_iso ) <0.005 && fixedPoroCompaction==false )
{
// only go to UNLOADING if it is needed
if ( currentState==STATE_ISO_COMPACTION && autoUnload && sigmaLateralConfinement!=sigmaIsoCompaction ) {
@@ -123,7 +122,7 @@
{
updateParameters ();
maxStress = max(maxStress,stress[wall_top][1]);
- LOG_INFO("UnbalancedForce="<< UnbalancedForce<<", rel stress "<< abs ( ( meanStress-sigma_iso ) /sigma_iso ));
+ LOG_INFO("UnbalancedForce="<< UnbalancedForce<<", rel stress "<< std::abs ( ( meanStress-sigma_iso ) /sigma_iso ));
}
if ( saveSimulation )
{
@@ -163,7 +162,7 @@
if (scene->iter % 100 == 0) LOG_DEBUG("Compression active.");
const Real& dt = scene->dt;
- if (abs(epsilonMax) > abs(strain[1])) {
+ if (std::abs(epsilonMax) > std::abs(strain[1])) {
if ( currentStrainRate != strainRate ) currentStrainRate += ( strainRate-currentStrainRate ) *0.0003;
/* Move top and bottom wall according to strain rate */
State* p_bottom=Body::byId(wall_bottom_id,scene)->state.get();
=== modified file 'pkg/dem/TriaxialCompressionEngine.hpp'
--- pkg/dem/TriaxialCompressionEngine.hpp 2013-03-06 20:39:22 +0000
+++ pkg/dem/TriaxialCompressionEngine.hpp 2014-07-03 17:20:40 +0000
@@ -11,7 +11,6 @@
#include<yade/core/PartialEngine.hpp>
#include<yade/lib/base/Math.hpp>
#include<yade/pkg/dem/TriaxialStressController.hpp>
-#include<string>
/** \brief Class for controlling optional initial isotropic compaction and subsequent triaxial test with constant lateral stress and constant axial strain rate. The algorithms used have been developed initialy for simulations reported in [Chareyre2002a] and [Chareyre2005]. They have been ported to Yade in a second step and used in e.g. [Kozicki2008],[Scholtes2009b],[Jerier2010b].
*
=== modified file 'pkg/dem/TriaxialStateRecorder.cpp'
--- pkg/dem/TriaxialStateRecorder.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/TriaxialStateRecorder.cpp 2014-07-03 17:20:40 +0000
@@ -14,7 +14,6 @@
#include<yade/pkg/common/Sphere.hpp>
#include <yade/core/Omega.hpp>
#include <yade/core/Scene.hpp>
-#include <boost/lexical_cast.hpp>
#include <yade/pkg/dem/ScGeom.hpp>
#include <yade/pkg/dem/FrictPhys.hpp>
#include <yade/pkg/dem/Shop.hpp>
=== modified file 'pkg/dem/TriaxialTest.cpp'
--- pkg/dem/TriaxialTest.cpp 2014-06-17 10:18:00 +0000
+++ pkg/dem/TriaxialTest.cpp 2014-07-03 17:20:40 +0000
@@ -41,7 +41,6 @@
#include<yade/pkg/common/Wall.hpp>
#include <boost/filesystem/convenience.hpp>
-#include <boost/lexical_cast.hpp>
#include <boost/numeric/conversion/bounds.hpp>
#include <boost/limits.hpp>
// random
@@ -56,8 +55,6 @@
CREATE_LOGGER(TriaxialTest);
YADE_PLUGIN((TriaxialTest));
-using namespace std;
-
TriaxialTest::~TriaxialTest () {}
bool TriaxialTest::generate(string& message)
@@ -110,9 +107,9 @@
Vector3r center = Vector3r((lowerCorner[0]+upperCorner[0])/2,
lowerCorner[1]-thickness/2.0,
(lowerCorner[2]+upperCorner[2])/2);
- Vector3r halfSize = Vector3r(wallOversizeFactor*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ Vector3r halfSize = Vector3r(wallOversizeFactor*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
thickness/2.0,
- wallOversizeFactor*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ wallOversizeFactor*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,true);
scene->bodies->insert(body);
triaxialcompressionEngine->wall_bottom_id = body->getId();
@@ -120,9 +117,9 @@
center = Vector3r((lowerCorner[0]+upperCorner[0])/2,
upperCorner[1]+thickness/2.0,
(lowerCorner[2]+upperCorner[2])/2);
- halfSize = Vector3r(wallOversizeFactor*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ halfSize = Vector3r(wallOversizeFactor*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
thickness/2.0,
- wallOversizeFactor*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ wallOversizeFactor*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,true);
scene->bodies->insert(body);
triaxialcompressionEngine->wall_top_id = body->getId();
@@ -131,8 +128,8 @@
(lowerCorner[1]+upperCorner[1])/2,
(lowerCorner[2]+upperCorner[2])/2);
halfSize = Vector3r(thickness/2.0,
- wallOversizeFactor*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
- wallOversizeFactor*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ wallOversizeFactor*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,true);
scene->bodies->insert(body);
triaxialcompressionEngine->wall_left_id = body->getId();
@@ -141,8 +138,8 @@
(lowerCorner[1]+upperCorner[1])/2,
(lowerCorner[2]+upperCorner[2])/2);
halfSize = Vector3r(thickness/2.0,
- wallOversizeFactor*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
- wallOversizeFactor*fabs(lowerCorner[2]-upperCorner[2])/2+thickness);
+ wallOversizeFactor*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[2]-upperCorner[2])/2+thickness);
createBox(body,center,halfSize,true);
scene->bodies->insert(body);
@@ -151,8 +148,8 @@
center = Vector3r((lowerCorner[0]+upperCorner[0])/2,
(lowerCorner[1]+upperCorner[1])/2,
lowerCorner[2]-thickness/2.0);
- halfSize = Vector3r(wallOversizeFactor*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
- wallOversizeFactor*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ halfSize = Vector3r(wallOversizeFactor*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
thickness/2.0);
createBox(body,center,halfSize,true);
scene->bodies->insert(body);
@@ -161,8 +158,8 @@
center = Vector3r((lowerCorner[0]+upperCorner[0])/2,
(lowerCorner[1]+upperCorner[1])/2,
upperCorner[2]+thickness/2.0);
- halfSize = Vector3r(wallOversizeFactor*fabs(lowerCorner[0]-upperCorner[0])/2+thickness,
- wallOversizeFactor*fabs(lowerCorner[1]-upperCorner[1])/2+thickness,
+ halfSize = Vector3r(wallOversizeFactor*std::abs(lowerCorner[0]-upperCorner[0])/2+thickness,
+ wallOversizeFactor*std::abs(lowerCorner[1]-upperCorner[1])/2+thickness,
thickness/2.0);
createBox(body,center,halfSize,true);
scene->bodies->insert(body);
=== modified file 'pkg/dem/UniaxialStrainer.cpp'
--- pkg/dem/UniaxialStrainer.cpp 2014-05-23 13:05:19 +0000
+++ pkg/dem/UniaxialStrainer.cpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,5 @@
// 2008 © Václav Šmilauer <eudoxos@xxxxxxxx>
#include"UniaxialStrainer.hpp"
-#include<boost/foreach.hpp>
-#include<stdexcept>
#include<yade/core/Scene.hpp>
#include<yade/core/InteractionContainer.hpp>
@@ -89,7 +87,7 @@
//nothing to do
if(posIds.size()==0 || negIds.size()==0) return;
// linearly increase strain to the desired value
- if(abs(currentStrainRate)<abs(strainRate)){
+ if(std::abs(currentStrainRate)<std::abs(strainRate)){
if(initAccelTime_s!=0) currentStrainRate=(scene->time/initAccelTime_s)*strainRate;
else currentStrainRate=strainRate;
} else currentStrainRate=strainRate;
@@ -98,7 +96,7 @@
if(!isnan(stopStrain)){
Real axialLength=axisCoord(posIds[0])-axisCoord(negIds[0]);
Real newStrain=(axialLength+dAX)/originalLength-1;
- if((newStrain*stopStrain>0) && abs(newStrain)>=stopStrain){ // same sign of newStrain and stopStrain && over the limit from below in abs values
+ if((newStrain*stopStrain>0) && std::abs(newStrain)>=stopStrain){ // same sign of newStrain and stopStrain && over the limit from below in abs values
dAX=originalLength*(stopStrain+1)-axialLength;
LOG_INFO("Reached stopStrain "<<stopStrain<<", deactivating self and stopping in "<<idleIterations+1<<" iterations.");
this->active=false;
=== modified file 'pkg/dem/UniaxialStrainer.hpp'
--- pkg/dem/UniaxialStrainer.hpp 2014-04-02 07:44:58 +0000
+++ pkg/dem/UniaxialStrainer.hpp 2014-07-03 17:20:40 +0000
@@ -1,15 +1,9 @@
// 2008 © Václav Šmilauer <eudoxos@xxxxxxxx>
#pragma once
-#include<fstream>
-#include<limits>
#include<yade/core/Scene.hpp>
#include<yade/pkg/dem/Shop.hpp>
#include<yade/pkg/common/BoundaryController.hpp>
-#ifndef FOREACH
-#define FOREACH BOOST_FOREACH
-#endif
-
/*! Axial displacing two groups of bodies in the opposite direction with given strain rate.
*
* Takes two groups of body IDs (in posIds and negIds) and displaces them at each timestep in the direction given by axis∈{0,1,2} (for axes x,y,z respectively). These bodies automatically have Body::isDynamic==false.
=== modified file 'pkg/dem/VTKRecorder.cpp'
--- pkg/dem/VTKRecorder.cpp 2014-06-17 10:18:00 +0000
+++ pkg/dem/VTKRecorder.cpp 2014-07-03 07:16:58 +0000
@@ -378,7 +378,7 @@
const GenericSpheresContact* geom = YADE_CAST<GenericSpheresContact*>(I->geom.get());
// gives _signed_ scalar of normal force, following the convention used in the respective constitutive law
float fn=phys->normalForce.dot(geom->normal);
- float fs[3]={ (float) abs(phys->shearForce[0]), (float) abs(phys->shearForce[1]), (float) abs(phys->shearForce[2])};
+ float fs[3]={ (float) std::abs(phys->shearForce[0]), (float) std::abs(phys->shearForce[1]), (float) std::abs(phys->shearForce[2])};
// add the value once for each interaction object that we created (might be 2 for the periodic boundary)
for(int i=0; i<numAddValues; i++){
intrAbsForceT->InsertNextTupleValue(fs);
=== modified file 'pkg/dem/ViscoelasticCapillarPM.hpp'
--- pkg/dem/ViscoelasticCapillarPM.hpp 2014-06-13 13:58:12 +0000
+++ pkg/dem/ViscoelasticCapillarPM.hpp 2014-06-25 14:46:14 +0000
@@ -1,6 +1,7 @@
-#include"ViscoelasticPM.hpp"
+#pragma once
+#include "ViscoelasticPM.hpp"
#include <boost/unordered_map.hpp>
-#include<yade/core/PartialEngine.hpp>
+#include <yade/core/PartialEngine.hpp>
class ViscElCapMat : public ViscElMat {
public:
=== modified file 'pkg/dem/ViscoelasticPM.cpp'
--- pkg/dem/ViscoelasticPM.cpp 2014-04-14 11:52:51 +0000
+++ pkg/dem/ViscoelasticPM.cpp 2014-07-03 07:16:58 +0000
@@ -10,6 +10,7 @@
#include<yade/pkg/common/SPHEngine.hpp>
#endif
+using std::isfinite;
YADE_PLUGIN((ViscElMat)(ViscElPhys)(Ip2_ViscElMat_ViscElMat_ViscElPhys)(Law2_ScGeom_ViscElPhys_Basic));
/* ViscElMat */
@@ -195,10 +196,10 @@
ks1 = ks2 = 2.0/7.0 /Tc/Tc * ( Mathr::PI*Mathr::PI + pow(log(Et),2) )*massR;
cs1 = cs2 = -2.0/7.0 /Tc * log(Et)*massR;
- if (abs(cn1) <= Mathr::ZERO_TOLERANCE ) cn1=0;
- if (abs(cn2) <= Mathr::ZERO_TOLERANCE ) cn2=0;
- if (abs(cs1) <= Mathr::ZERO_TOLERANCE ) cs1=0;
- if (abs(cs2) <= Mathr::ZERO_TOLERANCE ) cs2=0;
+ if (std::abs(cn1) <= Mathr::ZERO_TOLERANCE ) cn1=0;
+ if (std::abs(cn2) <= Mathr::ZERO_TOLERANCE ) cn2=0;
+ if (std::abs(cs1) <= Mathr::ZERO_TOLERANCE ) cs1=0;
+ if (std::abs(cs2) <= Mathr::ZERO_TOLERANCE ) cs2=0;
} else if ((isfinite(mat1->kn)) and (isfinite(mat1->ks)) and (isfinite(mat1->cn)) and (isfinite(mat1->cs))) {
//Set parameters explicitly
kn1 = mat1->kn;
=== modified file 'pkg/dem/WirePM.cpp'
--- pkg/dem/WirePM.cpp 2013-06-25 04:00:41 +0000
+++ pkg/dem/WirePM.cpp 2014-07-03 07:16:58 +0000
@@ -145,7 +145,7 @@
/* compute a limit value to check how far the interaction is from failing */
Real limitFactor = 0.;
- if (Fn < 0.) limitFactor = fabs(D/(DFValues.back()(0)));
+ if (Fn < 0.) limitFactor = std::abs(D/(DFValues.back()(0)));
phys->limitFactor = limitFactor;
State* st1 = Body::byId(id1,scene)->state.get();
@@ -196,7 +196,7 @@
if ( mat1->id == mat2->id ) { // interaction of two bodies of the same material
crossSection = mat1->as;
SSValues = mat1->strainStressValues;
- if ( (mat1->isDoubleTwist) && (abs(interaction->getId1()-interaction->getId2())==1) ) {// bodies which id differs by 1 are double twisted
+ if ( (mat1->isDoubleTwist) && (std::abs(interaction->getId1()-interaction->getId2())==1) ) {// bodies which id differs by 1 are double twisted
contactPhysics->isDoubleTwist = true;
if ( mat1->type==1 || mat1->type==2 ) {
SSValues = mat1->strainStressValuesDT;
=== modified file 'pkg/lbm/HydrodynamicsLawLBM.cpp'
--- pkg/lbm/HydrodynamicsLawLBM.cpp 2014-03-31 16:01:57 +0000
+++ pkg/lbm/HydrodynamicsLawLBM.cpp 2014-07-03 07:16:58 +0000
@@ -33,7 +33,6 @@
namespace bfs=boost::filesystem;
-using namespace std;
template<class Scalar> VECTOR3_TEMPLATE(Scalar) operator*(Scalar s, const VECTOR3_TEMPLATE(Scalar)& v) {return v*s;}
inline Vector3i vect3rToVect3i(Vector3r vect){Vector3i newvect((int)vect[0],(int)vect[1],(int)vect[2]);return(newvect);}
@@ -831,8 +830,8 @@
// for (int s=NB_WALLS ; s<NB_BODIES; s++) {FmoyCur = FmoyCur + LBbodies[s].force.norm();}
// FmoyCur = FmoyCur/(NB_DYNGRAINS);
// if (FmoyCur!=0.){
-// Real ErrorA = abs(FmoyCur-FmoyPrev)/abs(FmoyCur);
-// Real ErrorB = abs(FmoyCur-FmoyPrevPrev)/abs(FmoyCur);
+// Real ErrorA = std::abs(FmoyCur-FmoyPrev)/std::abs(FmoyCur);
+// Real ErrorB = std::abs(FmoyCur-FmoyPrevPrev)/std::abs(FmoyCur);
// Error=max(ErrorA,ErrorB);
// FmoyPrevPrev=FmoyPrev;
// FmoyPrev=FmoyCur;
@@ -845,8 +844,8 @@
// /*--------------------------------------------------------*/
// if((LBM_ITER > 100) & (LBM_ITER % 10 == 0)){
// if (VmeanFluidC!=0.){
-// Real ErrorA = abs(VmeanFluidC-PrevVmeanFluidC)/abs(VmeanFluidC);
-// //Real ErrorB = abs(VmeanFluidC-PrevPrevVmeanFluidC)/abs(VmeanFluidC);
+// Real ErrorA = std::abs(VmeanFluidC-PrevVmeanFluidC)/std::abs(VmeanFluidC);
+// //Real ErrorB = std::abs(VmeanFluidC-PrevPrevVmeanFluidC)/std::abs(VmeanFluidC);
// //Error=max(ErrorA,ErrorB);
// Error= ErrorA;
// PrevPrevVmeanFluidC=PrevVmeanFluidC;
=== modified file 'pkg/pfv/FlowEngine.ipp.in'
--- pkg/pfv/FlowEngine.ipp.in 2014-06-20 15:28:21 +0000
+++ pkg/pfv/FlowEngine.ipp.in 2014-07-03 07:16:58 +0000
@@ -391,7 +391,7 @@
case ( 3 ) : cell->info().volume() = volumeCellTripleFictious ( cell ); break;
default: break;
}
- if (flow.fluidBulkModulus>0) { cell->info().invVoidVolume() = 1 / ( abs(cell->info().volume()) - flow.volumeSolidPore(cell) ); }
+ if (flow.fluidBulkModulus>0) { cell->info().invVoidVolume() = 1 / ( std::abs(cell->info().volume()) - flow.volumeSolidPore(cell) ); }
}
if (debug) cout << "Volumes initialised." << endl;
}
@@ -486,7 +486,7 @@
}
}
Real Volume = 0.5* ( ( V[0]-V[1] ).cross ( V[0]-V[2] ) ) [solver->boundary ( b ).coordinate] * ( 0.33333333333* ( V[0][solver->boundary ( b ).coordinate]+ V[1][solver->boundary ( b ).coordinate]+ V[2][solver->boundary ( b ).coordinate] ) - Wall_coordinate );
- return abs ( Volume );
+ return std::abs ( Volume );
}
template< class _CellInfo, class _VertexInfo, class _Tesselation, class solverT >
template<class Cellhandle>
@@ -521,7 +521,7 @@
Real Vol1=0.5* ( ( A-BS ).cross ( B-BS ) ) [coord[1]]* ( 0.333333333* ( 2*B[coord[1]]+A[coord[1]] )-Wall_coordinate[1] );
//second pyramid with triangular base (A,AS,BS)
Real Vol2=0.5* ( ( AS-BS ).cross ( A-BS ) ) [coord[1]]* ( 0.333333333* ( B[coord[1]]+2*A[coord[1]] )-Wall_coordinate[1] );
- return abs ( Vol1+Vol2 );
+ return std::abs ( Vol1+Vol2 );
}
template< class _CellInfo, class _VertexInfo, class _Tesselation, class solverT >
template<class Cellhandle>
@@ -549,7 +549,7 @@
}
}
Real Volume = ( A[coord[0]]-Wall_coordinate[0] ) * ( A[coord[1]]-Wall_coordinate[1] ) * ( A[coord[2]]-Wall_coordinate[2] );
- return abs ( Volume );
+ return std::abs ( Volume );
}
template< class _CellInfo, class _VertexInfo, class _Tesselation, class solverT >
template<class Cellhandle>
@@ -620,7 +620,7 @@
bool v1fictious = Tes.vertex ( id1 )->info().isFictious;
int bnd = v1fictious? id1 : id2;
int coord = flow.boundary(bnd).coordinate;
- O1O2 = v1fictious ? abs((sph2->state->pos + makeVector3r(Tes.vertex(id2)->info().ghostShift()))[coord] - flow.boundary(bnd).p[coord]) : abs((sph1->state->pos + makeVector3r(Tes.vertex(id1)->info().ghostShift()))[coord] - flow.boundary(bnd).p[coord]);
+ O1O2 = v1fictious ? std::abs((sph2->state->pos + makeVector3r(Tes.vertex(id2)->info().ghostShift()))[coord] - flow.boundary(bnd).p[coord]) : std::abs((sph1->state->pos + makeVector3r(Tes.vertex(id1)->info().ghostShift()))[coord] - flow.boundary(bnd).p[coord]);
if(v1fictious)
normal = makeVector3r(flow.boundary(id1).normal);
else
@@ -725,8 +725,8 @@
// if ( !cell->info().isReal() ) continue;
if ( cell->info().isGhost ) continue;
for ( int i=0;i<3;i++ )
- meanVel[i]=meanVel[i]+ ( ( cell->info().averageVelocity() ) [i] * abs ( cell->info().volume() ) );
- volume+=abs ( cell->info().volume() );
+ meanVel[i]=meanVel[i]+ ( ( cell->info().averageVelocity() ) [i] * std::abs ( cell->info().volume() ) );
+ volume+=std::abs ( cell->info().volume() );
}
return ( meanVel/volume );
}
=== modified file 'pkg/pfv/PeriodicFlowEngine.cpp'
--- pkg/pfv/PeriodicFlowEngine.cpp 2014-06-20 17:48:57 +0000
+++ pkg/pfv/PeriodicFlowEngine.cpp 2014-07-03 07:16:58 +0000
@@ -317,7 +317,7 @@
}
}
Real Volume = 0.5* ( ( V[0]-V[1] ).cross ( V[0]-V[2] ) ) [solver->boundary ( b ).coordinate] * ( 0.33333333333* ( V[0][solver->boundary ( b ).coordinate]+ V[1][solver->boundary ( b ).coordinate]+ V[2][solver->boundary ( b ).coordinate] ) - Wall_coordinate );
- return abs ( Volume );
+ return std::abs ( Volume );
}
@@ -434,7 +434,7 @@
totVol+=newVol;
dVol=cell->info().volumeSign * ( newVol - cell->info().volume() );
totDVol+=dVol;
- epsVolMax = max ( epsVolMax, abs ( dVol/newVol ) );
+ epsVolMax = max ( epsVolMax, std::abs ( dVol/newVol ) );
cell->info().dv() = dVol * invDeltaT;
cell->info().volume() = newVol;
}
@@ -456,7 +456,7 @@
default: cell->info().volume() = 0; break;
}
//FIXME: the void volume is negative sometimes, hence crashing...
- if (flow.fluidBulkModulus>0) { cell->info().invVoidVolume() = 1. / (max(0.1*cell->info().volume(),abs(cell->info().volume()) - flow.volumeSolidPore(cell)) ); }
+ if (flow.fluidBulkModulus>0) { cell->info().invVoidVolume() = 1. / (max(0.1*cell->info().volume(),std::abs(cell->info().volume()) - flow.volumeSolidPore(cell)) ); }
}
if ( debug ) cout << "Volumes initialised." << endl;
}
=== modified file 'pkg/pfv/SoluteFlowEngine.cpp'
--- pkg/pfv/SoluteFlowEngine.cpp 2014-06-20 20:10:04 +0000
+++ pkg/pfv/SoluteFlowEngine.cpp 2014-07-03 07:16:58 +0000
@@ -101,7 +101,7 @@
// Fill coefficient matrix
FOREACH(CellHandle& cell, solver->T[solver->currentTes].cellHandles){
- cell->info().invVoidVolume() = 1 / ( abs(cell->info().volume()) - abs(solver->volumeSolidPore(cell) ) );
+ cell->info().invVoidVolume() = 1 / ( std::abs(cell->info().volume()) - std::abs(solver->volumeSolidPore(cell) ) );
invdistance=0.0;
@@ -115,15 +115,15 @@
invdistance+=(fluidSurf/sqrt(l.squared_length()));
coeff = deltatime*cell->info().invVoidVolume();
ID = cell->neighbor(ngb)->info().id;
- qin=abs(cell->info().kNorm() [ngb])* ( cell->neighbor ( ngb )->info().p()-cell->info().p());
+ qin=std::abs(cell->info().kNorm() [ngb])* ( cell->neighbor ( ngb )->info().p()-cell->info().p());
Qout=Qout+max(qin,0.0);
- coeff1=-1*coeff*(abs(max(qin,0.0))-(D*invdistancelocal));
+ coeff1=-1*coeff*(std::abs(max(qin,0.0))-(D*invdistancelocal));
if (coeff1 != 0.0){
tripletList2.push_back(ETriplet2(i,ID,coeff1));
}
}
- coeff2=1.0+(coeff*abs(Qout))+(coeff*D*invdistance);
+ coeff2=1.0+(coeff*std::abs(Qout))+(coeff*D*invdistance);
tripletList2.push_back(ETriplet2(i,i,coeff2));
Qout=0.0;
}
@@ -177,10 +177,10 @@
FOREACH(CellHandle& cell, solver->T[solver->currentTes].cellHandles)
{
CGT::Point& p1 = cell->info();
- if (abs(p1[xyz]) < abs(abs(Yobs) + abs(Yr))){
- if(abs(p1[xyz]) > abs(abs(Yobs) - abs(Yr))){
- sumConcentration += cell->info().solute()*(1-(abs(p1[xyz])-abs(Yobs))/abs(Yr));
- sumFraction += (1-(abs(p1[xyz])-abs(Yobs))/abs(Yr));
+ if (std::abs(p1[xyz]) < std::abs(std::abs(Yobs) + std::abs(Yr))){
+ if(std::abs(p1[xyz]) > std::abs(std::abs(Yobs) - std::abs(Yr))){
+ sumConcentration += cell->info().solute()*(1-(std::abs(p1[xyz])-std::abs(Yobs))/std::abs(Yr));
+ sumFraction += (1-(std::abs(p1[xyz])-std::abs(Yobs))/std::abs(Yr));
}
}
}
=== modified file 'py/_polyhedra_utils.cpp'
--- py/_polyhedra_utils.cpp 2014-05-23 13:05:19 +0000
+++ py/_polyhedra_utils.cpp 2014-07-03 17:20:40 +0000
@@ -5,8 +5,6 @@
#include"yade/pkg/dem/Polyhedra.hpp"
-#include<boost/python.hpp>
-#include <boost/python/module.hpp>
#include<yade/core/Scene.hpp>
#include<yade/core/Omega.hpp>
#include<yade/pkg/common/Sphere.hpp>
@@ -16,7 +14,6 @@
#include<numpy/ndarrayobject.h>
-using namespace std;
namespace py = boost::python;
@@ -87,18 +84,18 @@
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=boost::dynamic_pointer_cast<Sphere>(b->shape);
- shared_ptr<Polyhedra> p=boost::dynamic_pointer_cast<Polyhedra>(b->shape);
+ shared_ptr<Sphere> s=YADE_PTR_DYN_CAST<Sphere>(b->shape);
+ shared_ptr<Polyhedra> p=YADE_PTR_DYN_CAST<Polyhedra>(b->shape);
if(!s && !p) continue;
if(!p){
//spheres
- shared_ptr<ElastMat> ebp=boost::dynamic_pointer_cast<ElastMat>(b->material);
+ shared_ptr<ElastMat> ebp=YADE_PTR_DYN_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=boost::dynamic_pointer_cast<PolyhedraMat>(b->material);
+ shared_ptr<PolyhedraMat> ebp=YADE_PTR_DYN_CAST<PolyhedraMat>(b->material);
if(!ebp) continue;
Real density=b->state->mass/p->GetVolume();
//get equivalent radius and use same equation as for sphere
@@ -163,7 +160,7 @@
double total_volume = 0;
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
if(!b || !b->shape) continue;
- shared_ptr<Polyhedra> p=boost::dynamic_pointer_cast<Polyhedra>(b->shape);
+ shared_ptr<Polyhedra> p=YADE_PTR_DYN_CAST<Polyhedra>(b->shape);
if(p){
sieve_volume.push_back(std::pair<double,double>(SieveSize(p),p->GetVolume()));
total_volume += p->GetVolume();
@@ -191,7 +188,7 @@
myfile.open ("sizes.dat");
FOREACH(const shared_ptr<Body>& b, *rb->bodies){
if(!b || !b->shape) continue;
- shared_ptr<Polyhedra> p=boost::dynamic_pointer_cast<Polyhedra>(b->shape);
+ shared_ptr<Polyhedra> p=YADE_PTR_DYN_CAST<Polyhedra>(b->shape);
if(p){
myfile << SizeOfPolyhedra(p) << endl;
}
=== modified file 'py/_utils.cpp'
--- py/_utils.cpp 2014-05-23 13:05:19 +0000
+++ py/_utils.cpp 2014-07-03 17:20:40 +0000
@@ -1,7 +1,4 @@
#include<yade/pkg/dem/Shop.hpp>
-#include<boost/python.hpp>
-#include<boost/python/object.hpp>
-#include<boost/version.hpp>
#include<yade/core/Scene.hpp>
#include<yade/core/Omega.hpp>
#include<yade/pkg/dem/ScGeom.hpp>
@@ -12,12 +9,10 @@
#include<yade/pkg/common/NormShearPhys.hpp>
#include<yade/lib/computational-geometry/Hull2d.hpp>
#include<yade/lib/pyutil/doc_opts.hpp>
-#include<cmath>
#include<yade/pkg/dem/ViscoelasticPM.hpp>
#include<numpy/ndarrayobject.h>
-using namespace std;
namespace py = boost::python;
bool isInBB(Vector3r p, Vector3r bbMin, Vector3r bbMax){return p[0]>bbMin[0] && p[0]<bbMax[0] && p[1]>bbMin[1] && p[1]<bbMax[1] && p[2]>bbMin[2] && p[2]<bbMax[2];}
@@ -28,7 +23,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=boost::dynamic_pointer_cast<Sphere>(b->shape); if(!s) continue;
+ shared_ptr<Sphere> s=YADE_PTR_DYN_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 +37,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=boost::dynamic_pointer_cast<Sphere>(b->shape); if(!s) continue;
+ shared_ptr<Sphere> s=YADE_PTR_DYN_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());
}
@@ -234,7 +229,7 @@
switch(mode){
case none: wire=false; break;
case all: wire=true; break;
- case noSpheres: wire=!(bool)(boost::dynamic_pointer_cast<Sphere>(b->shape)); break;
+ case noSpheres: wire=!(bool)(YADE_PTR_DYN_CAST<Sphere>(b->shape)); break;
default: throw logic_error("No such case possible");
}
b->shape->wire=wire;
=== modified file 'py/export.py'
--- py/export.py 2014-06-06 13:40:28 +0000
+++ py/export.py 2014-06-29 21:25:01 +0000
@@ -572,6 +572,7 @@
elif isinstance(test,Vector3):
outFile.write("\nVECTORS %s double\n"%(name))
for ii,jj in intrs:
+ i = O.interactions[ii,jj]
v = eval(command)
outFile.write("%g %g %g\n"%(v[0],v[1],v[2]))
elif isinstance(test,(int,float)):
=== modified file 'py/mathWrap/miniEigen.cpp'
--- py/mathWrap/miniEigen.cpp 2013-07-09 12:42:00 +0000
+++ py/mathWrap/miniEigen.cpp 2014-07-03 17:24:54 +0000
@@ -1,11 +1,5 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
-#include<boost/python.hpp>
-#include<boost/lexical_cast.hpp>
#include<boost/algorithm/string/trim.hpp>
-#include<string>
-#include<stdexcept>
-#include<sstream>
-#include<iostream>
#include<yade/lib/base/Math.hpp>
#include<yade/lib/pyutil/doc_opts.hpp>
@@ -152,8 +146,8 @@
EIG_WRAP_METH0(Vector2i,Zero); EIG_WRAP_METH0(Vector2i,UnitX); EIG_WRAP_METH0(Vector2i,UnitY); EIG_WRAP_METH0(Vector2i,Ones);
EIG_WRAP_METH0(Quaternionr,Identity);
-#define EIG_OP1(klass,op,sym) typeof((sym klass()).eval()) klass##op(const klass& self){ return (sym self).eval();}
-#define EIG_OP2(klass,op,sym,klass2) typeof((klass() sym klass2()).eval()) klass##op##klass2(const klass& self, const klass2& other){ return (self sym other).eval(); }
+#define EIG_OP1(klass,op,sym) TYPEOF((sym klass()).eval()) klass##op(const klass& self){ return (sym self).eval();}
+#define EIG_OP2(klass,op,sym,klass2) TYPEOF((klass() sym klass2()).eval()) klass##op##klass2(const klass& self, const klass2& other){ return (self sym other).eval(); }
#define EIG_OP2_INPLACE(klass,op,sym,klass2) klass klass##op##klass2(klass& self, const klass2& other){ self sym other; return self; }
=== modified file 'py/pack/_packObb.cpp'
--- py/pack/_packObb.cpp 2014-05-23 13:03:50 +0000
+++ py/pack/_packObb.cpp 2014-07-03 17:20:40 +0000
@@ -2,21 +2,10 @@
// the code written after http://www.amillionpixels.us/bestfitobb.cpp
// which is MIT-licensed
-#include<boost/python.hpp>
-#include<boost/foreach.hpp>
-#include<boost/python/object.hpp>
-#include<boost/version.hpp>
#include<yade/lib/base/Logging.hpp>
#include<yade/lib/base/Math.hpp>
#include<yade/lib/pyutil/doc_opts.hpp>
-#include<vector>
-#include<stdexcept>
-
-#ifndef FOREACH
- #define FOREACH BOOST_FOREACH
-#endif
-
// compute minimum bounding for a cloud of points
// returns volume
=== modified file 'py/pack/_packPredicates.cpp'
--- py/pack/_packPredicates.cpp 2013-03-07 18:28:01 +0000
+++ py/pack/_packPredicates.cpp 2014-07-03 17:20:40 +0000
@@ -1,14 +1,9 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
-#include<boost/python.hpp>
-#include<boost/python/object.hpp>
-#include<boost/version.hpp>
#include<yade/lib/base/Logging.hpp>
#include<yade/lib/base/Math.hpp>
#include<yade/lib/pyutil/doc_opts.hpp>
-#include<iostream>
namespace py=boost::python;
-using namespace std;
/*
This file contains various predicates that say whether a given point is within the solid,
@@ -306,7 +301,7 @@
}
/* Helper function for inGtsSurface::aabb() */
-static void vertex_aabb(GtsVertex *vertex, pair<Vector3r,Vector3r> *bb)
+static void vertex_aabb(GtsVertex *vertex, std::pair<Vector3r,Vector3r> *bb)
{
GtsPoint *_p=GTS_POINT(vertex);
Vector3r p(_p->x,_p->y,_p->z);
@@ -326,16 +321,16 @@
GNode* tree;
public:
inGtsSurface(py::object _surf, bool _noPad=false): pySurf(_surf), noPad(_noPad), noPadWarned(false) {
- if(!pygts_surface_check(_surf.ptr())) throw invalid_argument("Ctor must receive a gts.Surface() instance.");
+ if(!pygts_surface_check(_surf.ptr())) throw std::invalid_argument("Ctor must receive a gts.Surface() instance.");
surf=PYGTS_SURFACE_AS_GTS_SURFACE(PYGTS_SURFACE(_surf.ptr()));
- if(!gts_surface_is_closed(surf)) throw invalid_argument("Surface is not closed.");
+ if(!gts_surface_is_closed(surf)) throw std::invalid_argument("Surface is not closed.");
is_open=gts_surface_volume(surf)<0.;
- if((tree=gts_bb_tree_surface(surf))==NULL) throw runtime_error("Could not create GTree.");
+ if((tree=gts_bb_tree_surface(surf))==NULL) throw std::runtime_error("Could not create GTree.");
}
~inGtsSurface(){g_node_destroy(tree);}
py::tuple aabb() const {
Real inf=std::numeric_limits<Real>::infinity();
- pair<Vector3r,Vector3r> bb; bb.first=Vector3r(inf,inf,inf); bb.second=Vector3r(-inf,-inf,-inf);
+ std::pair<Vector3r,Vector3r> bb; bb.first=Vector3r(inf,inf,inf); bb.second=Vector3r(-inf,-inf,-inf);
gts_surface_foreach_vertex(surf,(GtsFunc)vertex_aabb,&bb);
return vvec2tuple(bb.first,bb.second);
}
=== modified file 'py/utils.py'
--- py/utils.py 2014-02-12 13:18:59 +0000
+++ py/utils.py 2014-07-01 05:36:28 +0000
@@ -348,7 +348,7 @@
b.chain=chain
return b
-def tetraPoly(vertices,strictCheck=True,dynamic=True,fixed=False,wire=True,color=None,highlight=False,noBound=False,material=-1,mask=1,chain=-1):
+def tetraPoly(vertices,dynamic=True,fixed=False,wire=True,color=None,highlight=False,noBound=False,material=-1,mask=1,chain=-1):
"""Create tetrahedron (actually simple Polyhedra) with given parameters.
:param [Vector3,Vector3,Vector3,Vector3] vertices: coordinates of vertices in the global coordinate system.
@@ -360,7 +360,7 @@
inertia = b.shape.GetInertia()
center = b.shape.GetCentroid()
_commonBodySetup(b,volume,inertia,material,noBound=noBound,pos=center,fixed=fixed)
- b.aspherical=False # mass and inertia are 0 anyway; fell free to change to ``True`` if needed
+ b.aspherical=False
b.state.ori = b.shape.GetOri()
b.mask=mask
b.chain=chain
@@ -394,6 +394,24 @@
b.chain = chain
return b
+def polyhedron(vertices,dynamic=True,fixed=False,wire=True,color=None,highlight=False,noBound=False,material=-1,mask=1,chain=-1):
+ """Create tetrahedron (actually simple Polyhedra) with given parameters.
+
+ :param [Vector3,Vector3,Vector3,Vector3] vertices: coordinates of vertices in the global coordinate system.
+
+ See :yref:`yade.utils.sphere`'s documentation for meaning of other parameters."""
+ b=Body()
+ b.shape = Polyhedra(v=vertices,color=color if color else randomColor(),wire=wire,highlight=highlight)
+ volume = b.shape.GetVolume()
+ inertia = b.shape.GetInertia()
+ center = b.shape.GetCentroid()
+ _commonBodySetup(b,volume,inertia,material,noBound=noBound,pos=center,fixed=fixed)
+ b.aspherical=False
+ b.state.ori = b.shape.GetOri()
+ b.mask=mask
+ b.chain=chain
+ return b
+
@@ -1013,6 +1031,7 @@
b = facet([self.vertices[j] for j in c],**kw)
elif len(c) == 4:
b = tetra([self.vertices[j] for j in c],**kw)
+ #b = polyhedron([self.vertices[j] for j in c],**kw)
else:
raise RuntimeError, "Unsupported cell shape (should be triangle or tetrahedron)"
self.elements[i] = b
@@ -1050,6 +1069,8 @@
self.forces[ie[1]] += f*w1/ww
self.forces[ie[2]] += f*w2/ww
self.forces[ie[3]] += f*w3/ww
+ else:
+ raise RuntimeError, "TODO"
return self.forces
def setPositionsOfNodes(self,newPoss):
"""Sets new position of nodes and also updates all elements in the simulation
@@ -1070,6 +1091,8 @@
e.shape.vertices = [self.vertices[j] for j in c]
elif isinstance(e.shape,Tetra):
e.shape.v = [self.vertices[j] for j in c]
+ else:
+ raise RuntimeError, "TODO"
def toSimulation(self,bodies=None):
"""Insert all elements to Yade simulation
"""
=== modified file 'py/wrapper/customConverters.cpp'
--- py/wrapper/customConverters.cpp 2014-06-17 10:18:00 +0000
+++ py/wrapper/customConverters.cpp 2014-07-03 17:20:40 +0000
@@ -1,33 +1,6 @@
// 2009 © Václav Šmilauer <eudoxos@xxxxxxxx>
-// this is not currently used, but can be enabled if needed
-// probably breaks compilation for older (like <=1.35 or so)
-// boost::python
-#if 0
- #include<indexing_suite/container_suite.hpp>
- // #include<indexing_suite/container_proxy.hpp>
- #include<indexing_suite/vector.hpp>
-#endif
-
-#if 0
- #include<yade/lib/pyutil/numpy.hpp>
-#endif
-
-#include<boost/python.hpp>
-#include<boost/python/class.hpp>
-#include<boost/python/module.hpp>
-#include<boost/foreach.hpp>
-#ifndef FOREACH
- #define FOREACH BOOST_FOREACH
-#endif
-
-#include<vector>
-#include<string>
-#include<stdexcept>
-#include<iostream>
-#include<map>
-
#include<yade/lib/base/Math.hpp>
#include<yade/lib/base/openmp-accu.hpp>
@@ -43,7 +16,6 @@
#endif
#include<yade/pkg/common/MatchMaker.hpp>
-
// move this to the miniEigen wrapper later
/* two-way se3 handling */
=== modified file 'py/wrapper/yadeWrapper.cpp'
--- py/wrapper/yadeWrapper.cpp 2014-05-23 13:05:19 +0000
+++ py/wrapper/yadeWrapper.cpp 2014-07-03 17:24:54 +0000
@@ -1,28 +1,17 @@
// 2007,2008 © Václav Šmilauer <eudoxos@xxxxxxxx>
-#include<sstream>
-#include<map>
-#include<vector>
+#include<yade/lib/base/Math.hpp>
#include<unistd.h>
#include<list>
#include<signal.h>
-#include<boost/python.hpp>
#include<boost/python/raw_function.hpp>
-// unused now
-#if 0
- #include<boost/python/suite/indexing/vector_indexing_suite.hpp>
-#endif
#include<boost/bind.hpp>
#include<boost/lambda/bind.hpp>
#include<boost/thread/thread.hpp>
#include<boost/filesystem/operations.hpp>
#include<boost/date_time/posix_time/posix_time.hpp>
-#include<boost/any.hpp>
-#include<boost/python.hpp>
-#include<boost/foreach.hpp>
#include<boost/algorithm/string.hpp>
-#include<boost/version.hpp>
#include<yade/lib/base/Logging.hpp>
#include<yade/lib/pyutil/gil.hpp>
@@ -44,8 +33,7 @@
#include<yade/pkg/common/InteractionLoop.hpp>
-// #include<yade/pkg/dem/Shop.hpp>
-#include<yade/core/Clump.hpp>
+#include <yade/core/Clump.hpp>
#include <yade/pkg/common/Sphere.hpp>
#if BOOST_VERSION>=104700
@@ -54,23 +42,17 @@
#include<boost/math/nonfinite_num_facets.hpp>
#endif
+#include <locale>
#include <boost/random/linear_congruential.hpp>
#include <boost/random/uniform_real.hpp>
#include <boost/random/variate_generator.hpp>
-
-#include<yade/core/Timing.hpp>
-
-#include<locale>
-#include<boost/archive/codecvt_null.hpp>
-
-using namespace std;
+#include <boost/archive/codecvt_null.hpp>
+
+#include <yade/core/Timing.hpp>
+#include <yade/lib/serialization/ObjectIO.hpp>
+
namespace py = boost::python;
-#include<yade/lib/serialization/ObjectIO.hpp>
-
-#include<boost/python/object.hpp>
-#include<boost/version.hpp>
-
/*
Python normally iterates over object it is has __getitem__ and __len__, which BodyContainer does.
However, it will not skip removed bodies automatically, hence this iterator which does just that.
@@ -701,7 +683,7 @@
void switchToScene(int i){OMEGA.switchToScene(i);}
string sceneToString(){
ostringstream oss;
- yade::ObjectIO::save<typeof(OMEGA.getScene()),boost::archive::binary_oarchive>(oss,"scene",OMEGA.getScene());
+ yade::ObjectIO::save<TYPEOF(OMEGA.getScene()),boost::archive::binary_oarchive>(oss,"scene",OMEGA.getScene());
oss.flush();
return oss.str();
}
@@ -776,7 +758,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=boost::dynamic_pointer_cast<InteractionContainer>(ClassFactory::instance().createShared(clss));
+ shared_ptr<InteractionContainer> ic=YADE_PTR_DYN_CAST<InteractionContainer>(ClassFactory::instance().createShared(clss));
rb->interactions=ic;
}
string interactionContainer_get(string clss){ return OMEGA.getScene()->interactions->getClassName(); }
@@ -784,7 +766,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=boost::dynamic_pointer_cast<BodyContainer>(ClassFactory::instance().createShared(clss));
+ shared_ptr<BodyContainer> bc=YADE_PTR_DYN_CAST<BodyContainer>(ClassFactory::instance().createShared(clss));
rb->bodies=bc;
}
string bodyContainer_get(string clss){ return OMEGA.getScene()->bodies->getClassName(); }
=== modified file 'py/ymport.py'
--- py/ymport.py 2014-06-12 16:54:31 +0000
+++ py/ymport.py 2014-06-25 12:54:16 +0000
@@ -112,12 +112,9 @@
b.shape.color=color if color else utils.randomColor()
b.shape.wire=wire
b.shape.highlight=highlight
- pos,ori=b.state.pos,b.state.ori
+ pos=b.state.pos
utils._commonBodySetup(b,0,Vector3(0,0,0),material=material,pos=pos,noBound=noBound,dynamic=dynamic,fixed=fixed)
- #b.state.pos,b.state.ori=pos,ori
- b.state.ori=ori
- b.aspherical=False
- #b.dynamic=dynamic
+ b.aspherical=False
return facets
def gts(meshfile,shift=(0,0,0),scale=1.0,**kw):