Merge pull request #27 from ParticulateFlow/feature/cherry_pick_PUBLIC

Feature/cherry pick public
This commit is contained in:
Daniel
2017-08-24 16:17:53 +02:00
committed by GitHub
97 changed files with 1960 additions and 1562 deletions

View File

@ -25,7 +25,7 @@ License
along with CFDEMcoupling. If not, see <http://www.gnu.org/licenses/>. along with CFDEMcoupling. If not, see <http://www.gnu.org/licenses/>.
Application Application
cfdemSolverPiso cfdemSolverPisoScalar
Description Description
Transient solver for incompressible flow. Transient solver for incompressible flow.

View File

@ -111,6 +111,7 @@ $(voidFractionModels)/dividedVoidFractionMS/dividedVoidFractionMS.C
$(voidFractionModels)/bigParticleVoidFraction/bigParticleVoidFraction.C $(voidFractionModels)/bigParticleVoidFraction/bigParticleVoidFraction.C
$(voidFractionModels)/GaussVoidFraction/GaussVoidFraction.C $(voidFractionModels)/GaussVoidFraction/GaussVoidFraction.C
$(voidFractionModels)/IBVoidFraction/IBVoidFraction.C $(voidFractionModels)/IBVoidFraction/IBVoidFraction.C
$(voidFractionModels)/trilinearVoidFraction/trilinearVoidFraction.C
$(locateModels)/locateModel/locateModel.C $(locateModels)/locateModel/locateModel.C
$(locateModels)/locateModel/newLocateModel.C $(locateModels)/locateModel/newLocateModel.C

View File

@ -1,3 +1,2 @@
//set probeModel parameters for this force model //set probeModel parameters for this force model
particleCloud_.probeM().setOutputFile(); if (probeIt_) { particleCloud_.probeM().setOutputFile(typeName+".logDat"); }
particleCloud_.probeM().setCounter();

View File

@ -126,6 +126,7 @@ cfdemCloud::cfdemCloud
mesh, mesh,
dimensionedScalar("zero", dimensionSet(0,0,-1,0,0), 0) // 1/s dimensionedScalar("zero", dimensionSet(0,0,-1,0,0), 0) // 1/s
), ),
checkPeriodicCells_(false),
turbulence_ turbulence_
( (
mesh.lookupObject<turbulenceModel> mesh.lookupObject<turbulenceModel>
@ -196,7 +197,7 @@ cfdemCloud::cfdemCloud
clockModel::New clockModel::New
( (
couplingProperties_, couplingProperties_,
*this mesh.time()
) )
), ),
smoothingModel_ smoothingModel_
@ -225,6 +226,14 @@ cfdemCloud::cfdemCloud
solveFlow_=Switch(couplingProperties_.lookup("solveFlow")); solveFlow_=Switch(couplingProperties_.lookup("solveFlow"));
if (couplingProperties_.found("imExSplitFactor")) if (couplingProperties_.found("imExSplitFactor"))
imExSplitFactor_ = readScalar(couplingProperties_.lookup("imExSplitFactor")); imExSplitFactor_ = readScalar(couplingProperties_.lookup("imExSplitFactor"));
if(imExSplitFactor_ > 1.0)
FatalError << "You have set imExSplitFactor > 1 in your couplingProperties. Must be <= 1."
<< abort(FatalError);
if(imExSplitFactor_ < 0.0)
FatalError << "You have set imExSplitFactor < 0 in your couplingProperties. Must be >= 0."
<< abort(FatalError);
if (couplingProperties_.found("treatVoidCellsAsExplicitForce")) if (couplingProperties_.found("treatVoidCellsAsExplicitForce"))
treatVoidCellsAsExplicitForce_ = readBool(couplingProperties_.lookup("treatVoidCellsAsExplicitForce")); treatVoidCellsAsExplicitForce_ = readBool(couplingProperties_.lookup("treatVoidCellsAsExplicitForce"));
if (couplingProperties_.found("verbose")) verbose_=true; if (couplingProperties_.found("verbose")) verbose_=true;
@ -289,7 +298,37 @@ cfdemCloud::cfdemCloud
} }
dataExchangeM().setCG(); dataExchangeM().setCG();
if (!cgOK_ && cg_ > 1) FatalError<< "at least one of your models is not fit for cg !!!"<< abort(FatalError); Switch cgWarnOnly_(couplingProperties_.lookupOrDefault<Switch>("cgWarnOnly", true));
if (!cgOK_ && cg_ > 1)
{
if (cgWarnOnly_)
Warning << "at least one of your models is not fit for cg !!!" << endl;
else
FatalError << "at least one of your models is not fit for cg !!!" << abort(FatalError);
}
// check if simulation is a fully periodic box
const polyBoundaryMesh& patches = mesh_.boundaryMesh();
int nPatchesCyclic(0);
int nPatchesNonCyclic(0);
forAll(patches, patchI)
{
const polyPatch& pp = patches[patchI];
if (isA<cyclicPolyPatch>(pp) || isA<cyclicAMIPolyPatch>(pp))
++nPatchesCyclic;
else if (!isA<processorPolyPatch>(pp))
++nPatchesNonCyclic;
}
if (nPatchesNonCyclic == 0)
{
checkPeriodicCells_ = true;
}
else if (nPatchesCyclic > 0 && nPatchesNonCyclic > 0)
{
if (verbose_) Info << "nPatchesNonCyclic=" << nPatchesNonCyclic << ", nPatchesCyclic=" << nPatchesCyclic << endl;
Warning << "Periodic handing is disabled because the domain is not fully periodic!\n" << endl;
}
} }
// * * * * * * * * * * * * * * * * Destructors * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * Destructors * * * * * * * * * * * * * * //
@ -412,12 +451,15 @@ void cfdemCloud::setVectorAverages()
); );
if(verbose_) Info << "setVectorAverage done." << endl; if(verbose_) Info << "setVectorAverage done." << endl;
} }
// * * * * * * * * * * * * * * * public Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * public Member Functions * * * * * * * * * * * * * //
void cfdemCloud::checkCG(bool ok) void cfdemCloud::checkCG(bool ok)
{ {
if(!cgOK_) return; if(!cgOK_) return;
if(!ok) cgOK_ = ok; if(!ok) cgOK_ = ok;
} }
void cfdemCloud::setPos(double**& pos) void cfdemCloud::setPos(double**& pos)
{ {
for(int index = 0;index < numberOfParticles(); ++index) for(int index = 0;index < numberOfParticles(); ++index)
@ -427,40 +469,32 @@ void cfdemCloud::setPos(double**& pos)
} }
} }
} }
// * * * * * * * * * * * * * * * ACCESS * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * ACCESS * * * * * * * * * * * * * //
label cfdemCloud::particleCell(int index) label cfdemCloud::particleCell(int index) const
{ {
label cellI = cellIDs()[index][0]; return cellIDs()[index][0];
return cellI;
} }
vector cfdemCloud::position(int index) vector cfdemCloud::position(int index) const
{ {
vector pos; return vector(positions()[index][0],positions()[index][1],positions()[index][2]);
for(int i=0;i<3;i++) pos[i] = positions()[index][i];
return pos;
} }
vector cfdemCloud::velocity(int index) vector cfdemCloud::velocity(int index) const
{ {
vector vel; return vector(velocities()[index][0],velocities()[index][1],velocities()[index][2]);
for(int i=0;i<3;i++) vel[i] = velocities()[index][i];
return vel;
} }
vector cfdemCloud::expForce(int index) vector cfdemCloud::expForce(int index) const
{ {
vector force; return vector(DEMForces()[index][0],DEMForces()[index][1],DEMForces()[index][2]);
for(int i=0;i<3;i++) force[i] = DEMForces()[index][i];
return force;
} }
vector cfdemCloud::fluidVel(int index) vector cfdemCloud::fluidVel(int index) const
{ {
vector vel; return vector(fluidVels()[index][0],fluidVels()[index][1],fluidVels()[index][2]);
for(int i=0;i<3;i++) vel[i] = fluidVels()[index][i];
return vel;
} }
const forceModel& cfdemCloud::forceM(int i) const forceModel& cfdemCloud::forceM(int i)
@ -468,43 +502,31 @@ const forceModel& cfdemCloud::forceM(int i)
return forceModel_[i]; return forceModel_[i];
} }
int cfdemCloud::nrForceModels() label cfdemCloud::nrForceModels() const
{ {
return forceModels_.size(); return forceModels_.size();
} }
int cfdemCloud::nrMomCoupleModels() label cfdemCloud::nrMomCoupleModels() const
{ {
return momCoupleModels_.size(); return momCoupleModels_.size();
} }
scalar cfdemCloud::voidfraction(int index) scalar cfdemCloud::voidfraction(int index) const
{ {
return voidfractions()[index][0]; return voidfractions()[index][0];
} }
label cfdemCloud::liggghtsCommandModelIndex(word name) label cfdemCloud::liggghtsCommandModelIndex(word name) const
{ {
int index=-1;
forAll(liggghtsCommandModelList_,i) forAll(liggghtsCommandModelList_,i)
{ {
if(liggghtsCommand()[i]().name() == name) if(liggghtsCommand()[i]().name() == name)
{ {
index = i; return i;
break;
} }
} }
return index; return -1;
}
std::vector< std::vector<double*> >* cfdemCloud::getVprobe()
{
return probeModel_->getVprobe();
}
std::vector< std::vector<double> >* cfdemCloud::getSprobe()
{
return probeModel_->getSprobe();
} }
// * * * * * * * * * * * * * * * WRITE * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * WRITE * * * * * * * * * * * * * //
@ -675,29 +697,6 @@ bool cfdemCloud::reAllocArrays()
return false; return false;
} }
bool cfdemCloud::reAllocArrays(int nP, bool forceRealloc)
{
if( (numberOfParticlesChanged_ && !arraysReallocated_) || forceRealloc)
{
// get arrays of new length
dataExchangeM().allocateArray(positions_,0.,3,nP);
dataExchangeM().allocateArray(velocities_,0.,3,nP);
dataExchangeM().allocateArray(fluidVel_,0.,3,nP);
dataExchangeM().allocateArray(impForces_,0.,3,nP);
dataExchangeM().allocateArray(expForces_,0.,3,nP);
dataExchangeM().allocateArray(DEMForces_,0.,3,nP);
dataExchangeM().allocateArray(Cds_,0.,1,nP);
dataExchangeM().allocateArray(radii_,0.,1,nP);
dataExchangeM().allocateArray(voidfractions_,1.,voidFractionM().maxCellsPerParticle(),nP);
dataExchangeM().allocateArray(cellIDs_,-1,voidFractionM().maxCellsPerParticle(),nP);
dataExchangeM().allocateArray(particleWeights_,0.,voidFractionM().maxCellsPerParticle(),nP);
dataExchangeM().allocateArray(particleVolumes_,0.,voidFractionM().maxCellsPerParticle(),nP);
arraysReallocated_ = true;
return true;
}
return false;
}
tmp<fvVectorMatrix> cfdemCloud::divVoidfractionTau(volVectorField& U,volScalarField& voidfraction) const tmp<fvVectorMatrix> cfdemCloud::divVoidfractionTau(volVectorField& U,volScalarField& voidfraction) const
{ {
return return

View File

@ -49,7 +49,7 @@ SourceFiles
#include "fvCFD.H" #include "fvCFD.H"
#include "IFstream.H" #include "IFstream.H"
#include <turbulenceModel.H> #include "turbulenceModel.H"
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
@ -160,6 +160,8 @@ protected:
mutable volScalarField ddtVoidfraction_; mutable volScalarField ddtVoidfraction_;
mutable Switch checkPeriodicCells_;
const turbulenceModel& turbulence_; const turbulenceModel& turbulence_;
autoPtr<forceModel>* forceModel_; autoPtr<forceModel>* forceModel_;
@ -228,41 +230,41 @@ public:
void setPos(double **&); void setPos(double **&);
word modelType(){ return modelType_; } const word& modelType() const { return modelType_; }
label particleCell(int); label particleCell(int) const;
vector position(int); vector position(int) const;
vector velocity(int); vector velocity(int) const;
vector expForce(int); vector expForce(int) const;
vector fluidVel(int); vector fluidVel(int) const;
virtual const forceModel& forceM(int); virtual const forceModel& forceM(int);
virtual int nrForceModels(); virtual label nrForceModels() const;
virtual int nrMomCoupleModels(); virtual label nrMomCoupleModels() const;
scalar voidfraction(int); scalar voidfraction(int) const;
label liggghtsCommandModelIndex(word); label liggghtsCommandModelIndex(word) const;
inline void setCG(double) const; inline void setCG(double);
inline const scalar& cg() const; inline scalar cg() const;
inline const bool& impDEMdrag() const; inline bool impDEMdrag() const;
inline const bool& impDEMdragAcc() const; inline bool impDEMdragAcc() const;
inline const scalar& imExSplitFactor() const; inline scalar imExSplitFactor() const;
inline const bool& treatVoidCellsAsExplicitForce() const; inline bool treatVoidCellsAsExplicitForce() const;
inline const bool& ignore() const; inline bool ignore() const;
inline const fvMesh& mesh() const; inline const fvMesh& mesh() const;
@ -300,13 +302,13 @@ public:
inline double ** particleWeights() const; inline double ** particleWeights() const;
virtual inline label body(int); virtual inline label body(int) const;
virtual inline double particleVolume(int); virtual inline double particleVolume(int) const;
inline scalar radius(int); inline scalar radius(int) const;
virtual inline double d(int); virtual inline double d(int) const;
inline scalar d32(bool recalc=true); inline scalar d32(bool recalc=true);
virtual inline double dMin() {return -1;} virtual inline double dMin() {return -1;}
@ -322,11 +324,11 @@ public:
//access to the particle's rotation and torque data //access to the particle's rotation and torque data
virtual inline double ** DEMTorques() const {return NULL;} virtual inline double ** DEMTorques() const {return NULL;}
virtual inline double ** omegaArray() const {return NULL;} virtual inline double ** omegaArray() const {return NULL;}
virtual vector omega(int) const {return Foam::vector(0,0,0);} virtual vector omega(int) const {return vector(0,0,0);}
//access to the particles' orientation information //access to the particles' orientation information
virtual inline double ** exArray() const {return NULL;} virtual inline double ** exArray() const {return NULL;}
virtual vector ex(int) const {return Foam::vector(0,0,0);} virtual vector ex(int) const {return vector(0,0,0);}
//Detector if SRF module is enable or not //Detector if SRF module is enable or not
virtual inline bool SRFOn(){return false;} virtual inline bool SRFOn(){return false;}
@ -339,7 +341,7 @@ public:
inline bool arraysReallocated() const; inline bool arraysReallocated() const;
inline const wordList& forceModels(); inline const wordList& forceModels() const;
inline const voidFractionModel& voidFractionM() const; inline const voidFractionModel& voidFractionM() const;
@ -347,11 +349,11 @@ public:
inline const momCoupleModel& momCoupleM(int) const; inline const momCoupleModel& momCoupleM(int) const;
inline const dataExchangeModel& dataExchangeM() const; inline dataExchangeModel& dataExchangeM();
inline const IOModel& IOM() const; inline const IOModel& IOM() const;
inline const probeModel& probeM() const; inline probeModel& probeM();
inline const averagingModel& averagingM() const; inline const averagingModel& averagingM() const;
@ -376,13 +378,10 @@ public:
virtual bool reAllocArrays(); virtual bool reAllocArrays();
virtual bool reAllocArrays(int nP, bool forceRealloc); //force number of particles during reallocation
// IO // IO
void writeScalarFieldToTerminal(double**&); void writeScalarFieldToTerminal(double**&) const;
void writeVectorFieldToTerminal(double**&); void writeVectorFieldToTerminal(double**&) const;
// functions // functions
tmp<fvVectorMatrix> divVoidfractionTau(volVectorField& ,volScalarField&) const; tmp<fvVectorMatrix> divVoidfractionTau(volVectorField& ,volScalarField&) const;
@ -397,11 +396,9 @@ public:
void resetArray(double**&,int,int,double resetVal=0.); void resetArray(double**&,int,int,double resetVal=0.);
std::vector< std::vector<double*> >* getVprobe();
std::vector< std::vector<double> >* getSprobe();
void otherForces(volVectorField&); void otherForces(volVectorField&);
bool checkPeriodicCells() { return checkPeriodicCells_; }
}; };

View File

@ -44,38 +44,38 @@ namespace Foam
{ {
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
inline void cfdemCloud::setCG(double cg) const inline void cfdemCloud::setCG(double cg)
{ {
cg_ = cg; cg_ = cg;
Info << "cg is set to: " << cg_ << endl; Info << "cg is set to: " << cg_ << endl;
} }
inline const bool& cfdemCloud::impDEMdrag() const inline bool cfdemCloud::impDEMdrag() const
{ {
return impDEMdrag_; return impDEMdrag_;
} }
inline const bool& cfdemCloud::impDEMdragAcc() const inline bool cfdemCloud::impDEMdragAcc() const
{ {
return impDEMdragAcc_; return impDEMdragAcc_;
} }
inline const scalar& cfdemCloud::imExSplitFactor() const inline scalar cfdemCloud::imExSplitFactor() const
{ {
return imExSplitFactor_; return imExSplitFactor_;
} }
inline const bool& cfdemCloud::treatVoidCellsAsExplicitForce() const inline bool cfdemCloud::treatVoidCellsAsExplicitForce() const
{ {
return treatVoidCellsAsExplicitForce_; return treatVoidCellsAsExplicitForce_;
} }
inline const scalar& cfdemCloud::cg() const inline scalar cfdemCloud::cg() const
{ {
return cg_; return cg_;
} }
inline const bool& cfdemCloud::ignore() const inline bool cfdemCloud::ignore() const
{ {
return ignore_; return ignore_;
} }
@ -177,24 +177,24 @@ inline double ** cfdemCloud::particleWeights() const
return particleWeights_; return particleWeights_;
} }
inline label cfdemCloud::body(int index) inline label cfdemCloud::body(int index) const
{ {
return index; return index;
} }
inline double cfdemCloud::particleVolume(int index) inline double cfdemCloud::particleVolume(int index) const
{ {
return particleV_[index][0]; return particleV_[index][0];
} }
inline scalar cfdemCloud::radius(int index) inline scalar cfdemCloud::radius(int index) const
{ {
return radii_[index][0]; return radii_[index][0];
} }
inline double cfdemCloud::d(int index) inline double cfdemCloud::d(int index) const
{ {
return 2*radii_[index][0]; return 2.*radii_[index][0];
} }
inline double cfdemCloud::d32(bool recalc) inline double cfdemCloud::d32(bool recalc)
@ -237,7 +237,7 @@ inline bool cfdemCloud::arraysReallocated() const
return arraysReallocated_; return arraysReallocated_;
} }
inline const wordList& cfdemCloud::forceModels() inline const wordList& cfdemCloud::forceModels() const
{ {
return forceModels_; return forceModels_;
} }
@ -252,9 +252,9 @@ inline const momCoupleModel& cfdemCloud::momCoupleM(int i) const
return momCoupleModel_[i]; return momCoupleModel_[i];
} }
inline const dataExchangeModel& cfdemCloud::dataExchangeM() const inline dataExchangeModel& cfdemCloud::dataExchangeM()
{ {
return dataExchangeModel_; return dataExchangeModel_();
} }
inline const IOModel& cfdemCloud::IOM() const inline const IOModel& cfdemCloud::IOM() const
@ -262,9 +262,9 @@ inline const IOModel& cfdemCloud::IOM() const
return IOModel_; return IOModel_;
} }
inline const probeModel& cfdemCloud::probeM() const inline probeModel& cfdemCloud::probeM()
{ {
return probeModel_; return probeModel_();
} }
inline const voidFractionModel& cfdemCloud::voidFractionM() const inline const voidFractionModel& cfdemCloud::voidFractionM() const

View File

@ -48,7 +48,7 @@ namespace Foam
// * * * * * * * * * * * * * * * IO * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * IO * * * * * * * * * * * * * //
void cfdemCloud::writeScalarFieldToTerminal(double**& array) void cfdemCloud::writeScalarFieldToTerminal(double**& array) const
{ {
// init double array // init double array
for (int i=0; i<numberOfParticles(); i++) for (int i=0; i<numberOfParticles(); i++)
@ -57,7 +57,7 @@ void cfdemCloud::writeScalarFieldToTerminal(double**& array)
} }
} }
void cfdemCloud::writeVectorFieldToTerminal(double**& array) void cfdemCloud::writeVectorFieldToTerminal(double**& array) const
{ {
// init double array // init double array
for (int i=0; i<numberOfParticles(); i++) for (int i=0; i<numberOfParticles(); i++)

View File

@ -92,12 +92,12 @@ void cfdemCloudEnergy::speciesExecute()
} }
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
int cfdemCloudEnergy::nrEnergyModels() label cfdemCloudEnergy::nrEnergyModels() const
{ {
return energyModels_.size(); return energyModels_.size();
} }
bool& cfdemCloudEnergy::implicitEnergyModel() bool cfdemCloudEnergy::implicitEnergyModel() const
{ {
return implicitEnergyModel_; return implicitEnergyModel_;
} }

View File

@ -94,11 +94,11 @@ public:
const chemistryModel& chemistryM(); const chemistryModel& chemistryM();
int nrEnergyModels(); label nrEnergyModels() const;
inline const wordList& energyModels(); inline const wordList& energyModels() const;
bool& implicitEnergyModel(); bool implicitEnergyModel() const;
void energyContributions(volScalarField&); void energyContributions(volScalarField&);

View File

@ -25,7 +25,7 @@ namespace Foam
{ {
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
inline const wordList& cfdemCloudEnergy::energyModels() inline const wordList& cfdemCloudEnergy::energyModels() const
{ {
return energyModels_; return energyModels_;
} }

View File

@ -91,7 +91,7 @@ bool cfdemCloudIB::reAllocArrays()
if(cfdemCloud::reAllocArrays()) if(cfdemCloud::reAllocArrays())
{ {
// get arrays of new length // get arrays of new length
dataExchangeM().allocateArray(angularVelocities_,0,3); dataExchangeM().allocateArray(angularVelocities_,0.,3);
return true; return true;
} }
return false; return false;
@ -224,11 +224,9 @@ void cfdemCloudIB::calcVelocityCorrection
} }
vector cfdemCloudIB::angularVelocity(int index) vector cfdemCloudIB::angularVelocity(int index) const
{ {
vector vel; return vector(angularVelocities_[index][0],angularVelocities_[index][1],angularVelocities_[index][2]);
for(int i=0;i<3;i++) vel[i] = angularVelocities_[index][i];
return vel;
} }
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //

View File

@ -90,7 +90,7 @@ public:
void calcVelocityCorrection(volScalarField&,volVectorField&,volScalarField&,volScalarField&); // this could be moved to an IB mom couple model void calcVelocityCorrection(volScalarField&,volVectorField&,volScalarField&,volScalarField&); // this could be moved to an IB mom couple model
// Access // Access
vector angularVelocity(int); vector angularVelocity(int) const;
inline double ** angularVelocities() const inline double ** angularVelocities() const
{ {

View File

@ -128,7 +128,7 @@ void cfdemCloudMS::getDEMdata()
//- save clump volume and mass //- save clump volume and mass
double **typeDH(NULL); double **typeDH(NULL);
dataExchangeM().allocateArray(typeDH,-1,1,nClumpTypes()+1); dataExchangeM().allocateArray(typeDH,-1.,1,nClumpTypes()+1);
if(manDHdev_) // use manually defined dH if(manDHdev_) // use manually defined dH
{ {
for(int k = 1;k <= nClumpTypes(); k++) for(int k = 1;k <= nClumpTypes(); k++)
@ -192,18 +192,18 @@ bool cfdemCloudMS::reAllocArrays()
if(cfdemCloud::reAllocArrays()) if(cfdemCloud::reAllocArrays())
{ {
// get arrays of new length // get arrays of new length
dataExchangeM().allocateArray(positionsCM_,0,3,"nbodies"); dataExchangeM().allocateArray(positionsCM_,0.,3,"nbodies");
dataExchangeM().allocateArray(velocitiesCM_,0,3,"nbodies"); dataExchangeM().allocateArray(velocitiesCM_,0.,3,"nbodies");
dataExchangeM().allocateArray(cellIDsCM_,-1,1,"nbodies"); dataExchangeM().allocateArray(cellIDsCM_,-1,1,"nbodies");
dataExchangeM().allocateArray(bodies_,0,1); dataExchangeM().allocateArray(bodies_,0,1);
dataExchangeM().allocateArray(nrigids_,0,1,"nbodies"); dataExchangeM().allocateArray(nrigids_,0,1,"nbodies");
dataExchangeM().allocateArray(clumpType_,0,1,"nbodies"); dataExchangeM().allocateArray(clumpType_,0,1,"nbodies");
dataExchangeM().allocateArray(clumpVol_,0,1,"nbodies"); dataExchangeM().allocateArray(clumpVol_,0.,1,"nbodies");
dataExchangeM().allocateArray(clumpDH_,1.,1,"nbodies"); dataExchangeM().allocateArray(clumpDH_,1.,1,"nbodies");
dataExchangeM().allocateArray(clumpWeights_,1,1,"nbodies"); dataExchangeM().allocateArray(clumpWeights_,1.,1,"nbodies");
dataExchangeM().allocateArray(impForcesCM_,0,3,"nbodies"); dataExchangeM().allocateArray(impForcesCM_,0.,3,"nbodies");
dataExchangeM().allocateArray(expForcesCM_,0,3,"nbodies"); dataExchangeM().allocateArray(expForcesCM_,0.,3,"nbodies");
dataExchangeM().allocateArray(DEMForcesCM_,0,3,"nbodies"); dataExchangeM().allocateArray(DEMForcesCM_,0.,3,"nbodies");
return true; return true;
} }
return false; return false;

View File

@ -117,9 +117,9 @@ public:
// Member Functions // Member Functions
// Access // Access
inline label body(int); inline label body(int) const;
inline double particleVolume(int); inline double particleVolume(int) const;
inline vector positionCM(int); inline vector positionCM(int);
@ -127,9 +127,9 @@ public:
inline label cellIDCM(int); inline label cellIDCM(int);
inline label nrigid(int); inline label nrigid(int) const;
inline int nrForceModels(); inline label nrForceModels() const;
inline double **& positionsCM() const; inline double **& positionsCM() const;

View File

@ -36,12 +36,12 @@ namespace Foam
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
inline label cfdemCloudMS::body(int index) inline label cfdemCloudMS::body(int index) const
{ {
return bodies_[0][index]-1; return bodies_[0][index]-1;
} }
inline double cfdemCloudMS::particleVolume(int index) inline double cfdemCloudMS::particleVolume(int index) const
{ {
int ind = body(index); // particle to clump ID int ind = body(index); // particle to clump ID
@ -75,12 +75,12 @@ inline label cfdemCloudMS::cellIDCM(int index)
return cellIDsCM_[index][0]; return cellIDsCM_[index][0];
} }
inline label cfdemCloudMS::nrigid(int index) inline label cfdemCloudMS::nrigid(int index) const
{ {
return nrigids_[0][index]; return nrigids_[0][index];
} }
inline int cfdemCloudMS::nrForceModels() inline label cfdemCloudMS::nrForceModels() const
{ {
return forceModels_.size(); return forceModels_.size();
} }

View File

@ -313,7 +313,7 @@ void averagingModel::resetWeightFields() const
} }
void Foam::averagingModel::undoWeightFields(double**const& mask) const void averagingModel::undoWeightFields(double**const& mask) const
{ {
for(int index=0; index< particleCloud_.numberOfParticles(); index++) for(int index=0; index< particleCloud_.numberOfParticles(); index++)
{ {
@ -326,41 +326,22 @@ void Foam::averagingModel::undoWeightFields(double**const& mask) const
} }
} }
tmp<volVectorField> Foam::averagingModel::UsInterp() const tmp<volVectorField> averagingModel::UsInterp() const
{ {
tmp<volVectorField> tsource
(
new volVectorField
(
IOobject
(
"Us_averagingModel",
particleCloud_.mesh().time().timeName(),
particleCloud_.mesh(),
IOobject::NO_READ,
IOobject::NO_WRITE
),
particleCloud_.mesh(),
dimensionedVector
(
"zero",
dimensionSet(0, 1, -1, 0, 0),
vector::zero
)
)
);
if (particleCloud_.dataExchangeM().couplingStep() > 1) if (particleCloud_.dataExchangeM().couplingStep() > 1)
{ {
tsource.ref() = (1 - particleCloud_.dataExchangeM().timeStepFraction()) * UsPrev_ return tmp<volVectorField>
+ particleCloud_.dataExchangeM().timeStepFraction() * UsNext_; (
new volVectorField("Us_averagingModel", (1. - particleCloud_.dataExchangeM().timeStepFraction()) * UsPrev_ + particleCloud_.dataExchangeM().timeStepFraction() * UsNext_)
);
} }
else else
{ {
tsource.ref() = UsNext_; return tmp<volVectorField>
(
new volVectorField("Us_averagingModel", UsNext_)
);
} }
return tsource;
} }
// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * //

View File

@ -147,11 +147,11 @@ species::species
species::~species() species::~species()
{ {
delete partTemp_; particleCloud_.dataExchangeM().destroy(partTemp_,1);
delete partRho_; particleCloud_.dataExchangeM().destroy(partRho_,1);
for (int i=0; i<speciesNames_.size();i++) delete [] concentrations_[i]; for (int i=0; i<speciesNames_.size();i++) particleCloud_.dataExchangeM().destroy(concentrations_[i],1);
for (int i=0; i<speciesNames_.size();i++) delete [] changeOfSpeciesMass_[i]; for (int i=0; i<speciesNames_.size();i++) particleCloud_.dataExchangeM().destroy(changeOfSpeciesMass_[i],1);
} }

View File

@ -33,7 +33,7 @@ Description
#include <mpi.h> #include <mpi.h>
#include "clockModel.H" #include "clockModel.H"
#include <unistd.h> #include <unistd.h>
#include <time.h>
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
@ -48,19 +48,18 @@ defineRunTimeSelectionTable(clockModel, dictionary);
// * * * * * * * * * * * * * public Member Functions * * * * * * * * * * * * // // * * * * * * * * * * * * * public Member Functions * * * * * * * * * * * * //
void Foam::clockModel::start(int pos) const void clockModel::start(int pos) const
{ {
start(pos,""); start(pos,"");
return;
} }
void Foam::clockModel::start(int pos, const std::string& ident) const void clockModel::start(int pos, const std::string& ident) const
{ {
if (particleCloud_.mesh().time().value() > startTime_) if (time_.value() > startTime_)
{ {
if (pos >= n_) // alternatively one fixed size? if (pos >= n_) // alternatively one fixed size?
{ {
n_ = 2*n_; n_ += 32;
deltaT_.resize(n_,0); deltaT_.resize(n_,0);
identifier_.resize(n_,""); identifier_.resize(n_,"");
nOfRuns_.resize(n_,0); nOfRuns_.resize(n_,0);
@ -75,12 +74,11 @@ void Foam::clockModel::start(int pos, const std::string& ident) const
nOfRuns_[pos] += 1; nOfRuns_[pos] += 1;
deltaT_[pos] -= std::clock(); deltaT_[pos] -= std::clock();
} }
return;
} }
void Foam::clockModel::stop() const void clockModel::stop() const
{ {
if (particleCloud_.mesh().time().value() > startTime_) if (time_.value() > startTime_)
{ {
deltaT_[curParent_] += std::clock(); deltaT_[curParent_] += std::clock();
curLev_ -= 1; curLev_ -= 1;
@ -93,12 +91,11 @@ void Foam::clockModel::stop() const
curParent_ = -1; curParent_ = -1;
} }
} }
return;
} }
void Foam::clockModel::stop(const std::string& ident) const void clockModel::stop(const std::string& ident) const
{ {
if (particleCloud_.mesh().time().value() > startTime_) if (time_.value() > startTime_)
{ {
deltaT_[curParent_] += std::clock(); deltaT_[curParent_] += std::clock();
if (curParent_ > 0 && identifier_[curParent_].compare(ident) != 0) if (curParent_ > 0 && identifier_[curParent_].compare(ident) != 0)
@ -115,10 +112,9 @@ void Foam::clockModel::stop(const std::string& ident) const
curParent_ = -1; curParent_ = -1;
} }
} }
return;
} }
std::string Foam::clockModel::eval() const std::string clockModel::eval() const
{ {
std::ostringstream strs("Measurements in CPU-seconds:\n"); std::ostringstream strs("Measurements in CPU-seconds:\n");
strs << "Name\tdeltaT\tnOfRuns\tlevel\tparentNr\tparentName\n"; strs << "Name\tdeltaT\tnOfRuns\tlevel\tparentNr\tparentName\n";
@ -149,7 +145,7 @@ std::string Foam::clockModel::eval() const
return strs.str(); return strs.str();
} }
void Foam::clockModel::evalFile() const void clockModel::evalFile() const
{ {
std::ofstream outFile; std::ofstream outFile;
std::string fileName(path_/"timeEval.txt"); std::string fileName(path_/"timeEval.txt");
@ -159,7 +155,7 @@ void Foam::clockModel::evalFile() const
outFile.close(); outFile.close();
} }
void Foam::clockModel::evalPar() const void clockModel::evalPar() const
{ {
int myrank, numprocs; int myrank, numprocs;
MPI_Comm_rank(MPI_COMM_WORLD, &myrank); MPI_Comm_rank(MPI_COMM_WORLD, &myrank);
@ -227,29 +223,27 @@ void Foam::clockModel::evalPar() const
outFile << strs.str(); outFile << strs.str();
outFile.close(); outFile.close();
} }
return;
} }
void Foam::clockModel::initElems() void clockModel::initElems()
{ {
//init elems //init elems
for (int i = 0;i < n_; i++) for (int i = 0; i < n_; ++i)
{ {
deltaT_[i] = 0; deltaT_[i] = 0;
identifier_[i] = ""; identifier_[i].clear();
nOfRuns_[i] = 0; nOfRuns_[i] = 0;
level_[i] = -1; level_[i] = -1;
parent_[i] = -2; parent_[i] = -2;
} }
} }
std::vector<int> Foam::clockModel::calcShift() const std::vector<int> clockModel::calcShift() const
{ {
std::vector<int> shifts(n_, 0); std::vector<int> shifts(n_, 0);
for (int i=1; i<n_; i++) for (int i=1; i<n_; ++i)
{ {
if (parent_[i] == -2) if (parent_[i] == -2)
{ {
@ -263,7 +257,7 @@ std::vector<int> Foam::clockModel::calcShift() const
return shifts; return shifts;
} }
void Foam::clockModel::normHist() const void clockModel::normHist() const
{ {
int myrank, numprocs; int myrank, numprocs;
MPI_Comm_rank(MPI_COMM_WORLD,&myrank); MPI_Comm_rank(MPI_COMM_WORLD,&myrank);
@ -300,12 +294,12 @@ void Foam::clockModel::normHist() const
Info << "===========================" << endl; Info << "===========================" << endl;
getRAMUsage(); getRAMUsage();
return;
} }
void Foam::clockModel::plotHist(double buffIn,const std::string& identifier,int numprocs,int myrank) const void clockModel::plotHist(double buffIn,const std::string& identifier,int numprocs,int myrank) const
{ {
double* globalTime_all = NULL; double* globalTime_all = NULL;
if (myrank == 0) globalTime_all = new double[numprocs]; if (myrank == 0) globalTime_all = new double[numprocs];
MPI_Gather(&buffIn, 1, MPI_DOUBLE, globalTime_all, 1, MPI_DOUBLE, 0, MPI_COMM_WORLD); MPI_Gather(&buffIn, 1, MPI_DOUBLE, globalTime_all, 1, MPI_DOUBLE, 0, MPI_COMM_WORLD);
@ -318,9 +312,9 @@ void Foam::clockModel::plotHist(double buffIn,const std::string& identifier,int
delete [] globalTime_all; delete [] globalTime_all;
} }
void Foam::clockModel::Hist() const void clockModel::Hist() const
{ {
int myrank=-10; int myrank = -1;
MPI_Comm_rank(MPI_COMM_WORLD, &myrank); MPI_Comm_rank(MPI_COMM_WORLD, &myrank);
//Global = 1 / Coupling = 2 / LIGGGHTS = 3 /Flow = 26 //Global = 1 / Coupling = 2 / LIGGGHTS = 3 /Flow = 26
@ -333,11 +327,9 @@ void Foam::clockModel::Hist() const
Pout << "[" << myrank << "]: " << "Coupling - LIGGGHTS" << " " << ((deltaT_[2]-deltaT_[3])/CLOCKS_PER_SEC) << '\n'; Pout << "[" << myrank << "]: " << "Coupling - LIGGGHTS" << " " << ((deltaT_[2]-deltaT_[3])/CLOCKS_PER_SEC) << '\n';
//Flow = 26 //Flow = 26
Pout << "[" << myrank << "]: " << identifier_[26] << " " << (deltaT_[26]/CLOCKS_PER_SEC) << '\n'; Pout << "[" << myrank << "]: " << identifier_[26] << " " << (deltaT_[26]/CLOCKS_PER_SEC) << '\n';
return;
} }
void Foam::clockModel::getRAMUsage() const void clockModel::getRAMUsage() const
{ {
int myrank, numprocs; int myrank, numprocs;
MPI_Comm_rank(MPI_COMM_WORLD,&myrank); MPI_Comm_rank(MPI_COMM_WORLD,&myrank);
@ -360,6 +352,7 @@ void Foam::clockModel::getRAMUsage() const
int SwapMem = 0; int SwapMem = 0;
int temp = 0; int temp = 0;
strs.str(""); strs.str("");
if (inFile.is_open()) //search in File smaps for Rss and Swap entries if (inFile.is_open()) //search in File smaps for Rss and Swap entries
{ {
while (inFile.good()) while (inFile.good())
@ -382,14 +375,15 @@ void Foam::clockModel::getRAMUsage() const
} }
} }
} }
double SwapMB = static_cast<double>(SwapMem)/1024.0; //kB -> MB double SwapMB = SwapMem/1024.0; //kB -> MB
double RssMB = static_cast<double>(RssMem)/1024.0; double RssMB = RssMem/1024.0;
inFile.close(); inFile.close();
// set up communication between Procs and plot Stuff // set up communication between Procs and plot Stuff
Info << " RAM USAGE HISTOGRAM in MB" << endl; Info << " RAM USAGE HISTOGRAM in MB" << endl;
plotHist(RssMB,"RSS memory used",numprocs,myrank); plotHist(RssMB,"RSS memory used",numprocs,myrank);
if (SwapMem > 0) if (SwapMem > 0)
{ {
plotHist(SwapMB,"WARNING: Swap",numprocs,myrank); plotHist(SwapMB,"WARNING: Swap",numprocs,myrank);
@ -398,26 +392,23 @@ void Foam::clockModel::getRAMUsage() const
//Pout << "SWAP Memory used: " << SwapMem <<"MB\n"; //Pout << "SWAP Memory used: " << SwapMem <<"MB\n";
//Pout << "Rss Memory used: " << RssMem <<"MB\n"; //Pout << "Rss Memory used: " << RssMem <<"MB\n";
return;
} }
// * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * // // * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * //
// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * //
// Construct from components // Construct from components
Foam::clockModel::clockModel clockModel::clockModel
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm const Time& time
) )
: :
dict_(dict), dict_(dict),
particleCloud_(sm), time_(time),
path_("clockData"), path_("clockData"),
startTime_(sm.mesh().time().startTime().value()+sm.mesh().time().deltaT().value()+SMALL), // delay start of measurement by deltaT startTime_(time.startTime().value()+time.deltaT().value()+SMALL), // delay start of measurement by deltaT
//startTime_(0), //no delay n_(32),
n_(30),
deltaT_(n_), deltaT_(n_),
identifier_(n_), identifier_(n_),
nOfRuns_(n_), nOfRuns_(n_),
@ -432,7 +423,7 @@ Foam::clockModel::clockModel
// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * //
Foam::clockModel::~clockModel() clockModel::~clockModel()
{} {}

View File

@ -42,10 +42,8 @@ SourceFiles
#define START(x) start(__COUNTER__,x) #define START(x) start(__COUNTER__,x)
#include "fvCFD.H" #include "fvCFD.H"
#include "cfdemCloud.H"
#include "dataExchangeModel.H"
#include <vector> #include <vector>
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
namespace Foam namespace Foam
@ -61,7 +59,7 @@ protected:
// Protected data // Protected data
const dictionary& dict_; const dictionary& dict_;
cfdemCloud& particleCloud_; const Time& time_;
fileName path_; fileName path_;
scalar startTime_; scalar startTime_;
@ -88,9 +86,9 @@ public:
dictionary, dictionary,
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm const Time& time
), ),
(dict,sm) (dict,time)
); );
@ -100,7 +98,7 @@ public:
clockModel clockModel
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm const Time& time
); );
@ -114,7 +112,7 @@ public:
static autoPtr<clockModel> New static autoPtr<clockModel> New
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm const Time& time
); );

View File

@ -44,7 +44,7 @@ namespace Foam
autoPtr<clockModel> clockModel::New autoPtr<clockModel> clockModel::New
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm const Time& time
) )
{ {
word clockModelType word clockModelType
@ -73,7 +73,7 @@ autoPtr<clockModel> clockModel::New
<< abort(FatalError); << abort(FatalError);
} }
return autoPtr<clockModel>(cstrIter()(dict,sm)); return autoPtr<clockModel>(cstrIter()(dict,time));
} }

View File

@ -56,10 +56,10 @@ addToRunTimeSelectionTable
noClock::noClock noClock::noClock
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm const Time& time
) )
: :
clockModel(dict,sm) clockModel(dict,time)
{ {
initElems(); initElems();
} }

View File

@ -47,7 +47,7 @@ namespace Foam
{ {
/*---------------------------------------------------------------------------*\ /*---------------------------------------------------------------------------*\
Class noDrag Declaration Class noClock Declaration
\*---------------------------------------------------------------------------*/ \*---------------------------------------------------------------------------*/
class noClock class noClock
@ -67,7 +67,7 @@ public:
noClock noClock
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm const Time& time
); );
// Destructor // Destructor

View File

@ -30,7 +30,6 @@ Description
\*---------------------------------------------------------------------------*/ \*---------------------------------------------------------------------------*/
#include "error.H" #include "error.H"
#include "IOModel.H"
#include "standardClock.H" #include "standardClock.H"
#include "addToRunTimeSelectionTable.H" #include "addToRunTimeSelectionTable.H"
@ -57,12 +56,14 @@ addToRunTimeSelectionTable
standardClock::standardClock standardClock::standardClock
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm const Time& time
) )
: :
clockModel(dict,sm) clockModel(dict,time)
{ {
path_=particleCloud_.IOM().createTimeDir(path_); path_ = path_/time_.timeName();
mkDir(path_,0777);
initElems(); initElems();
} }

View File

@ -47,7 +47,7 @@ namespace Foam
{ {
/*---------------------------------------------------------------------------*\ /*---------------------------------------------------------------------------*\
Class noDrag Declaration Class standardClock Declaration
\*---------------------------------------------------------------------------*/ \*---------------------------------------------------------------------------*/
class standardClock class standardClock
@ -67,7 +67,7 @@ public:
standardClock standardClock
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm const Time& time
); );
// Destructor // Destructor

View File

@ -45,7 +45,7 @@ defineRunTimeSelectionTable(dataExchangeModel, dictionary);
// * * * * * * * * * * * * * * protected Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * protected Member Functions * * * * * * * * * * * * * //
void Foam::dataExchangeModel::setNumberOfParticles(int numberOfParticles) const void dataExchangeModel::setNumberOfParticles(int numberOfParticles) const
{ {
particleCloud_.setNumberOfParticles(numberOfParticles); particleCloud_.setNumberOfParticles(numberOfParticles);
} }
@ -55,7 +55,7 @@ void Foam::dataExchangeModel::setNumberOfParticles(int numberOfParticles) const
//==== //====
// double ** // double **
void Foam::dataExchangeModel::allocateArray void dataExchangeModel::allocateArray
( (
double**& array, double**& array,
double initVal, double initVal,
@ -77,7 +77,7 @@ void Foam::dataExchangeModel::allocateArray
} }
} }
void Foam::dataExchangeModel::allocateArray void dataExchangeModel::allocateArray
( (
double**& array, double**& array,
double initVal, double initVal,
@ -92,7 +92,7 @@ void Foam::dataExchangeModel::allocateArray
allocateArray(array,initVal,width,len); allocateArray(array,initVal,width,len);
} }
void Foam::dataExchangeModel::destroy(double** array,int /*len*/) const void dataExchangeModel::destroy(double** array,int /*len*/) const
{ {
if (array == NULL) return; if (array == NULL) return;
@ -103,7 +103,7 @@ void Foam::dataExchangeModel::destroy(double** array,int /*len*/) const
//==== //====
// int ** // int **
void Foam::dataExchangeModel::allocateArray void dataExchangeModel::allocateArray
( (
int**& array, int**& array,
int initVal, int initVal,
@ -125,7 +125,7 @@ void Foam::dataExchangeModel::allocateArray
} }
} }
void Foam::dataExchangeModel::allocateArray void dataExchangeModel::allocateArray
( (
int**& array, int**& array,
int initVal, int initVal,
@ -140,7 +140,7 @@ void Foam::dataExchangeModel::allocateArray
allocateArray(array,initVal,width,len); allocateArray(array,initVal,width,len);
} }
void Foam::dataExchangeModel::destroy(int** array,int /*len*/) const void dataExchangeModel::destroy(int** array,int /*len*/) const
{ {
if (array == NULL) return; if (array == NULL) return;
@ -152,7 +152,7 @@ void Foam::dataExchangeModel::destroy(int** array,int /*len*/) const
//==== //====
// int * // int *
void Foam::dataExchangeModel::allocateArray void dataExchangeModel::allocateArray
( (
int*& array, int*& array,
int initVal, int initVal,
@ -166,16 +166,15 @@ void Foam::dataExchangeModel::allocateArray
array[i] = initVal; array[i] = initVal;
} }
void Foam::dataExchangeModel::destroy(int* array) const void dataExchangeModel::destroy(int* array) const
{ {
if (array == NULL) return;
delete [] array; delete [] array;
} }
//==== //====
//==== //====
// double * // double *
void Foam::dataExchangeModel::allocateArray void dataExchangeModel::allocateArray
( (
double*& array, double*& array,
double initVal, double initVal,
@ -189,16 +188,14 @@ void Foam::dataExchangeModel::allocateArray
array[i] = initVal; array[i] = initVal;
} }
void Foam::dataExchangeModel::destroy(double* array) const void dataExchangeModel::destroy(double* array) const
{ {
if (array == NULL) return;
delete [] array; delete [] array;
} }
//==== //====
bool Foam::dataExchangeModel::couple(int i) const bool dataExchangeModel::couple(int i) const
{ {
bool coupleNow = false; bool coupleNow = false;
if (doCoupleNow()) if (doCoupleNow())
@ -209,7 +206,7 @@ bool Foam::dataExchangeModel::couple(int i) const
return coupleNow; return coupleNow;
} }
scalar Foam::dataExchangeModel::timeStepFraction() const scalar dataExchangeModel::timeStepFraction() const
{ {
//return fraction between previous coupling TS and actual TS //return fraction between previous coupling TS and actual TS
//scalar DEMtime = DEMts_ * couplingInterval_; //scalar DEMtime = DEMts_ * couplingInterval_;
@ -220,25 +217,25 @@ scalar Foam::dataExchangeModel::timeStepFraction() const
return frac; return frac;
} }
int Foam::dataExchangeModel::getNumberOfParticles() const int dataExchangeModel::getNumberOfParticles() const
{ {
Warning << "ask for nr of particles - which is not supported for this dataExchange model" << endl; Warning << "ask for nr of particles - which is not supported for this dataExchange model" << endl;
return -1; return -1;
} }
int Foam::dataExchangeModel::getNumberOfClumps() const int dataExchangeModel::getNumberOfClumps() const
{ {
Warning << "ask for nr of clumps - which is not supported for this dataExchange model" << endl; Warning << "ask for nr of clumps - which is not supported for this dataExchange model" << endl;
return -1; return -1;
} }
int Foam::dataExchangeModel::getNumberOfTypes() const int dataExchangeModel::getNumberOfTypes() const
{ {
Warning << "ask for nr of types - which is not supported for this dataExchange model" << endl; Warning << "ask for nr of types - which is not supported for this dataExchange model" << endl;
return -1; return -1;
} }
double* Foam::dataExchangeModel::getTypeVol() const double* dataExchangeModel::getTypeVol() const
{ {
Warning << "ask for type volume - which is not supported for this dataExchange model" << endl; Warning << "ask for type volume - which is not supported for this dataExchange model" << endl;
return NULL; return NULL;

View File

@ -245,16 +245,16 @@ public:
for (int i=0;i<n;i++) for (int i=0;i<n;i++)
for (int j=0;j<3;j++) for (int j=0;j<3;j++)
particleCloud_.positions_[i][j]=pos[i*3+j]; particleCloud_.positions_[i][j]=pos[i*3+j];
}; }
inline void setCellIDs(label n,int* ID) const inline void setCellIDs(label n,int* ID) const
{ {
for (int i=0;i<n;i++) for (int i=0;i<n;i++)
particleCloud_.cellIDs_[i][0]=ID[i]; particleCloud_.cellIDs_[i][0]=ID[i];
}; }
virtual word myType() const=0; virtual word myType() const=0;
virtual void setCG() const { Warning << "setCG() not executed correctly!" << endl; } virtual void setCG() { Warning << "setCG() not executed correctly!" << endl; }
}; };

View File

@ -127,7 +127,7 @@ void twoWayMPI::giveData
//============ //============
// double ** // double **
void Foam::twoWayMPI::allocateArray void twoWayMPI::allocateArray
( (
double**& array, double**& array,
double initVal, double initVal,
@ -138,7 +138,7 @@ void Foam::twoWayMPI::allocateArray
allocate_external_double(array, width, length, initVal, lmp); allocate_external_double(array, width, length, initVal, lmp);
} }
void Foam::twoWayMPI::allocateArray void twoWayMPI::allocateArray
( (
double**& array, double**& array,
double initVal, double initVal,
@ -149,7 +149,7 @@ void Foam::twoWayMPI::allocateArray
allocate_external_double(array, width, length, initVal, lmp); allocate_external_double(array, width, length, initVal, lmp);
} }
void Foam::twoWayMPI::destroy(double** array,int /*len*/) const void twoWayMPI::destroy(double** array,int /*len*/) const
{ {
if (array == NULL) return; if (array == NULL) return;
@ -160,7 +160,7 @@ void Foam::twoWayMPI::destroy(double** array,int /*len*/) const
//============ //============
// int ** // int **
void Foam::twoWayMPI::allocateArray void twoWayMPI::allocateArray
( (
int**& array, int**& array,
int initVal, int initVal,
@ -171,7 +171,7 @@ void Foam::twoWayMPI::allocateArray
allocate_external_int(array, width, length, initVal, lmp); allocate_external_int(array, width, length, initVal, lmp);
} }
void Foam::twoWayMPI::allocateArray void twoWayMPI::allocateArray
( (
int**& array, int**& array,
int initVal, int initVal,
@ -182,7 +182,7 @@ void Foam::twoWayMPI::allocateArray
allocate_external_int(array, width, length, initVal, lmp); allocate_external_int(array, width, length, initVal, lmp);
} }
void Foam::twoWayMPI::destroy(int** array,int /*len*/) const void twoWayMPI::destroy(int** array,int /*len*/) const
{ {
if (array == NULL) return; if (array == NULL) return;
@ -192,21 +192,19 @@ void Foam::twoWayMPI::destroy(int** array,int /*len*/) const
} }
//============ //============
// int * // int *
void Foam::twoWayMPI::destroy(int* array) const void twoWayMPI::destroy(int* array) const
{ {
if (array == NULL) return;
free(array); free(array);
} }
//============ //============
// double * // double *
void Foam::twoWayMPI::destroy(double* array) const void twoWayMPI::destroy(double* array) const
{ {
if (array == NULL) return;
free(array); free(array);
} }
//============ //============
bool Foam::twoWayMPI::couple(int i) const bool twoWayMPI::couple(int i) const
{ {
bool coupleNow = false; bool coupleNow = false;
if (i==0) if (i==0)
@ -354,12 +352,12 @@ bool Foam::twoWayMPI::couple(int i) const
return coupleNow; return coupleNow;
} }
int Foam::twoWayMPI::getNumberOfParticles() const int twoWayMPI::getNumberOfParticles() const
{ {
return liggghts_get_maxtag(lmp); return liggghts_get_maxtag(lmp);
} }
int Foam::twoWayMPI::getNumberOfClumps() const int twoWayMPI::getNumberOfClumps() const
{ {
#ifdef multisphere #ifdef multisphere
return liggghts_get_maxtag_ms(lmp); return liggghts_get_maxtag_ms(lmp);
@ -369,7 +367,7 @@ int Foam::twoWayMPI::getNumberOfClumps() const
return -1; return -1;
} }
int Foam::twoWayMPI::getNumberOfTypes() const int twoWayMPI::getNumberOfTypes() const
{ {
#ifdef multisphere #ifdef multisphere
return liggghts_get_ntypes_ms(lmp); return liggghts_get_ntypes_ms(lmp);
@ -378,7 +376,7 @@ int Foam::twoWayMPI::getNumberOfTypes() const
return -1; return -1;
} }
double* Foam::twoWayMPI::getTypeVol() const double* twoWayMPI::getTypeVol() const
{ {
#ifdef multisphere #ifdef multisphere
return liggghts_get_vclump_ms(lmp); return liggghts_get_vclump_ms(lmp);

View File

@ -160,7 +160,7 @@ public:
word myType() const { return typeName; } word myType() const { return typeName; }
void setCG() const { particleCloud_.setCG(lmp->force->cg()); } void setCG() { particleCloud_.setCG(lmp->force->cg()); }
}; };

View File

@ -280,7 +280,7 @@ void twoWayMany2Many::giveData
//============ //============
// double ** // double **
void Foam::twoWayMany2Many::allocateArray void twoWayMany2Many::allocateArray
( (
double**& array, double**& array,
double initVal, double initVal,
@ -295,7 +295,7 @@ void Foam::twoWayMany2Many::allocateArray
array[i][j] = initVal; array[i][j] = initVal;
} }
void Foam::twoWayMany2Many::allocateArray void twoWayMany2Many::allocateArray
( (
double**& array, double**& array,
double initVal, double initVal,
@ -310,14 +310,14 @@ void Foam::twoWayMany2Many::allocateArray
array[i][j] = initVal; array[i][j] = initVal;
} }
void inline Foam::twoWayMany2Many::destroy(double** array,int len) const void inline twoWayMany2Many::destroy(double** array,int len) const
{ {
lmp->memory->destroy(array); lmp->memory->destroy(array);
} }
//============ //============
// int ** // int **
void Foam::twoWayMany2Many::allocateArray void twoWayMany2Many::allocateArray
( (
int**& array, int**& array,
int initVal, int initVal,
@ -332,7 +332,7 @@ void Foam::twoWayMany2Many::allocateArray
array[i][j] = initVal; array[i][j] = initVal;
} }
void Foam::twoWayMany2Many::allocateArray void twoWayMany2Many::allocateArray
( (
int**& array, int**& array,
int initVal, int initVal,
@ -347,14 +347,14 @@ void Foam::twoWayMany2Many::allocateArray
array[i][j] = initVal; array[i][j] = initVal;
} }
void inline Foam::twoWayMany2Many::destroy(int** array,int len) const void inline twoWayMany2Many::destroy(int** array,int len) const
{ {
lmp->memory->destroy(array); lmp->memory->destroy(array);
} }
//============ //============
// double * // double *
void Foam::twoWayMany2Many::allocateArray(double*& array, double initVal, int length) const void twoWayMany2Many::allocateArray(double*& array, double initVal, int length) const
{ {
int len = max(length,1); int len = max(length,1);
lmp->memory->grow(array, len, "m2m:dbl*"); lmp->memory->grow(array, len, "m2m:dbl*");
@ -362,14 +362,14 @@ void Foam::twoWayMany2Many::allocateArray(double*& array, double initVal, int le
array[i] = initVal; array[i] = initVal;
} }
void inline Foam::twoWayMany2Many::destroy(double* array) const void inline twoWayMany2Many::destroy(double* array) const
{ {
lmp->memory->destroy(array); lmp->memory->destroy(array);
} }
//============== //==============
// int * // int *
void Foam::twoWayMany2Many::allocateArray(int*& array, int initVal, int length) const void twoWayMany2Many::allocateArray(int*& array, int initVal, int length) const
{ {
int len = max(length,1); int len = max(length,1);
lmp->memory->grow(array, len, "m2m:int*"); lmp->memory->grow(array, len, "m2m:int*");
@ -377,14 +377,14 @@ void Foam::twoWayMany2Many::allocateArray(int*& array, int initVal, int length)
array[i] = initVal; array[i] = initVal;
} }
void inline Foam::twoWayMany2Many::destroy(int* array) const void inline twoWayMany2Many::destroy(int* array) const
{ {
lmp->memory->destroy(array); lmp->memory->destroy(array);
} }
//============== //==============
bool Foam::twoWayMany2Many::couple(int i) const bool twoWayMany2Many::couple(int i) const
{ {
bool coupleNow = false; bool coupleNow = false;
if (i==0) if (i==0)
@ -443,19 +443,19 @@ bool Foam::twoWayMany2Many::couple(int i) const
return coupleNow; return coupleNow;
} }
int Foam::twoWayMany2Many::getNumberOfParticles() const int twoWayMany2Many::getNumberOfParticles() const
{ {
return liggghts_get_maxtag(lmp); return liggghts_get_maxtag(lmp);
} }
int Foam::twoWayMany2Many::getNumberOfClumps() const int twoWayMany2Many::getNumberOfClumps() const
{ {
Warning << "Foam::twoWayMany2Many::getNumberOfClumps() - changes necessary here" << endl; Warning << "Foam::twoWayMany2Many::getNumberOfClumps() - changes necessary here" << endl;
//return liggghts_get_maxtag_ms(lmp); //return liggghts_get_maxtag_ms(lmp);
return 1; return 1;
} }
void Foam::twoWayMany2Many::syncIDs() const void twoWayMany2Many::syncIDs() const
{ {
particleCloud_.clockM().start(5,"recv_DEM_ids"); particleCloud_.clockM().start(5,"recv_DEM_ids");
@ -575,7 +575,7 @@ void Foam::twoWayMany2Many::syncIDs() const
particleCloud_.clockM().stop("setup_Comm"); particleCloud_.clockM().stop("setup_Comm");
} }
void Foam::twoWayMany2Many::locateParticle(int* id_lammpsSync, bool id_lammps_alloc_flag) const void twoWayMany2Many::locateParticle(int* id_lammpsSync, bool id_lammps_alloc_flag) const
{ {
#if defined(version21) #if defined(version21)
@ -802,7 +802,7 @@ void Foam::twoWayMany2Many::locateParticle(int* id_lammpsSync, bool id_lammps_al
if (firstRun_) if (firstRun_)
{ {
int* id_foam_nowhere_all; int* id_foam_nowhere_all;
Foam::dataExchangeModel::allocateArray(id_foam_nowhere_all,1,nlocal_foam_lostAll); dataExchangeModel::allocateArray(id_foam_nowhere_all,1,nlocal_foam_lostAll);
MPI_Allreduce(id_foamLostAll, id_foam_nowhere_all, nlocal_foam_lostAll, MPI_INT, MPI_MIN, MPI_COMM_WORLD); MPI_Allreduce(id_foamLostAll, id_foam_nowhere_all, nlocal_foam_lostAll, MPI_INT, MPI_MIN, MPI_COMM_WORLD);
int i = 0; int i = 0;
@ -828,7 +828,7 @@ void Foam::twoWayMany2Many::locateParticle(int* id_lammpsSync, bool id_lammps_al
} }
i++; i++;
} }
Foam::dataExchangeModel::destroy(id_foam_nowhere_all); dataExchangeModel::destroy(id_foam_nowhere_all);
id_foam_nowhere_all = NULL; id_foam_nowhere_all = NULL;
if (id_lammps_alloc_flag) destroy(id_lammps_); if (id_lammps_alloc_flag) destroy(id_lammps_);
id_lammps_ = NULL; id_lammps_ = NULL;

View File

@ -209,7 +209,7 @@ public:
void syncIDs() const; void syncIDs() const;
void locateParticle(int*, bool) const; void locateParticle(int*, bool) const;
word myType() const { return typeName; } word myType() const { return typeName; }
void setCG() const { particleCloud_.setCG(lmp->force->cg()); } void setCG() { particleCloud_.setCG(lmp->force->cg()); }
}; };

View File

@ -155,10 +155,10 @@ heatTransferGunn::heatTransferGunn
heatTransferGunn::~heatTransferGunn() heatTransferGunn::~heatTransferGunn()
{ {
delete partTemp_; particleCloud_.dataExchangeM().destroy(partTemp_,1);
delete partHeatFlux_; particleCloud_.dataExchangeM().destroy(partHeatFlux_,1);
delete partRe_; particleCloud_.dataExchangeM().destroy(partRe_,1);
delete partNu_; particleCloud_.dataExchangeM().destroy(partNu_,1);
} }
// * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * //
@ -354,13 +354,10 @@ void heatTransferGunn::addEnergyContribution(volScalarField& Qsource) const
scalar heatTransferGunn::Nusselt(scalar voidfraction, scalar Rep, scalar Pr) const scalar heatTransferGunn::Nusselt(scalar voidfraction, scalar Rep, scalar Pr) const
{ {
scalar Nup(0.0); return (7 - 10 * voidfraction + 5 * voidfraction * voidfraction) *
Nup = (7 - 10 * voidfraction + 5 * voidfraction * voidfraction) *
(1 + 0.7 * Foam::pow(Rep,0.2) * Foam::pow(Pr,0.33)) + (1 + 0.7 * Foam::pow(Rep,0.2) * Foam::pow(Pr,0.33)) +
(1.33 - 2.4 * voidfraction + 1.2 * voidfraction * voidfraction) * (1.33 - 2.4 * voidfraction + 1.2 * voidfraction * voidfraction) *
Foam::pow(Rep,0.7) * Foam::pow(Pr,0.33); Foam::pow(Rep,0.7) * Foam::pow(Pr,0.33);
return Nup;
} }
void heatTransferGunn::heatFlux(label index, scalar h, scalar As, scalar Tfluid) void heatTransferGunn::heatFlux(label index, scalar h, scalar As, scalar Tfluid)

View File

@ -68,7 +68,7 @@ heatTransferGunnImplicit::heatTransferGunnImplicit
heatTransferGunnImplicit::~heatTransferGunnImplicit() heatTransferGunnImplicit::~heatTransferGunnImplicit()
{ {
delete partHeatFluxCoeff_; particleCloud_.dataExchangeM().destroy(partHeatFluxCoeff_,1);
} }
// * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * //

View File

@ -77,7 +77,7 @@ reactionHeat::reactionHeat
reactionHeat::~reactionHeat() reactionHeat::~reactionHeat()
{ {
delete reactionHeat_; particleCloud_.dataExchangeM().destroy(reactionHeat_,1);
} }
// * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * //

View File

@ -68,7 +68,7 @@ Archimedes::Archimedes
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "archimedesF.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("archimedesForce"); //first entry must the be the force particleCloud_.probeM().vectorFields_.append("archimedesForce"); //first entry must the be the force
particleCloud_.probeM().scalarFields_.append("Vp"); particleCloud_.probeM().scalarFields_.append("Vp");
particleCloud_.probeM().writeHeader(); particleCloud_.probeM().writeHeader();
@ -84,18 +84,20 @@ Archimedes::Archimedes
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(1,true); // activate treatForceDEM switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_DEM,true); // activate treatForceDEM switch
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
if (modelType_=="A" || modelType_=="Bfull"){ if (modelType_=="A" || modelType_=="Bfull")
if(!forceSubM(0).switches()[1]) // treatDEM != true {
if(!forceSubM(0).switches()[SW_TREAT_FORCE_DEM]) // treatDEM != true
{ {
Warning << "Usually model type A and Bfull need Archimedes only on DEM side only (treatForceDEM=true)! are you sure about your settings?" << endl; Warning << "Usually model type A and Bfull need Archimedes only on DEM side only (treatForceDEM=true)! are you sure about your settings?" << endl;
} }
} }
if (modelType_=="B"){ else if (modelType_=="B")
if(forceSubM(0).switches()[1]) // treatDEM = true {
if(forceSubM(0).switches()[SW_TREAT_FORCE_DEM]) // treatDEM = true
{ {
Warning << "Usually model type B needs Archimedes on CFD and DEM side (treatForceDEM=false)! are you sure about your settings?" << endl; Warning << "Usually model type B needs Archimedes on CFD and DEM side (treatForceDEM=false)! are you sure about your settings?" << endl;
} }
@ -133,7 +135,9 @@ void Archimedes::setForce() const
scalar r = particleCloud_.radius(index); scalar r = particleCloud_.radius(index);
force = -g_.value()*forceSubM(0).rhoField()[cellI]*r*r*M_PI; // circle area force = -g_.value()*forceSubM(0).rhoField()[cellI]*r*r*M_PI; // circle area
Warning << "Archimedes::setForce() : this functionality is not tested!" << endl; Warning << "Archimedes::setForce() : this functionality is not tested!" << endl;
}else{ }
else
{
force = -g_.value()*forceSubM(0).rhoField()[cellI]*particleCloud_.particleVolume(index); force = -g_.value()*forceSubM(0).rhoField()[cellI]*particleCloud_.particleVolume(index);
} }

View File

@ -69,7 +69,7 @@ ArchimedesIB::ArchimedesIB
g_(sm.mesh().lookupObject<uniformDimensionedVectorField> (gravityFieldName_)) g_(sm.mesh().lookupObject<uniformDimensionedVectorField> (gravityFieldName_))
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "archimedesIBF.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("archimedesIBForce"); //first entry must the be the force particleCloud_.probeM().vectorFields_.append("archimedesIBForce"); //first entry must the be the force
particleCloud_.probeM().writeHeader(); particleCloud_.probeM().writeHeader();
@ -83,12 +83,12 @@ ArchimedesIB::ArchimedesIB
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
forceSubM(0).setSwitches(1,true); // treatDEM = true forceSubM(0).setSwitches(SW_TREAT_FORCE_DEM,true); // treatDEM = true
Info << "accounting for Archimedes only on DEM side!" << endl; Info << "accounting for Archimedes only on DEM side!" << endl;
particleCloud_.checkCG(true); particleCloud_.checkCG(true);

View File

@ -59,7 +59,7 @@ BeetstraDrag::BeetstraDrag
scaleDrag_(1.) scaleDrag_(1.)
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "BeetstraDrag.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must be the force particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must be the force
particleCloud_.probeM().vectorFields_.append("Urel"); particleCloud_.probeM().vectorFields_.append("Urel");
particleCloud_.probeM().scalarFields_.append("Rep"); particleCloud_.probeM().scalarFields_.append("Rep");
@ -70,11 +70,11 @@ BeetstraDrag::BeetstraDrag
// init force sub model // init force sub model
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(2,true); // activate implDEM switch forceSubM(0).setSwitchesList(SW_IMPL_FORCE_DEM,true); // activate implDEM switch
forceSubM(0).setSwitchesList(3,true); // activate search for verbose switch forceSubM(0).setSwitchesList(SW_VERBOSE,true); // activate search for verbose switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
forceSubM(0).setSwitchesList(8,true); // activate scalarViscosity switch forceSubM(0).setSwitchesList(SW_SCALAR_VISCOSITY,true); // activate scalarViscosity switch
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
particleCloud_.checkCG(true); particleCloud_.checkCG(true);
@ -97,8 +97,11 @@ BeetstraDrag::~BeetstraDrag()
void BeetstraDrag::setForce() const void BeetstraDrag::setForce() const
{ {
if (scaleDia_ > 1) if (scaleDia_ > 1)
{
Info << "Beetstra using scale = " << scaleDia_ << endl; Info << "Beetstra using scale = " << scaleDia_ << endl;
else if (particleCloud_.cg() > 1){ }
else if (particleCloud_.cg() > 1)
{
scaleDia_=particleCloud_.cg(); scaleDia_=particleCloud_.cg();
Info << "Beetstra using scale from liggghts cg = " << scaleDia_ << endl; Info << "Beetstra using scale from liggghts cg = " << scaleDia_ << endl;
} }

View File

@ -34,8 +34,6 @@ Description
#include "DiFeliceDrag.H" #include "DiFeliceDrag.H"
#include "addToRunTimeSelectionTable.H" #include "addToRunTimeSelectionTable.H"
//#include <mpi.h>
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
namespace Foam namespace Foam
@ -74,7 +72,7 @@ DiFeliceDrag::DiFeliceDrag
scaleDrag_(1.) scaleDrag_(1.)
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "diFeliceDrag.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("dragForce"); // first entry must the be the force particleCloud_.probeM().vectorFields_.append("dragForce"); // first entry must the be the force
particleCloud_.probeM().vectorFields_.append("Urel"); // other are debug particleCloud_.probeM().vectorFields_.append("Urel"); // other are debug
particleCloud_.probeM().scalarFields_.append("Rep"); // other are debug particleCloud_.probeM().scalarFields_.append("Rep"); // other are debug
@ -92,11 +90,11 @@ DiFeliceDrag::DiFeliceDrag
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(2,true); // activate implDEM switch forceSubM(0).setSwitchesList(SW_IMPL_FORCE_DEM,true); // activate implDEM switch
forceSubM(0).setSwitchesList(3,true); // activate search for verbose switch forceSubM(0).setSwitchesList(SW_VERBOSE,true); // activate search for verbose switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
forceSubM(0).setSwitchesList(8,true); // activate scalarViscosity switch forceSubM(0).setSwitchesList(SW_SCALAR_VISCOSITY,true); // activate scalarViscosity switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
@ -114,8 +112,11 @@ DiFeliceDrag::~DiFeliceDrag()
void DiFeliceDrag::setForce() const void DiFeliceDrag::setForce() const
{ {
if (scaleDia_ > 1) if (scaleDia_ > 1)
{
Info << "DiFeliceDrag using scale = " << scaleDia_ << endl; Info << "DiFeliceDrag using scale = " << scaleDia_ << endl;
else if (particleCloud_.cg() > 1){ }
else if (particleCloud_.cg() > 1)
{
scaleDia_=particleCloud_.cg(); scaleDia_=particleCloud_.cg();
Info << "DiFeliceDrag using scale from liggghts cg = " << scaleDia_ << endl; Info << "DiFeliceDrag using scale from liggghts cg = " << scaleDia_ << endl;
} }
@ -144,7 +145,7 @@ void DiFeliceDrag::setForce() const
#include "setupProbeModel.H" #include "setupProbeModel.H"
for(int index = 0;index < particleCloud_.numberOfParticles(); index++) for(int index = 0; index < particleCloud_.numberOfParticles(); ++index)
{ {
cellI = particleCloud_.cellIDs()[index][0]; cellI = particleCloud_.cellIDs()[index][0];
drag = vector(0,0,0); drag = vector(0,0,0);
@ -159,7 +160,8 @@ void DiFeliceDrag::setForce() const
position = particleCloud_.position(index); position = particleCloud_.position(index);
voidfraction = voidfractionInterpolator_.interpolate(position,cellI); voidfraction = voidfractionInterpolator_.interpolate(position,cellI);
Ufluid = UInterpolator_.interpolate(position,cellI); Ufluid = UInterpolator_.interpolate(position,cellI);
}else }
else
{ {
voidfraction = voidfraction_[cellI]; voidfraction = voidfraction_[cellI];
Ufluid = U_[cellI]; Ufluid = U_[cellI];

View File

@ -66,7 +66,7 @@ ErgunStatFines::ErgunStatFines
switchingVoidfraction_(0.8) switchingVoidfraction_(0.8)
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "ErgunStatFines.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must be the force particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must be the force
particleCloud_.probeM().vectorFields_.append("Urel"); particleCloud_.probeM().vectorFields_.append("Urel");
particleCloud_.probeM().scalarFields_.append("Rep"); particleCloud_.probeM().scalarFields_.append("Rep");
@ -77,11 +77,11 @@ ErgunStatFines::ErgunStatFines
// init force sub model // init force sub model
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(2,true); // activate implDEM switch forceSubM(0).setSwitchesList(SW_IMPL_FORCE_DEM,true); // activate implDEM switch
forceSubM(0).setSwitchesList(3,true); // activate search for verbose switch forceSubM(0).setSwitchesList(SW_VERBOSE,true); // activate search for verbose switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
forceSubM(0).setSwitchesList(8,true); // activate scalarViscosity switch forceSubM(0).setSwitchesList(SW_SCALAR_VISCOSITY,true); // activate scalarViscosity switch
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
particleCloud_.checkCG(true); particleCloud_.checkCG(true);
@ -117,7 +117,9 @@ scalar ErgunStatFines::dSauter(label cellI) const
void ErgunStatFines::setForce() const void ErgunStatFines::setForce() const
{ {
if (scaleDia_ > 1) if (scaleDia_ > 1)
{
Info << "ErgunStatFines using scale = " << scaleDia_ << endl; Info << "ErgunStatFines using scale = " << scaleDia_ << endl;
}
else if (particleCloud_.cg() > 1) else if (particleCloud_.cg() > 1)
{ {
scaleDia_=particleCloud_.cg(); scaleDia_=particleCloud_.cg();

View File

@ -65,10 +65,10 @@ FanningDynFines::FanningDynFines
// init force sub model // init force sub model
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(3,true); // activate search for verbose switch forceSubM(0).setSwitchesList(SW_VERBOSE,true); // activate search for verbose switch
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
forceSubM(0).setSwitches(0,true); forceSubM(0).setSwitches(SW_TREAT_FORCE_EXPLICIT,true);
particleCloud_.checkCG(true); particleCloud_.checkCG(true);
if (propsDict_.found("scale")) if (propsDict_.found("scale"))
@ -93,7 +93,9 @@ void FanningDynFines::setForce() const
Info << "Entering force loop of FanningDynFines.\n" << endl; Info << "Entering force loop of FanningDynFines.\n" << endl;
if (scaleDia_ > 1) if (scaleDia_ > 1)
{
Info << "FanningDynFines using scale = " << scaleDia_ << endl; Info << "FanningDynFines using scale = " << scaleDia_ << endl;
}
else if (particleCloud_.cg() > 1) else if (particleCloud_.cg() > 1)
{ {
scaleDia_=particleCloud_.cg(); scaleDia_=particleCloud_.cg();

View File

@ -314,6 +314,7 @@ void FinesFields::calcSource()
scalar dmean(0.0); scalar dmean(0.0);
scalar d1(0.0); scalar d1(0.0);
scalar d2(0.0); scalar d2(0.0);
forAll(Sds_,cellI) forAll(Sds_,cellI)
{ {
// calculate everything in units auf dSauter // calculate everything in units auf dSauter

View File

@ -75,7 +75,7 @@ GidaspowDrag::GidaspowDrag
switchingVoidfraction_(0.8) switchingVoidfraction_(0.8)
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "gidaspowDrag.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("dragForce"); // first entry must be the force particleCloud_.probeM().vectorFields_.append("dragForce"); // first entry must be the force
particleCloud_.probeM().vectorFields_.append("Urel"); particleCloud_.probeM().vectorFields_.append("Urel");
particleCloud_.probeM().scalarFields_.append("Rep"); particleCloud_.probeM().scalarFields_.append("Rep");
@ -86,11 +86,11 @@ GidaspowDrag::GidaspowDrag
// init force sub model // init force sub model
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(2,true); // activate implDEM switch forceSubM(0).setSwitchesList(SW_IMPL_FORCE_DEM,true); // activate implDEM switch
forceSubM(0).setSwitchesList(3,true); // activate search for verbose switch forceSubM(0).setSwitchesList(SW_VERBOSE,true); // activate search for verbose switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
forceSubM(0).setSwitchesList(8,true); // activate scalarViscosity switch forceSubM(0).setSwitchesList(SW_SCALAR_VISCOSITY,true); // activate scalarViscosity switch
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
particleCloud_.checkCG(true); particleCloud_.checkCG(true);
@ -114,9 +114,12 @@ GidaspowDrag::~GidaspowDrag()
void GidaspowDrag::setForce() const void GidaspowDrag::setForce() const
{ {
if (scaleDia_ > 1) if (scaleDia_ > 1.)
{
Info << "Gidaspow using scale = " << scaleDia_ << endl; Info << "Gidaspow using scale = " << scaleDia_ << endl;
else if (particleCloud_.cg() > 1){ }
else if (particleCloud_.cg() > 1.)
{
scaleDia_ = particleCloud_.cg(); scaleDia_ = particleCloud_.cg();
Info << "Gidaspow using scale from liggghts cg = " << scaleDia_ << endl; Info << "Gidaspow using scale from liggghts cg = " << scaleDia_ << endl;
} }
@ -174,8 +177,8 @@ void GidaspowDrag::setForce() const
Ufluid = UInterpolator_.interpolate(position,cellI); Ufluid = UInterpolator_.interpolate(position,cellI);
//Ensure interpolated void fraction to be meaningful //Ensure interpolated void fraction to be meaningful
// Info << " --> voidfraction: " << voidfraction << endl; // Info << " --> voidfraction: " << voidfraction << endl;
if(voidfraction>1.00) voidfraction = 1.0; if (voidfraction > 1.0) voidfraction = 1.0;
if(voidfraction<0.10) voidfraction = 0.10; else if (voidfraction < 0.1) voidfraction = 0.10;
} }
else else
{ {

View File

@ -74,7 +74,7 @@ KochHillDrag::KochHillDrag
scaleDrag_(1.) scaleDrag_(1.)
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "kochHillDrag.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must the be the force particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must the be the force
particleCloud_.probeM().vectorFields_.append("Urel"); //other are debug particleCloud_.probeM().vectorFields_.append("Urel"); //other are debug
particleCloud_.probeM().scalarFields_.append("Rep"); //other are debug particleCloud_.probeM().scalarFields_.append("Rep"); //other are debug
@ -86,12 +86,12 @@ KochHillDrag::KochHillDrag
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(2,true); // activate implDEM switch forceSubM(0).setSwitchesList(SW_IMPL_FORCE_DEM,true); // activate implDEM switch
forceSubM(0).setSwitchesList(3,true); // activate search for verbose switch forceSubM(0).setSwitchesList(SW_VERBOSE,true); // activate search for verbose switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
forceSubM(0).setSwitchesList(7,true); // activate implForceDEMacc switch forceSubM(0).setSwitchesList(SW_IMPL_FORCE_DEM_ACCUMULATED,true); // activate implForceDEMacc switch
forceSubM(0).setSwitchesList(8,true); // activate scalarViscosity switch forceSubM(0).setSwitchesList(SW_SCALAR_VISCOSITY,true); // activate scalarViscosity switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
@ -154,7 +154,7 @@ void KochHillDrag::setForce() const
#include "setupProbeModel.H" #include "setupProbeModel.H"
for (int index=0; index<particleCloud_.numberOfParticles(); index++) for (int index = 0; index<particleCloud_.numberOfParticles(); ++index)
{ {
cellI = particleCloud_.cellIDs()[index][0]; cellI = particleCloud_.cellIDs()[index][0];
drag = vector(0,0,0); drag = vector(0,0,0);
@ -174,8 +174,8 @@ void KochHillDrag::setForce() const
Ufluid = UInterpolator_.interpolate(position,cellI); Ufluid = UInterpolator_.interpolate(position,cellI);
//Ensure interpolated void fraction to be meaningful //Ensure interpolated void fraction to be meaningful
// Info << " --> voidfraction: " << voidfraction << endl; // Info << " --> voidfraction: " << voidfraction << endl;
if (voidfraction > 1.00) voidfraction = 1.00; if (voidfraction > 1.0) voidfraction = 1.0;
if (voidfraction < 0.40) voidfraction = 0.40; else if (voidfraction < 0.4) voidfraction = 0.4;
} }
else else
{ {
@ -230,7 +230,7 @@ void KochHillDrag::setForce() const
if (modelType_ == "B") if (modelType_ == "B")
dragCoefficient /= voidfraction; dragCoefficient /= voidfraction;
if (forceSubM(0).switches()[7]) // implForceDEMaccumulated=true if (forceSubM(0).switches()[SW_IMPL_FORCE_DEM_ACCUMULATED]) // implForceDEMaccumulated=true
{ {
//get drag from the particle itself //get drag from the particle itself
for (int j=0; j<3; j++) drag[j] = particleCloud_.fAccs()[index][j]/couplingInterval; for (int j=0; j<3; j++) drag[j] = particleCloud_.fAccs()[index][j]/couplingInterval;

View File

@ -87,8 +87,8 @@ KochHillRWDrag::KochHillRWDrag
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(2,true); // activate implDEM switch forceSubM(0).setSwitchesList(SW_IMPL_FORCE_DEM,true); // activate implDEM switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
@ -120,8 +120,8 @@ KochHillRWDrag::KochHillRWDrag
KochHillRWDrag::~KochHillRWDrag() KochHillRWDrag::~KochHillRWDrag()
{ {
delete partTime_; particleCloud_.dataExchangeM().destroy(partTime_, 1);
delete partUfluct_; particleCloud_.dataExchangeM().destroy(partUfluct_, 3);
} }
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
@ -195,7 +195,7 @@ void KochHillRWDrag::setForce() const
//Info << "RW-TEST: We are in setForce() at t = " << t << endl; // TEST-Output //Info << "RW-TEST: We are in setForce() at t = " << t << endl; // TEST-Output
for (int index=0; index<particleCloud_.numberOfParticles(); index++) for (int index = 0; index<particleCloud_.numberOfParticles(); ++index)
{ {
//if (mask[index][0]) //if (mask[index][0])
//{ //{
@ -217,8 +217,8 @@ void KochHillRWDrag::setForce() const
Ufluid = UInterpolator_.interpolate(position,cellI); Ufluid = UInterpolator_.interpolate(position,cellI);
//Ensure interpolated void fraction to be meaningful //Ensure interpolated void fraction to be meaningful
// Info << " --> voidfraction: " << voidfraction << endl; // Info << " --> voidfraction: " << voidfraction << endl;
if (voidfraction > 1.00) voidfraction = 1.00; if (voidfraction > 1.0) voidfraction = 1.0;
if (voidfraction < 0.40) voidfraction = 0.40; else if (voidfraction < 0.4) voidfraction = 0.4;
} }
else else
{ {

View File

@ -89,9 +89,9 @@ LaEuScalarTemp::LaEuScalarTemp
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(3,true); // activate search for verbose switch forceSubM(0).setSwitchesList(SW_VERBOSE,true); // activate search for verbose switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
forceSubM(0).setSwitchesList(8,true); // activate scalarViscosity switch forceSubM(0).setSwitchesList(SW_SCALAR_VISCOSITY,true); // activate scalarViscosity switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
@ -105,8 +105,8 @@ LaEuScalarTemp::LaEuScalarTemp
LaEuScalarTemp::~LaEuScalarTemp() LaEuScalarTemp::~LaEuScalarTemp()
{ {
delete partTemp_; particleCloud_.dataExchangeM().destroy(partTemp_,1);
delete partHeatFlux_; particleCloud_.dataExchangeM().destroy(partHeatFlux_,1);
} }
// * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * //

View File

@ -73,16 +73,16 @@ MeiLift::MeiLift
// init force sub model // init force sub model
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(3,true); // activate search for verbose switch forceSubM(0).setSwitchesList(SW_VERBOSE,true); // activate search for verbose switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
forceSubM(0).setSwitchesList(8,true); // activate scalarViscosity switch forceSubM(0).setSwitchesList(SW_SCALAR_VISCOSITY,true); // activate scalarViscosity switch
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
particleCloud_.checkCG(false); particleCloud_.checkCG(false);
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "meiLift.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("liftForce"); //first entry must the be the force particleCloud_.probeM().vectorFields_.append("liftForce"); //first entry must the be the force
particleCloud_.probeM().vectorFields_.append("Urel"); //other are debug particleCloud_.probeM().vectorFields_.append("Urel"); //other are debug
particleCloud_.probeM().vectorFields_.append("vorticity"); //other are debug particleCloud_.probeM().vectorFields_.append("vorticity"); //other are debug
@ -134,7 +134,7 @@ void MeiLift::setForce() const
#include "setupProbeModel.H" #include "setupProbeModel.H"
for(int index = 0;index < particleCloud_.numberOfParticles(); index++) for(int index = 0; index < particleCloud_.numberOfParticles(); ++index)
{ {
//if(mask[index][0]) //if(mask[index][0])
//{ //{

View File

@ -69,7 +69,7 @@ SchillerNaumannDrag::SchillerNaumannDrag
U_(sm.mesh().lookupObject<volVectorField> (velFieldName_)) U_(sm.mesh().lookupObject<volVectorField> (velFieldName_))
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "schillerNaumannDrag.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must the be the force particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must the be the force
particleCloud_.probeM().vectorFields_.append("Urel"); //other are debug particleCloud_.probeM().vectorFields_.append("Urel"); //other are debug
particleCloud_.probeM().scalarFields_.append("Rep"); //other are debug particleCloud_.probeM().scalarFields_.append("Rep"); //other are debug
@ -82,7 +82,7 @@ SchillerNaumannDrag::SchillerNaumannDrag
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();

View File

@ -72,7 +72,7 @@ ShirgaonkarIB::ShirgaonkarIB
p_(sm.mesh().lookupObject<volScalarField> (pressureFieldName_)) p_(sm.mesh().lookupObject<volScalarField> (pressureFieldName_))
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "shirgaonkarIB.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must the be the force particleCloud_.probeM().vectorFields_.append("dragForce"); //first entry must the be the force
particleCloud_.probeM().writeHeader(); particleCloud_.probeM().writeHeader();
@ -89,7 +89,7 @@ ShirgaonkarIB::ShirgaonkarIB
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();

View File

@ -113,11 +113,12 @@ dSauter::dSauter
dSauter::~dSauter() dSauter::~dSauter()
{ {
delete d2_; particleCloud_.dataExchangeM().destroy(d2_,1);
delete d3_; particleCloud_.dataExchangeM().destroy(d3_,1);
} }
// * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * //
void dSauter::allocateMyArrays() const void dSauter::allocateMyArrays() const
{ {
// get memory for 2d arrays // get memory for 2d arrays
@ -125,12 +126,15 @@ void dSauter::allocateMyArrays() const
particleCloud_.dataExchangeM().allocateArray(d2_,initVal,1); // field/initVal/with/lenghtFromLigghts particleCloud_.dataExchangeM().allocateArray(d2_,initVal,1); // field/initVal/with/lenghtFromLigghts
particleCloud_.dataExchangeM().allocateArray(d3_,initVal,1); particleCloud_.dataExchangeM().allocateArray(d3_,initVal,1);
} }
// * * * * * * * * * * * * * * * public Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * public Member Functions * * * * * * * * * * * * * //
void dSauter::setForce() const void dSauter::setForce() const
{ {
if (scaleDia_ > 1) if (scaleDia_ > 1)
{
Info << "dSauter using scaleCG = " << scaleDia_ << endl; Info << "dSauter using scaleCG = " << scaleDia_ << endl;
}
else if (particleCloud_.cg() > 1) else if (particleCloud_.cg() > 1)
{ {
scaleDia_ = particleCloud_.cg(); scaleDia_ = particleCloud_.cg();

View File

@ -88,14 +88,16 @@ forceModel::forceModel
probeIt_(sm.probeM().active()), probeIt_(sm.probeM().active()),
requiresEx_(false), requiresEx_(false),
forceSubModels_(0), forceSubModels_(0),
forceSubModel_(new autoPtr<forceSubModel>[nrForceSubModels()]) forceSubModel_(NULL)
{} {}
// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * //
forceModel::~forceModel() forceModel::~forceModel()
{} {
delete [] forceSubModel_;
}
// * * * * * * * * * * * * * * * * Member Fct * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * Member Fct * * * * * * * * * * * * * * * //
/*tmp<volScalarField> forceModel::provideScalarField() /*tmp<volScalarField> forceModel::provideScalarField()

View File

@ -131,7 +131,7 @@ public:
virtual void manipulateScalarField(volScalarField&) const; virtual void manipulateScalarField(volScalarField&) const;
// Access // Access
word modelType() { return modelType_; } const word& modelType() const { return modelType_; }
inline volVectorField& impParticleForces() const { return impParticleForces_; } inline volVectorField& impParticleForces() const { return impParticleForces_; }
@ -147,7 +147,7 @@ public:
inline double ** fluidVel() const { return particleCloud_.fluidVel_; } inline double ** fluidVel() const { return particleCloud_.fluidVel_; }
inline const bool& coupleForce() const { return coupleForce_; } inline bool coupleForce() const { return coupleForce_; }
virtual inline bool& requiresEx() { return requiresEx_; } virtual inline bool& requiresEx() { return requiresEx_; }
@ -157,9 +157,9 @@ public:
inline const wordList& forceSubModels() { return forceSubModels_; } inline const wordList& forceSubModels() { return forceSubModels_; }
inline const forceSubModel& forceSubM(int i) const { return forceSubModel_[i]; } inline forceSubModel& forceSubM(int i) const { return forceSubModel_[i](); }
inline int nrForceSubModels(){ return forceSubModels_.size(); } inline int nrForceSubModels() const { return forceSubModels_.size(); }
void setForceSubModels(dictionary& dict); void setForceSubModels(dictionary& dict);
}; };

View File

@ -62,7 +62,7 @@ ScaleForce::~ScaleForce()
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
void ScaleForce::partToArray void ScaleForce::partToArray
( (
label& index, label index,
vector& dragTot, vector& dragTot,
const vector& dragEx, const vector& dragEx,
const vector& Ufluid, const vector& Ufluid,

View File

@ -71,7 +71,7 @@ public:
// Member Functions // Member Functions
void partToArray(label&, vector&, const vector&, const vector& Ufluid=vector::zero, scalar Cd=scalar(0)) const; void partToArray(label, vector&, const vector&, const vector& Ufluid=vector::zero, scalar Cd=scalar(0)) const;
word myType() const{return typeName; }; word myType() const{return typeName; };
}; };

View File

@ -59,7 +59,7 @@ forceSubModel::forceSubModel
dict_(dict), dict_(dict),
particleCloud_(sm), particleCloud_(sm),
forceModel_(fm), forceModel_(fm),
nrDefaultSwitches_(9), // !!! nrDefaultSwitches_(SW_MAX),
switchesNameList_(nrDefaultSwitches_), switchesNameList_(nrDefaultSwitches_),
switchesList_(nrDefaultSwitches_), switchesList_(nrDefaultSwitches_),
switches_(nrDefaultSwitches_), switches_(nrDefaultSwitches_),
@ -106,16 +106,15 @@ forceSubModel::forceSubModel
rho_(sm.mesh().lookupObject<volScalarField> (densityFieldName_)) rho_(sm.mesh().lookupObject<volScalarField> (densityFieldName_))
{ {
// init standard switch list // init standard switch list
int iCounter(0); switchesNameList_[SW_TREAT_FORCE_EXPLICIT] = "treatForceExplicit";
switchesNameList_[iCounter]="treatForceExplicit"; iCounter++; //0 switchesNameList_[SW_TREAT_FORCE_DEM] = "treatForceDEM";
switchesNameList_[iCounter]="treatForceDEM";iCounter++; //1 switchesNameList_[SW_IMPL_FORCE_DEM] = "implForceDEM";
switchesNameList_[iCounter]="implForceDEM";iCounter++; //2 switchesNameList_[SW_VERBOSE] = "verbose";
switchesNameList_[iCounter]="verbose";iCounter++; //3 switchesNameList_[SW_INTERPOLATION] = "interpolation";
switchesNameList_[iCounter]="interpolation";iCounter++; //4 switchesNameList_[SW_FILTERED_DRAG_MODEL] ="useFilteredDragModel";
switchesNameList_[iCounter]="useFilteredDragModel";iCounter++; //5 switchesNameList_[SW_PARCEL_SIZE_DEPENDENT_FILTERED_DRAG] = "useParcelSizeDependentFilteredDrag";
switchesNameList_[iCounter]="useParcelSizeDependentFilteredDrag";iCounter++; //6 switchesNameList_[SW_IMPL_FORCE_DEM_ACCUMULATED] = "implForceDEMaccumulated";
switchesNameList_[iCounter]="implForceDEMaccumulated";iCounter++; //7 switchesNameList_[SW_SCALAR_VISCOSITY] = "scalarViscosity";
switchesNameList_[iCounter]="scalarViscosity";iCounter++; //8
// sanity check of what is defined above // sanity check of what is defined above
if(switchesNameList_.size() != nrDefaultSwitches_) if(switchesNameList_.size() != nrDefaultSwitches_)
@ -131,7 +130,7 @@ forceSubModel::~forceSubModel()
// * * * * * * * * * * * * * * * * Member Fct * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * Member Fct * * * * * * * * * * * * * * * //
void forceSubModel::partToArray void forceSubModel::partToArray
( (
label& index, label index,
vector& dragTot, vector& dragTot,
const vector& dragEx, const vector& dragEx,
const vector& Ufluid, const vector& Ufluid,
@ -139,9 +138,9 @@ void forceSubModel::partToArray
) const ) const
{ {
// forces for CFD // forces for CFD
if(!switches_[1])// !treatDEM if(!switches_[SW_TREAT_FORCE_DEM])// !treatDEM
{ {
if(switches_[0]) // treatExplicit if(switches_[SW_TREAT_FORCE_EXPLICIT]) // treatExplicit
{ {
for(int j=0;j<3;j++) for(int j=0;j<3;j++)
myForceM().expForces()[index][j] += dragTot[j]; myForceM().expForces()[index][j] += dragTot[j];
@ -157,7 +156,7 @@ void forceSubModel::partToArray
} }
// forces for DEM // forces for DEM
if(switches_[2]) // implForceDEM if(switches_[SW_IMPL_FORCE_DEM]) // implForceDEM
{ {
for(int j=0;j<3;j++) for(int j=0;j<3;j++)
myForceM().fluidVel()[index][j]=Ufluid[j]; myForceM().fluidVel()[index][j]=Ufluid[j];
@ -191,7 +190,7 @@ void forceSubModel::explicitCorr
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
void forceSubModel::readSwitches() const void forceSubModel::readSwitches()
{ {
Info << "\nreading switches for forceSubModel:" << myType() << endl; Info << "\nreading switches for forceSubModel:" << myType() << endl;
forAll(switchesNameList_,i) forAll(switchesNameList_,i)
@ -207,7 +206,7 @@ void forceSubModel::readSwitches() const
} }
Info << endl; Info << endl;
if(switches_[2]) // implForceDEM=true if(switches_[SW_IMPL_FORCE_DEM]) // implForceDEM=true
{ {
// communicate implForceDEM to particleCloud // communicate implForceDEM to particleCloud
particleCloud_.impDEMdrag_ = true; particleCloud_.impDEMdrag_ = true;
@ -216,7 +215,7 @@ void forceSubModel::readSwitches() const
// This can work if the accumulator is used, but is explicitely applied on the CFD side // This can work if the accumulator is used, but is explicitely applied on the CFD side
// Sanity check is therefore not necessary here // Sanity check is therefore not necessary here
/* /*
if(switches_[0]) // treatExplicit=true if(switches_[SW_TREAT_FORCE_EXPLICIT]) // treatExplicit=true
{ {
FatalError << "Please check your settings, treatExplicit together with implForceDEM does not work!." FatalError << "Please check your settings, treatExplicit together with implForceDEM does not work!."
<< abort(FatalError); << abort(FatalError);
@ -224,20 +223,20 @@ void forceSubModel::readSwitches() const
*/ */
} }
if(switches_[7]) // implForceDEMaccumulated=true if(switches_[SW_IMPL_FORCE_DEM_ACCUMULATED]) // implForceDEMaccumulated=true
{ {
// sanity check for implForceDEMaccumulated // sanity check for implForceDEMaccumulated
if(!switches_[2]) //implForceDEM=false if(!switches_[SW_IMPL_FORCE_DEM]) //implForceDEM=false
{ {
Warning<< "please check your settings, implForceDEMaccumulated without implForceDEM does not work! (using implForceDEMaccumulated=false)" << endl; Warning<< "please check your settings, implForceDEMaccumulated without implForceDEM does not work! (using implForceDEMaccumulated=false)" << endl;
switches_[3]=false; switches_[SW_VERBOSE] = false;
}else }else
{ {
particleCloud_.impDEMdragAcc_ = true; particleCloud_.impDEMdragAcc_ = true;
} }
} }
if(switches_[8]) // scalarViscosity=true if(switches_[SW_SCALAR_VISCOSITY]) // scalarViscosity=true
{ {
Info << "Using a constant viscosity for this force model." << endl; Info << "Using a constant viscosity for this force model." << endl;
dimensionedScalar nu0_("nu", dimensionSet(0, 2, -1, 0, 0), dict_.lookup("nu")); dimensionedScalar nu0_("nu", dimensionSet(0, 2, -1, 0, 0), dict_.lookup("nu"));
@ -274,7 +273,7 @@ const volScalarField& forceSubModel::nuField() const
nu_=particleCloud_.turbulence().mu() / rho_; nu_=particleCloud_.turbulence().mu() / rho_;
return nu_; return nu_;
#else #else
if(switches_[8]) // scalarViscosity=true if(switches_[SW_SCALAR_VISCOSITY]) // scalarViscosity=true
return nu_; return nu_;
else else
return particleCloud_.turbulence().nu(); return particleCloud_.turbulence().nu();
@ -289,7 +288,7 @@ const volScalarField& forceSubModel::muField() const
// passing the ref to nu*rho will not work->generate a mu_ field like nu_ // passing the ref to nu*rho will not work->generate a mu_ field like nu_
FatalError << "implementation not complete!" << abort(FatalError); FatalError << "implementation not complete!" << abort(FatalError);
if(switches_[8]) // scalarViscosity=true if(switches_[SW_SCALAR_VISCOSITY]) // scalarViscosity=true
return nu_*rho_; return nu_*rho_;
else else
return particleCloud_.turbulence().nu()*rho_; return particleCloud_.turbulence().nu()*rho_;

View File

@ -47,6 +47,19 @@ SourceFiles
namespace Foam namespace Foam
{ {
enum {
SW_TREAT_FORCE_EXPLICIT = 0,
SW_TREAT_FORCE_DEM,
SW_IMPL_FORCE_DEM,
SW_VERBOSE,
SW_INTERPOLATION,
SW_FILTERED_DRAG_MODEL,
SW_PARCEL_SIZE_DEPENDENT_FILTERED_DRAG,
SW_IMPL_FORCE_DEM_ACCUMULATED,
SW_SCALAR_VISCOSITY,
SW_MAX
};
/*---------------------------------------------------------------------------*\ /*---------------------------------------------------------------------------*\
Class forceSubModel Declaration Class forceSubModel Declaration
\*---------------------------------------------------------------------------*/ \*---------------------------------------------------------------------------*/
@ -67,9 +80,9 @@ protected:
wordList switchesNameList_; // names of switches available wordList switchesNameList_; // names of switches available
mutable List<Switch> switchesList_; // switches which are requested in dict List<Switch> switchesList_; // switches which are requested from dict
mutable List<Switch> switches_; List<Switch> switches_; // switch status
mutable volScalarField nu_; mutable volScalarField nu_;
@ -130,19 +143,19 @@ public:
// Member Functions // Member Functions
virtual void partToArray(label&, vector&, const vector&, const vector& Ufluid=vector::zero, scalar Cd=scalar(0)) const; virtual void partToArray(label, vector&, const vector&, const vector& Ufluid=vector::zero, scalar Cd=scalar(0)) const;
virtual void explicitCorr(vector&, vector&, scalar&, vector&, const vector&, vector&, const vector&, bool,label index=100) const; virtual void explicitCorr(vector&, vector&, scalar&, vector&, const vector&, vector&, const vector&, bool,label index=100) const;
// Access // Access
inline bool verbose() const { return switches_[3]; } inline bool verbose() const { return switches_[SW_VERBOSE]; }
inline bool interpolation() const { return switches_[4]; } inline bool interpolation() const { return switches_[SW_INTERPOLATION]; }
inline bool useFilteredDragModel() const { return switches_[5]; } inline bool useFilteredDragModel() const { return switches_[SW_FILTERED_DRAG_MODEL]; }
inline bool useParcelSizeDependentFilteredDrag() const { return switches_[6]; } inline bool useParcelSizeDependentFilteredDrag() const { return switches_[SW_PARCEL_SIZE_DEPENDENT_FILTERED_DRAG]; }
virtual word myType() const = 0; virtual word myType() const = 0;
@ -152,13 +165,11 @@ public:
inline const wordList& switchesNameList() const { return switchesNameList_; } inline const wordList& switchesNameList() const { return switchesNameList_; }
void setSwitchesList(label i, bool v) const { switchesList_[i] = v;} void setSwitchesList(label i, Switch v) { switchesList_[i] = v; }
void setSwitches(label i, Switch v) const { switches_[i] = v;} void setSwitches(label i, Switch v) { switches_[i] = v; }
virtual void readSwitches() const; virtual void readSwitches();
const label& nrDefaultSwitches() const {return nrDefaultSwitches_;}
const volScalarField& nuField() const; const volScalarField& nuField() const;

View File

@ -97,7 +97,7 @@ scaleForceBoundary::~scaleForceBoundary()
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
void scaleForceBoundary::partToArray void scaleForceBoundary::partToArray
( (
label& index, label index,
vector& dragTot, vector& dragTot,
const vector& dragEx, const vector& dragEx,
const vector& Ufluid, const vector& Ufluid,

View File

@ -83,9 +83,9 @@ public:
// Member Functions // Member Functions
void partToArray(label&, vector&, const vector&, const vector& Ufluid=vector::zero, scalar Cd=scalar(0)) const; void partToArray(label, vector&, const vector&, const vector& Ufluid=vector::zero, scalar Cd=scalar(0)) const;
word myType() const{return typeName; }; word myType() const {return typeName; }
}; };

View File

@ -74,9 +74,9 @@ gradPForce::gradPForce
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(1,true); // activate treatForceDEM switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_DEM,true); // activate treatForceDEM switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
@ -84,23 +84,27 @@ gradPForce::gradPForce
if (modelType_ == "B") if (modelType_ == "B")
{ {
FatalError <<"using model gradPForce with model type B is not valid\n" << abort(FatalError); FatalError <<"using model gradPForce with model type B is not valid\n" << abort(FatalError);
}else if (modelType_ == "Bfull") }
else if (modelType_ == "Bfull")
{ {
if(forceSubM(0).switches()[1]) if(forceSubM(0).switches()[SW_TREAT_FORCE_DEM])
{ {
Info << "Using treatForceDEM false!" << endl; Info << "Using treatForceDEM false!" << endl;
forceSubM(0).setSwitches(1,false); // treatForceDEM = false forceSubM(0).setSwitches(SW_TREAT_FORCE_DEM,false); // treatForceDEM = false
} }
}else // modelType_=="A" }
else // modelType_=="A"
{ {
if(!forceSubM(0).switches()[1]) if(!forceSubM(0).switches()[SW_TREAT_FORCE_DEM])
{ {
Info << "Using treatForceDEM true!" << endl; Info << "Using treatForceDEM true!" << endl;
forceSubM(0).setSwitches(1,true); // treatForceDEM = true forceSubM(0).setSwitches(SW_TREAT_FORCE_DEM,true); // treatForceDEM = true
} }
} }
if (propsDict_.found("useU")) useU_=true; if (propsDict_.found("useU"))
useU_ = true;
if (propsDict_.found("useAddedMass")) if (propsDict_.found("useAddedMass"))
{ {
addedMassCoeff_ = readScalar(propsDict_.lookup("useAddedMass")); addedMassCoeff_ = readScalar(propsDict_.lookup("useAddedMass"));
@ -113,7 +117,7 @@ gradPForce::gradPForce
particleCloud_.checkCG(true); particleCloud_.checkCG(true);
particleCloud_.probeM().initialize(typeName, "gradP.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("gradPForce"); //first entry must the be the force particleCloud_.probeM().vectorFields_.append("gradPForce"); //first entry must the be the force
particleCloud_.probeM().scalarFields_.append("Vs"); particleCloud_.probeM().scalarFields_.append("Vs");
particleCloud_.probeM().scalarFields_.append("rho"); particleCloud_.probeM().scalarFields_.append("rho");
@ -152,7 +156,7 @@ void gradPForce::setForce() const
#include "setupProbeModel.H" #include "setupProbeModel.H"
for(int index = 0;index < particleCloud_.numberOfParticles(); index++) for(int index = 0; index < particleCloud_.numberOfParticles(); ++index)
{ {
//if(mask[index][0]) //if(mask[index][0])
//{ //{
@ -166,7 +170,8 @@ void gradPForce::setForce() const
if (forceSubM(0).interpolation()) // use intepolated values for alpha (normally off!!!) if (forceSubM(0).interpolation()) // use intepolated values for alpha (normally off!!!)
{ {
gradP = gradPInterpolator_.interpolate(position,cellI); gradP = gradPInterpolator_.interpolate(position,cellI);
}else }
else
{ {
gradP = gradPField[cellI]; gradP = gradPField[cellI];
} }

View File

@ -82,7 +82,7 @@ granKineticEnergy::granKineticEnergy
granKineticEnergy::~granKineticEnergy() granKineticEnergy::~granKineticEnergy()
{ {
delete vfluc_; particleCloud_.dataExchangeM().destroy(vfluc_,1);
} }
// * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * private Member Functions * * * * * * * * * * * * * //

View File

@ -83,7 +83,7 @@ interface::interface
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();

View File

@ -72,7 +72,7 @@ noDrag::noDrag
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
@ -98,7 +98,7 @@ void noDrag::setForce() const
// Do nothing // Do nothing
Info << "noDrag::setForce" << endl; Info << "noDrag::setForce" << endl;
label cellI=0; label cellI=0;
bool treatExplicit=forceSubM(0).switches()[0]; bool treatExplicit = forceSubM(0).switches()[SW_TREAT_FORCE_EXPLICIT];
for(int index = 0;index < particleCloud_.numberOfParticles(); ++index) for(int index = 0;index < particleCloud_.numberOfParticles(); ++index)
{ {
cellI = particleCloud_.cellIDs()[index][0]; cellI = particleCloud_.cellIDs()[index][0];

View File

@ -83,8 +83,8 @@ virtualMassForce::virtualMassForce
// init force sub model // init force sub model
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
//Extra switches/settings //Extra switches/settings
@ -92,9 +92,11 @@ virtualMassForce::virtualMassForce
{ {
splitUrelCalculation_ = readBool(propsDict_.lookup("splitUrelCalculation")); splitUrelCalculation_ = readBool(propsDict_.lookup("splitUrelCalculation"));
if(splitUrelCalculation_) if(splitUrelCalculation_)
{
Info << "Virtual mass model: will split the Urel calculation\n"; Info << "Virtual mass model: will split the Urel calculation\n";
Info << "WARNING: be sure that LIGGGHTS integration takes ddtv_p implicitly into account! \n"; Info << "WARNING: be sure that LIGGGHTS integration takes ddtv_p implicitly into account! \n";
} }
}
if(propsDict_.found("Cadd")) if(propsDict_.found("Cadd"))
{ {
Cadd_ = readScalar(propsDict_.lookup("Cadd")); Cadd_ = readScalar(propsDict_.lookup("Cadd"));
@ -104,7 +106,7 @@ virtualMassForce::virtualMassForce
particleCloud_.checkCG(true); particleCloud_.checkCG(true);
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "virtualMass.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("virtualMassForce"); //first entry must the be the force particleCloud_.probeM().vectorFields_.append("virtualMassForce"); //first entry must the be the force
particleCloud_.probeM().vectorFields_.append("Urel"); particleCloud_.probeM().vectorFields_.append("Urel");
particleCloud_.probeM().vectorFields_.append("UrelOld"); particleCloud_.probeM().vectorFields_.append("UrelOld");
@ -119,7 +121,7 @@ virtualMassForce::virtualMassForce
virtualMassForce::~virtualMassForce() virtualMassForce::~virtualMassForce()
{ {
delete UrelOld_; particleCloud_.dataExchangeM().destroy(UrelOld_,3);
} }

View File

@ -71,10 +71,10 @@ viscForce::viscForce
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(1,true); // activate treatForceDEM switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_DEM,true); // activate treatForceDEM switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
forceSubM(0).setSwitchesList(8,true); // activate scalarViscosity switch forceSubM(0).setSwitchesList(SW_SCALAR_VISCOSITY,true); // activate scalarViscosity switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
@ -84,18 +84,18 @@ viscForce::viscForce
FatalError <<"using model viscForce with model type B is not valid\n" << abort(FatalError); FatalError <<"using model viscForce with model type B is not valid\n" << abort(FatalError);
}else if (modelType_ == "Bfull") }else if (modelType_ == "Bfull")
{ {
if(forceSubM(0).switches()[1]) if(forceSubM(0).switches()[SW_TREAT_FORCE_DEM])
{ {
Info << "Using treatForceDEM false!" << endl; Info << "Using treatForceDEM false!" << endl;
forceSubM(0).setSwitches(1,false); // treatForceDEM = false forceSubM(0).setSwitches(SW_TREAT_FORCE_DEM,false); // treatForceDEM = false
} }
}else // modelType_=="A" }else // modelType_=="A"
{ {
if(!forceSubM(0).switches()[1]) if(!forceSubM(0).switches()[SW_TREAT_FORCE_DEM])
{ {
Info << "Using treatForceDEM true!" << endl; Info << "Using treatForceDEM true!" << endl;
forceSubM(0).setSwitches(1,true); // treatForceDEM = true forceSubM(0).setSwitches(SW_TREAT_FORCE_DEM,true); // treatForceDEM = true
} }
} }
@ -109,7 +109,7 @@ viscForce::viscForce
particleCloud_.checkCG(true); particleCloud_.checkCG(true);
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "visc.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("viscForce"); //first entry must the be the force particleCloud_.probeM().vectorFields_.append("viscForce"); //first entry must the be the force
particleCloud_.probeM().scalarFields_.append("Vs"); particleCloud_.probeM().scalarFields_.append("Vs");
particleCloud_.probeM().writeHeader(); particleCloud_.probeM().writeHeader();

View File

@ -75,7 +75,7 @@ DiFeliceDragMS::DiFeliceDragMS
//dH_(readScalar(propsDict_.lookup("hydraulicDiameter"))) //dH_(readScalar(propsDict_.lookup("hydraulicDiameter")))
{ {
//Append the field names to be probed //Append the field names to be probed
particleCloud_.probeM().initialize(typeName, "diFeliceDrag.logDat"); particleCloud_.probeM().initialize(typeName, typeName+".logDat");
particleCloud_.probeM().vectorFields_.append("dragForce"); // first entry must the be the force particleCloud_.probeM().vectorFields_.append("dragForce"); // first entry must the be the force
particleCloud_.probeM().vectorFields_.append("Urel"); // other are debug particleCloud_.probeM().vectorFields_.append("Urel"); // other are debug
particleCloud_.probeM().scalarFields_.append("Rep"); // other are debug particleCloud_.probeM().scalarFields_.append("Rep"); // other are debug
@ -87,9 +87,9 @@ DiFeliceDragMS::DiFeliceDragMS
setForceSubModels(propsDict_); setForceSubModels(propsDict_);
// define switches which can be read from dict // define switches which can be read from dict
forceSubM(0).setSwitchesList(0,true); // activate treatExplicit switch forceSubM(0).setSwitchesList(SW_TREAT_FORCE_EXPLICIT,true); // activate treatExplicit switch
forceSubM(0).setSwitchesList(3,true); // activate search for verbose switch forceSubM(0).setSwitchesList(SW_VERBOSE,true); // activate search for verbose switch
forceSubM(0).setSwitchesList(4,true); // activate search for interpolate switch forceSubM(0).setSwitchesList(SW_INTERPOLATION,true); // activate search for interpolate switch
// read those switches defined above, if provided in dict // read those switches defined above, if provided in dict
forceSubM(0).readSwitches(); forceSubM(0).readSwitches();
@ -98,6 +98,7 @@ DiFeliceDragMS::DiFeliceDragMS
{ {
Warning << " interpolation is commented for this force model - it seems to be unstable with AMI!" << endl; Warning << " interpolation is commented for this force model - it seems to be unstable with AMI!" << endl;
} }
if (propsDict_.found("splitImplicitExplicit")) if (propsDict_.found("splitImplicitExplicit"))
{ {
Info << "will split implicit / explicit force contributions." << endl; Info << "will split implicit / explicit force contributions." << endl;
@ -124,7 +125,7 @@ void DiFeliceDragMS::setForce() const
const volScalarField& nufField = forceSubM(0).nuField(); const volScalarField& nufField = forceSubM(0).nuField();
const volScalarField& rhoField = forceSubM(0).rhoField(); const volScalarField& rhoField = forceSubM(0).rhoField();
vector position(0,0,0); //vector position(0,0,0);
scalar voidfraction(1); scalar voidfraction(1);
vector Ufluid(0,0,0); vector Ufluid(0,0,0);
vector drag(0,0,0); vector drag(0,0,0);
@ -148,7 +149,7 @@ void DiFeliceDragMS::setForce() const
#include "setupProbeModel.H" #include "setupProbeModel.H"
for(int index = 0;index < cloudRefMS().numberOfClumps(); index++) for(int index = 0; index < cloudRefMS().numberOfClumps(); ++index)
{ {
//if(mask[index][0]) // would have to be transformed from body ID to particle ID //if(mask[index][0]) // would have to be transformed from body ID to particle ID
@ -246,8 +247,13 @@ void DiFeliceDragMS::setForce() const
particleCloud_.probeM().writeProbe(index, sValues, vValues); particleCloud_.probeM().writeProbe(index, sValues, vValues);
} }
} }
// set force on bodies // set force on bodies
if(forceSubM(0).switches()[0]) for(int j=0;j<3;j++) cloudRefMS().expForcesCM()[index][j] += drag[j]; if (forceSubM(0).switches()[SW_TREAT_FORCE_EXPLICIT])
{
for(int j=0;j<3;j++)
cloudRefMS().expForcesCM()[index][j] += drag[j];
}
else //implicit treatment, taking explicit force contribution into account else //implicit treatment, taking explicit force contribution into account
{ {
for(int j=0;j<3;j++) for(int j=0;j<3;j++)
@ -256,7 +262,9 @@ void DiFeliceDragMS::setForce() const
cloudRefMS().expForcesCM()[index][j] += dragExplicit[j]; cloudRefMS().expForcesCM()[index][j] += dragExplicit[j];
} }
} }
for(int j=0;j<3;j++) cloudRefMS().DEMForcesCM()[index][j] += drag[j];
for(int j=0;j<3;j++)
cloudRefMS().DEMForcesCM()[index][j] += drag[j];
//} //}
} }

View File

@ -108,32 +108,9 @@ explicitCouple::~explicitCouple()
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
tmp<volVectorField> explicitCouple::expMomSource() const tmp<volVectorField> explicitCouple::expMomSource() const
{ {
tmp<volVectorField> tsource
(
new volVectorField
(
IOobject
(
"f_explicitCouple",
particleCloud_.mesh().time().timeName(),
particleCloud_.mesh(),
IOobject::NO_READ,
IOobject::NO_WRITE
),
particleCloud_.mesh(),
dimensionedVector
(
"zero",
dimensionSet(1, -2, -2, 0, 0), // N/m3
vector::zero
),
"zeroGradient"
)
);
scalar tsf = particleCloud_.dataExchangeM().timeStepFraction(); scalar tsf = particleCloud_.dataExchangeM().timeStepFraction();
if(1-tsf < 1e-4) //tsf==1 if (1. - tsf < 1e-4) //tsf==1
{ {
// calc fNext // calc fNext
forAll(fNext_,cellI) forAll(fNext_,cellI)
@ -147,21 +124,27 @@ tmp<volVectorField> explicitCouple::expMomSource() const
if (magF > fLimit_[i]) fNext_[cellI][i] *= fLimit_[i]/magF; if (magF > fLimit_[i]) fNext_[cellI][i] *= fLimit_[i]/magF;
} }
} }
tsource.ref() = fPrev_; return tmp<volVectorField>
}else (
{ new volVectorField("f_explicitCouple", fPrev_)
tsource.ref() = (1 - tsf) * fPrev_ + tsf * fNext_; );
}
else
{
return tmp<volVectorField>
(
new volVectorField("f_explicitCouple", (1. - tsf) * fPrev_ + tsf * fNext_)
);
} }
return tsource;
} }
void Foam::explicitCouple::resetMomSourceField() const void explicitCouple::resetMomSourceField() const
{ {
fPrev_.ref() = fNext_.ref(); fPrev_.ref() = fNext_.ref();
fNext_.primitiveFieldRef() = vector::zero; fNext_.primitiveFieldRef() = vector::zero;
} }
inline vector Foam::explicitCouple::arrayToField(label cellI) const inline vector explicitCouple::arrayToField(label cellI) const
{ {
return particleCloud_.forceM(0).expParticleForces()[cellI] / particleCloud_.mesh().V()[cellI]; return particleCloud_.forceM(0).expParticleForces()[cellI] / particleCloud_.mesh().V()[cellI];
} }

View File

@ -122,35 +122,14 @@ implicitCouple::~implicitCouple()
tmp<volScalarField> implicitCouple::impMomSource() const tmp<volScalarField> implicitCouple::impMomSource() const
{ {
tmp<volScalarField> tsource
(
new volScalarField
(
IOobject
(
"Ksl_implicitCouple",
particleCloud_.mesh().time().timeName(),
particleCloud_.mesh(),
IOobject::NO_READ,
IOobject::NO_WRITE
),
particleCloud_.mesh(),
dimensionedScalar
(
"zero",
dimensionSet(1, -3, -1, 0, 0), // N/m3 / m/s
0
)
)
);
scalar tsf = particleCloud_.dataExchangeM().timeStepFraction(); scalar tsf = particleCloud_.dataExchangeM().timeStepFraction();
// calc Ksl // calc Ksl
if (1. - tsf < 1e-4) //tsf==1
{
scalar Ur; scalar Ur;
if(1-tsf < 1e-4) //tsf==1
{
forAll(KslNext_,cellI) forAll(KslNext_,cellI)
{ {
Ur = mag(U_[cellI] - Us_[cellI]); Ur = mag(U_[cellI] - Us_[cellI]);
@ -166,16 +145,21 @@ tmp<volScalarField> implicitCouple::impMomSource() const
// limiter // limiter
if (KslNext_[cellI] > KslLimit_) KslNext_[cellI] = KslLimit_; if (KslNext_[cellI] > KslLimit_) KslNext_[cellI] = KslLimit_;
} }
tsource.ref() = KslPrev_; return tmp<volScalarField>
}else (
new volScalarField("Ksl_implicitCouple", KslPrev_)
);
}
else
{ {
tsource.ref() = (1 - tsf) * KslPrev_ + tsf * KslNext_; return tmp<volScalarField>
(
new volScalarField("Ksl_implicitCouple", (1. - tsf) * KslPrev_ + tsf * KslNext_)
);
}
} }
return tsource; void implicitCouple::resetMomSourceField() const
}
void Foam::implicitCouple::resetMomSourceField() const
{ {
KslPrev_.ref() = KslNext_.ref(); KslPrev_.ref() = KslNext_.ref();
KslNext_.primitiveFieldRef() = 0; KslNext_.primitiveFieldRef() = 0;

View File

@ -72,7 +72,7 @@ noCouple::~noCouple()
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
void Foam::noCouple::resetMomSourceField() const void noCouple::resetMomSourceField() const
{ {
FatalError<<"the solver calls for resetMomSourceField() although you use IB method where this is not needed!\n" FatalError<<"the solver calls for resetMomSourceField() although you use IB method where this is not needed!\n"
<<", check your solver! - PANIC -\n"; <<", check your solver! - PANIC -\n";

View File

@ -100,25 +100,36 @@ particleProbe::particleProbe
particleProbe::~particleProbe() particleProbe::~particleProbe()
{ {
clearProbes(); forAll(sPtrList_, i)
delete sPtrList_[i];
} }
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
void particleProbe::setOutputFile() const void particleProbe::setOutputFile(const word& logFileName)
{ {
//set the current item ID if (itemCounter_ > 0 && verboseToFile_)
if(currItemId_== itemCounter_) {
currItemId_=1; bool foundFile = false;
else forAll(itemsToSample_, i)
currItemId_+=1; {
sPtr = sPtrList_[currItemId_-1]; //set the pointer to the output file from list if (itemsToSample_[i] == logFileName)
probeIndex_=currItemId_-1; {
probeIndex_ = i;
foundFile = true;
}
}
if(!foundFile)
FatalError << "particleProbe::setOutputFile for logFileName " << logFileName << " : " << "File not found" << abort(FatalError);
currItemId_ = probeIndex_ + 1;
setCounter();
}
} }
void particleProbe::initialize(word typeName, word logFileName) const void particleProbe::initialize(const word& modelName, const word& logFileName)
{ {
//update the list of items to be sampled //update the list of items to be sampled
++itemCounter_; ++itemCounter_;
@ -126,7 +137,7 @@ void particleProbe::initialize(word typeName, word logFileName) const
// init environment // init environment
//propsDict_ = particleCloud_.couplingProperties().subDict(typeName + "Props"); //propsDict_ = particleCloud_.couplingProperties().subDict(typeName + "Props");
name_ = typeName; name_ = modelName;
if (verboseToFile_) if (verboseToFile_)
{ {
@ -136,8 +147,8 @@ void particleProbe::initialize(word typeName, word logFileName) const
MPI_Comm_rank(MPI_COMM_WORLD, &rank_); MPI_Comm_rank(MPI_COMM_WORLD, &rank_);
//open a separate file for each processor //open a separate file for each processor
char* filecurrent_ = new char[strlen(logFileName.c_str()) + 4]; //reserve 4 chars for processor name char* filecurrent_ = new char[logFileName.length() + 1 + 4 + 1]; //reserve 4 chars for processor name
sprintf(filecurrent_,"%s%s%d", logFileName.c_str(), ".", rank_); sprintf(filecurrent_,"%s.%d", logFileName.c_str(), rank_);
Info << "particleProbe for model " << name_ << " will write to file " << filecurrent_ << endl; Info << "particleProbe for model " << name_ << " will write to file " << filecurrent_ << endl;
@ -171,19 +182,15 @@ void particleProbe::initialize(word typeName, word logFileName) const
scalarFields_.clear(); scalarFields_.clear();
vectorFields_.clear(); vectorFields_.clear();
} }
return;
} }
void particleProbe::writeHeader() const void particleProbe::writeHeader() const
{ {
if (verboseToFile_) if (verboseToFile_)
{ {
*sPtr << "#processor: " << rank_ << endl; *sPtr << "#processor: " << rank_ << endl;
*sPtr << "#index time " << " "; *sPtr << "#index time " << " ";
*sPtr << "|| vectorData: " << " "; *sPtr << "|| vectorData: " << " ";
forAll(vectorFields_, iter) forAll(vectorFields_, iter)
@ -204,87 +211,15 @@ void particleProbe::writeHeader() const
if (includePosition_) *sPtr << " || position" << endl; if (includePosition_) *sPtr << " || position" << endl;
else *sPtr << endl; else *sPtr << endl;
} }
} }
void particleProbe::clearProbes() const
void particleProbe::writeProbe(int index, Field<scalar> sValues, Field<vector> vValues)
{ {
for (unsigned int i=0; i<vProbes_.size(); i++) if (printNow_ && verboseToFile_ && checkIDForPrint(index))
vProbes_[i].clear();
for (unsigned int j=0; j<sProbes_.size(); j++)
sProbes_[j].clear();
sProbes_.clear();
vProbes_.clear();
}
void particleProbe::updateProbes(int index, Field<scalar> sValues, Field<vector> vValues) const
{ {
int vSize_=vProbes_.size(); sPtr = sPtrList_[probeIndex_]; //set the pointer to the output file from list
int sSize_=sProbes_.size();
//check if the particle already has an allocated vector. If not, create it. It should be only called at the beginning.
while(index >= vSize_)
{
std::vector<double*> particleVector_;
vProbes_.push_back(particleVector_);
vSize_=vProbes_.size();
}
while(index >= sSize_)
{
std::vector<double> particleScalar_;
sProbes_.push_back(particleScalar_);
sSize_=sProbes_.size();
}
//register vector probes on the corresponding vector
forAll(vValues, iter)
{
int ProbeSize_=vProbes_[index].size();
if(probeIndex_<ProbeSize_) //The corresponding probe for this particle already exists, values are overwritten.
{
vProbes_[index][probeIndex_][0]=vValues[iter][0];
vProbes_[index][probeIndex_][1]=vValues[iter][1];
vProbes_[index][probeIndex_][2]=vValues[iter][2];
}
else //The corresponding probe for this particle has to be created
{
double * probe_= new double[3];
probe_[0]=vValues[iter][0];
probe_[1]=vValues[iter][1];
probe_[2]=vValues[iter][2];
vProbes_[index].push_back(probe_);
}
}
//register scalar probes on the corresponding vector
forAll(sValues, iter)
{
int ProbeSize_=sProbes_[index].size();
if(probeIndex_<ProbeSize_) //The corresponding probe for this particle already exists, values are overwritten.
{
sProbes_[index][probeIndex_]=sValues[iter];
}
else //The corresponding probe for this particle has to be created
{
sProbes_[index].push_back(sValues[iter]);
}
}
}
void particleProbe::writeProbe(int index, Field<scalar> sValues, Field<vector> vValues) const
{
updateProbes(index,sValues,vValues); //update probe vectors
if(printNow_ && checkIDForPrint(index) && verboseToFile_)
{
//index and time //index and time
*sPtr << setprecision(IOstream::defaultPrecision()+7); *sPtr << setprecision(IOstream::defaultPrecision()+7);
*sPtr << index << tab << particleCloud_.mesh().time().value() << " "; *sPtr << index << tab << particleCloud_.mesh().time().value() << " ";
@ -298,7 +233,6 @@ void particleProbe::writeProbe(int index, Field<scalar> sValues, Field<vector> v
*sPtr << vValues[iter][0] << " "; *sPtr << vValues[iter][0] << " ";
*sPtr << vValues[iter][1] << " "; *sPtr << vValues[iter][1] << " ";
*sPtr << vValues[iter][2] << " "; *sPtr << vValues[iter][2] << " ";
} }
//scalarFields //scalarFields
@ -324,42 +258,40 @@ void particleProbe::writeProbe(int index, Field<scalar> sValues, Field<vector> v
*sPtr << endl; *sPtr << endl;
} }
} }
return;
} }
bool particleProbe::checkIDForPrint(int index) const bool particleProbe::checkIDForPrint(int index) const
{ {
bool sampleThisId_ = false; if(sampleAll_)
if(sampleAll_) sampleThisId_ = true; {
return true;
}
else else
{ {
forAll(particleIDsToSample_, iSample) forAll(particleIDsToSample_, iSample)
{ {
if(index==particleIDsToSample_[iSample]) sampleThisId_ = true; if (index == particleIDsToSample_[iSample]) return true;
} }
} }
return sampleThisId_; return false;
} }
void particleProbe::setCounter() const void particleProbe::setCounter()
{ {
//reset or increment counter for printing to file //reset or increment counter for printing to file
//Do only if called by first item in the list of items! //Do only if called by first item in the list of items!
if (currItemId_ == 1) if (currItemId_ == 1)
{ {
printCounter_++; ++printCounter_;
if (printCounter_ >= printEvery_) if (printCounter_ >= printEvery_)
{ {
printCounter_ = 0; printCounter_ = 0;
printNow_ = true; printNow_ = true;
} }
else printNow_ = false; else printNow_ = false;
} }
return;
} }
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //

View File

@ -63,7 +63,7 @@ private:
dictionary propsDict_; dictionary propsDict_;
mutable word name_; word name_;
cfdemCloud& particleCloud_; cfdemCloud& particleCloud_;
@ -75,7 +75,7 @@ private:
word dirName_; word dirName_;
mutable int rank_; int rank_;
mutable OFstream* sPtr; mutable OFstream* sPtr;
@ -89,25 +89,23 @@ private:
const labelList particleIDsToSample_; const labelList particleIDsToSample_;
mutable wordList itemsToSample_; wordList itemsToSample_;
mutable List<OFstream*> sPtrList_; List<OFstream*> sPtrList_;
mutable int itemCounter_; int itemCounter_;
mutable int currItemId_; int currItemId_;
mutable int printCounter_; int printCounter_;
mutable bool printNow_; bool printNow_;
mutable std::vector< std::vector<double> > sProbes_; std::vector<std::string> probeName_;
mutable std::vector< std::vector<double*> > vProbes_; int probeIndex_;
mutable std::vector<std::string> probeName_; void setCounter();
mutable int probeIndex_;
public: public:
@ -131,17 +129,11 @@ public:
~particleProbe(); ~particleProbe();
// Member Functions // Member Functions
void updateProbes(int index, Field<scalar> sValues, Field<vector> vValues) const; void initialize(const word& modelName, const word& logFileName);
void initialize(word typeName, word logFileName) const; void setOutputFile(const word& logFileName);
void setOutputFile() const;
void writeHeader() const; void writeHeader() const;
void writeProbe(int index, Field<scalar> sValues, Field<vector> vValues) const; void writeProbe(int index, Field<scalar> sValues, Field<vector> vValues);
bool checkIDForPrint(int) const; bool checkIDForPrint(int) const;
void setCounter() const;
void clearProbes() const;
std::vector< std::vector<double*> >* getVprobe() { return &vProbes_; }
std::vector< std::vector<double> >* getSprobe() { return &sProbes_; }
}; };

View File

@ -133,16 +133,12 @@ public:
// Member Functions // Member Functions
virtual void initialize(word typeName, word logFileName) const {} virtual void initialize(const word& modelName, const word& logFileName) {}
virtual void setOutputFile() const {} virtual void setOutputFile(const word& logFileName) {}
virtual void writeHeader() const {} virtual void writeHeader() const {}
virtual void writeProbe(int index, Field<scalar> sValues, Field<vector> vValues) const {} virtual void writeProbe(int index, Field<scalar> sValues, Field<vector> vValues) {}
virtual bool checkIDForPrint(int) const { return false; } virtual bool checkIDForPrint(int) const { return false; }
virtual void setCounter() const {}
virtual bool active() const { return true; } virtual bool active() const { return true; }
virtual std::vector< std::vector<double*> >* getVprobe() { return NULL; }
virtual std::vector< std::vector<double> >* getSprobe() { return NULL; }
virtual void clearProbes() const {}
// Access // Access

View File

@ -46,13 +46,13 @@ defineRunTimeSelectionTable(regionModel, dictionary);
// * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
void Foam::regionModel::reAllocArrays() const void regionModel::reAllocArrays() const
{ {
if(particleCloud_.numberOfParticlesChanged()) if(particleCloud_.numberOfParticlesChanged())
{ {
// get arrays of new length // get arrays of new length
particleCloud_.dataExchangeM().allocateArray(inRegion_,1,1); particleCloud_.dataExchangeM().allocateArray(inRegion_,1.,1);
particleCloud_.dataExchangeM().allocateArray(outRegion_,1,1); particleCloud_.dataExchangeM().allocateArray(outRegion_,1.,1);
} }
} }
@ -83,8 +83,8 @@ regionModel::regionModel
regionModel::~regionModel() regionModel::~regionModel()
{ {
free(inRegion_); particleCloud_.dataExchangeM().destroy(inRegion_,1);
free(outRegion_); particleCloud_.dataExchangeM().destroy(outRegion_,1);
} }

View File

@ -94,7 +94,7 @@ bool constDiffSmoothing::doSmoothing() const
} }
void Foam::constDiffSmoothing::smoothen(volScalarField& fieldSrc) const void constDiffSmoothing::smoothen(volScalarField& fieldSrc) const
{ {
// Create scalar smooth field from virgin scalar smooth field template // Create scalar smooth field from virgin scalar smooth field template
volScalarField sSmoothField = sSmoothField_; volScalarField sSmoothField = sSmoothField_;
@ -135,7 +135,7 @@ void Foam::constDiffSmoothing::smoothen(volScalarField& fieldSrc) const
} }
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
void Foam::constDiffSmoothing::smoothen(volVectorField& fieldSrc) const void constDiffSmoothing::smoothen(volVectorField& fieldSrc) const
{ {
// Create scalar smooth field from virgin scalar smooth field template // Create scalar smooth field from virgin scalar smooth field template
volVectorField vSmoothField = vSmoothField_; volVectorField vSmoothField = vSmoothField_;
@ -170,7 +170,7 @@ void Foam::constDiffSmoothing::smoothen(volVectorField& fieldSrc) const
} }
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
void Foam::constDiffSmoothing::smoothenReferenceField(volVectorField& fieldSrc) const void constDiffSmoothing::smoothenReferenceField(volVectorField& fieldSrc) const
{ {
// Create scalar smooth field from virgin scalar smooth field template // Create scalar smooth field from virgin scalar smooth field template
volVectorField vSmoothField = vSmoothField_; volVectorField vSmoothField = vSmoothField_;
@ -194,7 +194,7 @@ void Foam::constDiffSmoothing::smoothenReferenceField(volVectorField& fieldSrc)
( (
IOobject IOobject
( (
"xxx", "NLarge",
particleCloud_.mesh().time().timeName(), particleCloud_.mesh().time().timeName(),
particleCloud_.mesh(), particleCloud_.mesh(),
IOobject::NO_READ, IOobject::NO_READ,

View File

@ -70,13 +70,13 @@ noSmoothing::~noSmoothing()
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
void Foam::noSmoothing::smoothen(volScalarField& field) const void noSmoothing::smoothen(volScalarField& field) const
{} {}
void Foam::noSmoothing::smoothen(volVectorField& field) const void noSmoothing::smoothen(volVectorField& field) const
{} {}
void Foam::noSmoothing::smoothenReferenceField(volVectorField& field) const void noSmoothing::smoothenReferenceField(volVectorField& field) const
{} {}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //

View File

@ -50,7 +50,7 @@ defineRunTimeSelectionTable(smoothingModel, dictionary);
// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * //
// Construct from components // Construct from components
Foam::smoothingModel::smoothingModel smoothingModel::smoothingModel
( (
const dictionary& dict, const dictionary& dict,
cfdemCloud& sm cfdemCloud& sm
@ -89,7 +89,7 @@ Foam::smoothingModel::smoothingModel
// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * //
Foam::smoothingModel::~smoothingModel() smoothingModel::~smoothingModel()
{} {}

View File

@ -137,7 +137,7 @@ void GaussVoidFraction::setvoidFraction(double** const& mask,double**& voidfract
if (hashSetLength > maxCellsPerParticle_) if (hashSetLength > maxCellsPerParticle_)
{ {
FatalError<< "big particle algo found more cells ("<< hashSetLength FatalError<< "big particle algo found more cells ("<< hashSetLength
<<") than storage is prepered ("<<maxCellsPerParticle_<<")" << abort(FatalError); <<") than storage is prepared ("<<maxCellsPerParticle_<<")" << abort(FatalError);
} }
else if (hashSetLength > 0) else if (hashSetLength > 0)
{ {

View File

@ -36,8 +36,6 @@ Description
#include "locateModel.H" #include "locateModel.H"
#include "dataExchangeModel.H" #include "dataExchangeModel.H"
#include <mpi.h>
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
namespace Foam namespace Foam
@ -68,17 +66,15 @@ IBVoidFraction::IBVoidFraction
propsDict_(dict.subDict(typeName + "Props")), propsDict_(dict.subDict(typeName + "Props")),
alphaMin_(readScalar(propsDict_.lookup("alphaMin"))), alphaMin_(readScalar(propsDict_.lookup("alphaMin"))),
alphaLimited_(0), alphaLimited_(0),
scaleUpVol_(readScalar(propsDict_.lookup("scaleUpVol"))), scaleUpVol_(readScalar(propsDict_.lookup("scaleUpVol")))
checkPeriodicCells_(false)
{ {
Info << "\n\n W A R N I N G - do not use in combination with differentialRegion model!\n\n" << endl; Info << "\n\n W A R N I N G - do not use in combination with differentialRegion model!\n\n" << endl;
//Info << "\n\n W A R N I N G - this model does not yet work properly! \n\n" << endl;
maxCellsPerParticle_ = readLabel(propsDict_.lookup("maxCellsPerParticle")); maxCellsPerParticle_ = readLabel(propsDict_.lookup("maxCellsPerParticle"));
if(scaleUpVol_ < 1){ FatalError<< "scaleUpVol shloud be > 1."<< abort(FatalError); } if (scaleUpVol_ < 1.0)
if(alphaMin_ > 1 || alphaMin_ < 0.01){ FatalError<< "alphaMin shloud be > 1 and < 0.01." << abort(FatalError); } FatalError << "scaleUpVol shloud be > 1." << abort(FatalError);
if (alphaMin_ > 1.0 || alphaMin_ < 0.01)
if(propsDict_.found("checkPeriodicCells")) checkPeriodicCells_=true; FatalError << "alphaMin shloud be > 1 and < 0.01." << abort(FatalError);
} }
@ -96,7 +92,7 @@ void IBVoidFraction::setvoidFraction(double** const& mask,double**& voidfraction
reAllocArrays(); reAllocArrays();
voidfractionNext_.ref()=1; voidfractionNext_.ref() = 1.0;
for (int index=0; index < particleCloud_.numberOfParticles(); index++) for (int index=0; index < particleCloud_.numberOfParticles(); index++)
{ {
@ -105,9 +101,10 @@ void IBVoidFraction::setvoidFraction(double** const& mask,double**& voidfraction
//reset //reset
for (int subcell=0; subcell < cellsPerParticle_[index][0]; subcell++) for (int subcell=0; subcell < cellsPerParticle_[index][0]; subcell++)
{ {
particleWeights[index][subcell]=0; particleWeights[index][subcell] = 0.0;
particleVolumes[index][subcell]=0; particleVolumes[index][subcell] = 0.0;
} }
cellsPerParticle_[index][0]=1; cellsPerParticle_[index][0]=1;
particleV[index][0]=0; particleV[index][0]=0;
@ -122,87 +119,61 @@ void IBVoidFraction::setvoidFraction(double** const& mask,double**& voidfraction
//compute the voidfraction for the cell "particleCentreCellID //compute the voidfraction for the cell "particleCentreCellID
vector cellCentrePosition = particleCloud_.mesh().C()[particleCenterCellID]; vector cellCentrePosition = particleCloud_.mesh().C()[particleCenterCellID];
scalar centreDist=mag(cellCentrePosition-positionCenter); scalar fc = pointInParticle(index, positionCenter, cellCentrePosition);
vector minPeriodicParticlePos = positionCenter; vector minPeriodicParticlePos = positionCenter;
if(checkPeriodicCells_) //consider minimal distance to all periodic images of this particle
if (particleCloud_.checkPeriodicCells()) //consider minimal distance to all periodic images of this particle
{ {
centreDist = minPeriodicDistance(cellCentrePosition, positionCenter, globalBb, fc = minPeriodicDistance(index,cellCentrePosition, positionCenter, globalBb, minPeriodicParticlePos);
minPeriodicParticlePos);
} }
if(centreDist + 0.5*sqrt(3.0)*pow(particleCloud_.mesh().V()[particleCenterCellID],0.33333) < radius) scalar centreDist = mag(cellCentrePosition - minPeriodicParticlePos);
scalar corona = 0.5 * sqrt(3.0) * pow(particleCloud_.mesh().V()[particleCenterCellID], 1./3.);
vector coronaPoint = cellCentrePosition + (cellCentrePosition - minPeriodicParticlePos) * (corona / centreDist);
if (pointInParticle(index, minPeriodicParticlePos, coronaPoint) < 0.0)
{ {
voidfractionNext_[particleCenterCellID] = 0; voidfractionNext_[particleCenterCellID] = 0.0;
} }
else else
{ {
const labelList& vertices = particleCloud_.mesh().cellPoints()[particleCenterCellID]; const labelList& vertices = particleCloud_.mesh().cellPoints()[particleCenterCellID];
const double ratio = 0.125;
forAll(vertices, i) forAll(vertices, i)
{ {
vector vertexPosition = particleCloud_.mesh().points()[vertices[i]]; vector vertexPosition = particleCloud_.mesh().points()[vertices[i]];
scalar centreVertexDist = mag(vertexPosition-positionCenter); scalar fv = pointInParticle(index, positionCenter, vertexPosition);
if(checkPeriodicCells_) //consider minimal distance to all periodic images of this particle
if (particleCloud_.checkPeriodicCells()) //consider minimal distance to all periodic images of this particle
{ {
centreVertexDist = minPeriodicDistance(vertexPosition, positionCenter, globalBb, fv = minPeriodicDistance(index, vertexPosition, positionCenter, globalBb, minPeriodicParticlePos);
minPeriodicParticlePos);
} }
if(centreDist<radius && centreVertexDist<radius) if (fc < 0.0 && fv < 0.0)
{ {
voidfractionNext_[particleCenterCellID]-=0.125; voidfractionNext_[particleCenterCellID] -= ratio;
} }
else if(centreDist<radius && centreVertexDist>radius) else if (fc < 0.0 && fv > 0.0)
{ {
//compute lambda //compute lambda
scalar a = (vertexPosition - cellCentrePosition) scalar lambda = segmentParticleIntersection(index, minPeriodicParticlePos, cellCentrePosition, vertexPosition);
& (vertexPosition - cellCentrePosition); voidfractionNext_[particleCenterCellID] -= ratio * lambda;
scalar b = 2. * (vertexPosition - cellCentrePosition)
& (cellCentrePosition-minPeriodicParticlePos);
scalar c = ( (cellCentrePosition-minPeriodicParticlePos)
&(cellCentrePosition-minPeriodicParticlePos)
)
- radius*radius;
scalar lambda = 0.;
if (b*b-4.*a*c>=0.) lambda = (-b+sqrt(b*b-4.*a*c))/(2.*a);
if (lambda > 0 && lambda <=1) voidfractionNext_[particleCenterCellID]-=lambda*0.125;
else
{
lambda = (-b-sqrt(b*b-4.*a*c))/(2.*a);
if (lambda > 0. && lambda <=1.) voidfractionNext_[particleCenterCellID]-=lambda*0.125;
} }
} else if (fc > 0.0 && fv < 0.0)
else if(centreDist>radius && centreVertexDist<radius)
{ {
//compute another lambda too //compute lambda
scalar a = (vertexPosition - cellCentrePosition) scalar lambda = segmentParticleIntersection(index, minPeriodicParticlePos, vertexPosition, cellCentrePosition);
& (vertexPosition - cellCentrePosition); voidfractionNext_[particleCenterCellID] -= ratio * lambda;
scalar b = 2.* (vertexPosition - cellCentrePosition)
& (cellCentrePosition-minPeriodicParticlePos);
scalar c = ( (cellCentrePosition-minPeriodicParticlePos)
&(cellCentrePosition-minPeriodicParticlePos)
)
- radius*radius;
scalar lambda = 0.;
if(b*b-4.*a*c>=0.) lambda = (-b+sqrt(b*b-4.*a*c))/(2.*a);
if(lambda > 0. && lambda <=1.) voidfractionNext_[particleCenterCellID]-=(1.-lambda)*0.125;
else
{
lambda = (-b-sqrt(b*b-4.*a*c))/(2.*a);
if (lambda > 0. && lambda <=1.) voidfractionNext_[particleCenterCellID]-=(1.-lambda)*0.125;
}
} }
} }
} //end particle partially overlapping with cell } //end particle partially overlapping with cell
//generating list with cell and subcells //generating list with cell and subcells
buildLabelHashSet(radius, minPeriodicParticlePos, particleCenterCellID, hashSett, true); buildLabelHashSet(index, minPeriodicParticlePos, particleCenterCellID, hashSett, true);
//Add cells of periodic particle images on same processor //Add cells of periodic particle images on same processor
if(checkPeriodicCells_) if (particleCloud_.checkPeriodicCells())
{ {
int doPeriodicImage[3]; int doPeriodicImage[3];
for (int iDir=0; iDir < 3; iDir++) for (int iDir=0; iDir < 3; iDir++)
@ -313,6 +284,8 @@ void IBVoidFraction::setvoidFraction(double** const& mask,double**& voidfraction
if(cellID >= 0) if(cellID >= 0)
{ {
if (voidfractionNext_[cellID] < 0.0)
voidfractionNext_[cellID] = 0.0;
voidfractions[index][subcell] = voidfractionNext_[cellID]; voidfractions[index][subcell] = voidfractionNext_[cellID];
} }
else else
@ -325,14 +298,15 @@ void IBVoidFraction::setvoidFraction(double** const& mask,double**& voidfraction
void IBVoidFraction::buildLabelHashSet void IBVoidFraction::buildLabelHashSet
( (
const scalar radius, int index,
const vector position, const vector position,
const label cellID, const label cellID,
labelHashSet& hashSett, labelHashSet& hashSett,
bool initialInsert //initial insertion of own cell bool initialInsert //initial insertion of own cell
)const )const
{ {
if(initialInsert) hashSett.insert(cellID); if(initialInsert)
hashSett.insert(cellID);
const labelList& nc = particleCloud_.mesh().cellCells()[cellID]; const labelList& nc = particleCloud_.mesh().cellCells()[cellID];
forAll(nc,i) forAll(nc,i)
@ -341,65 +315,47 @@ void IBVoidFraction::buildLabelHashSet
vector cellCentrePosition = particleCloud_.mesh().C()[neighbor]; vector cellCentrePosition = particleCloud_.mesh().C()[neighbor];
scalar centreDist = mag(cellCentrePosition-position); scalar centreDist = mag(cellCentrePosition-position);
if(!hashSett.found(neighbor) && centreDist + 0.5*sqrt(3.0)*pow(particleCloud_.mesh().V()[neighbor],0.33333) < radius) scalar fc = pointInParticle(index, position, cellCentrePosition);
scalar corona = 0.5 * sqrt(3.0) * pow(particleCloud_.mesh().V()[neighbor], 1./3.);
vector coronaPoint = cellCentrePosition + (cellCentrePosition - position) * (corona / centreDist);
if (!hashSett.found(neighbor) && pointInParticle(index, position, coronaPoint) < 0.0)
{ {
voidfractionNext_[neighbor] = 0.; voidfractionNext_[neighbor] = 0.;
buildLabelHashSet(radius,position,neighbor,hashSett,true); buildLabelHashSet(index,position,neighbor,hashSett,true);
} }
else if(!hashSett.found(neighbor) && centreDist < radius + sqrt(3.0)*pow(particleCloud_.mesh().V()[neighbor],0.33333)) else if(!hashSett.found(neighbor))
{ {
scalar scale = 1.; scalar scale = 1.;
const labelList& vertexPoints = particleCloud_.mesh().cellPoints()[neighbor]; const labelList& vertexPoints = particleCloud_.mesh().cellPoints()[neighbor];
const scalar ratio = 0.125;
forAll(vertexPoints, j) forAll(vertexPoints, j)
{ {
vector vertexPosition = particleCloud_.mesh().points()[vertexPoints[j]]; vector vertexPosition = particleCloud_.mesh().points()[vertexPoints[j]];
scalar vertexDist = mag(vertexPosition - position); scalar fv = pointInParticle(index, position, vertexPosition);
if (centreDist < radius) if (fc < 0.0)
{ {
if (vertexDist < radius) if (fv < 0.0)
{ {
scale -= 0.125; scale -= ratio;
} }
else else
{ {
scalar a = (vertexPosition - cellCentrePosition)&(vertexPosition - cellCentrePosition); scalar lambda = segmentParticleIntersection(index, position, cellCentrePosition, vertexPosition);
scalar b = 2.* (vertexPosition - cellCentrePosition)&(cellCentrePosition-position); scale -= lambda * ratio;
scalar c = ((cellCentrePosition-position)&(cellCentrePosition-position))-radius*radius; }
scalar lambda = 0.; }
else if (fv < 0.0)
{
scalar lambda = segmentParticleIntersection(index, position, vertexPosition, cellCentrePosition);
scale -= lambda * ratio;
}
}
if(b*b-4.*a*c >= 0.) lambda = (-b+sqrt(b*b-4.*a*c))/(2.*a); if (scale < 0.0)
if (lambda > 0. && lambda <=1.) scale = 0.0;
{
scale -=lambda * 0.125;
}
else
{
lambda = (-b-sqrt(b*b-4.*a*c))/(2.*a);
if (lambda > 0. && lambda <= 1.) scale -=lambda * 0.125;
}
}
}
else if (vertexDist < radius)
{
scalar a = (vertexPosition - cellCentrePosition)&(vertexPosition - cellCentrePosition);
scalar b = 2.* (vertexPosition - cellCentrePosition)&(cellCentrePosition-position);
scalar c = ((cellCentrePosition-position)&(cellCentrePosition-position))-radius*radius;
scalar lambda = 0.;
if (b*b-4.*a*c >= 0.) lambda = (-b+sqrt(b*b-4.*a*c))/(2.*a);
if (lambda > 0. && lambda <= 1.)
{
scale -=(1.-lambda) * 0.125;
}
else
{
lambda = (-b-sqrt(b*b-4.*a*c))/(2.*a);
if (lambda > 0. && lambda <= 1.) scale -= (1.-lambda) * 0.125;
}
}
}
if (voidfractionNext_[neighbor] == 1.0) if (voidfractionNext_[neighbor] == 1.0)
{ {
@ -408,48 +364,50 @@ void IBVoidFraction::buildLabelHashSet
else else
{ {
voidfractionNext_[neighbor] -= (1.0-scale); voidfractionNext_[neighbor] -= (1.0-scale);
if(voidfractionNext_[neighbor] < 0.) voidfractionNext_[neighbor] = 0.0; if (voidfractionNext_[neighbor] < 0.)
voidfractionNext_[neighbor] = 0.0;
} }
if(!(scale == 1.0)) buildLabelHashSet(radius,position,neighbor,hashSett, true);
if (!(scale == 1.0))
buildLabelHashSet(index,position,neighbor,hashSett, true);
} }
} }
} }
//Function to determine minimal distance of point double IBVoidFraction::segmentParticleIntersection(int index, vector positionCenter, vector pointInside, vector pointOutside) const
//to one of the periodic images of a particle
double IBVoidFraction::minPeriodicDistance(vector cellCentrePosition,
vector positionCenter,
boundBox globalBb,
vector& minPeriodicPos)const
{ {
double centreDist = 999e32; const scalar radius = particleCloud_.radius(index);
vector positionCenterPeriodic; const scalar a = (pointOutside - pointInside) & (pointOutside - pointInside);
const scalar b = 2.*(pointOutside - pointInside) & (pointInside - positionCenter);
const scalar c = ((pointInside - positionCenter) & (pointInside - positionCenter)) - radius*radius;
const scalar D = b*b - 4.0*a*c;
const scalar eps = 1e-12;
scalar lambda_ = 0.0;
scalar lambda = 0.0;
for (int xDir=-1; xDir<=1; xDir++) if (D >= 0.0)
{ {
positionCenterPeriodic[0] = positionCenter[0] scalar sqrtD = sqrt(D);
+ static_cast<double>(xDir) lambda_ = (-b + sqrtD)/(2.0*a);
* (globalBb.max()[0] - globalBb.min()[0]);
for (int yDir=-1; yDir<=1; yDir++) if (lambda_ >= -eps && lambda_ <= 1.0+eps)
{ {
positionCenterPeriodic[1] = positionCenter[1] lambda = lambda_;
+ static_cast<double>(yDir)
* (globalBb.max()[1] - globalBb.min()[1]);
for (int zDir=-1; zDir<=1; zDir++)
{
positionCenterPeriodic[2] = positionCenter[2]
+ static_cast<double>(zDir)
* (globalBb.max()[2] - globalBb.min()[2]);
if (mag(cellCentrePosition-positionCenterPeriodic) < centreDist)
{
centreDist = mag(cellCentrePosition-positionCenterPeriodic);
minPeriodicPos = positionCenterPeriodic;
}
} }
else
{
lambda_ = (-b - sqrtD)/(2.0*a);
if (lambda_ >= -eps && lambda_ <= 1.0+eps)
lambda = lambda_;
} }
} }
return centreDist; if (lambda < 0.0)
return 0.0;
else if (lambda > 1.0)
return 1.0;
return lambda;
} }
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //

View File

@ -68,8 +68,6 @@ private:
const scalar scaleUpVol_; //NP scaling radius, keeping volume of particle const scalar scaleUpVol_; //NP scaling radius, keeping volume of particle
mutable bool checkPeriodicCells_;
public: public:
//- Runtime type information //- Runtime type information
@ -95,22 +93,14 @@ public:
void buildLabelHashSet void buildLabelHashSet
( (
const scalar radius, int index,
const vector position, const vector position,
const label cellID, const label cellID,
labelHashSet& hashSett, labelHashSet& hashSett,
bool initialInsert bool initialInsert
) const; ) const;
double minPeriodicDistance virtual double segmentParticleIntersection(int index, vector positionCenter, vector pointInside, vector pointOutside) const;
(
vector cellCentrePosition,
vector positionCenter,
boundBox globalBb,
vector& minPeriodicPos
) const;
}; };

View File

@ -132,7 +132,7 @@ void bigParticleVoidFraction::setvoidFraction(double** const& mask,double**& voi
if (hashSetLength > maxCellsPerParticle_) if (hashSetLength > maxCellsPerParticle_)
{ {
FatalError<< "big particle algo found more cells ("<< hashSetLength FatalError<< "big particle algo found more cells ("<< hashSetLength
<<") than storage is prepered ("<<maxCellsPerParticle_<<")" << abort(FatalError); <<") than storage is prepared ("<<maxCellsPerParticle_<<")" << abort(FatalError);
} }
else if (hashSetLength > 0) else if (hashSetLength > 0)
{ {

View File

@ -140,6 +140,7 @@ void centreVoidFraction::setvoidFraction(double** const& mask,double**& voidfrac
} }
//} //}
} }
voidfractionNext_.correctBoundaryConditions();
// bring voidfraction from Eulerian Field to particle array // bring voidfraction from Eulerian Field to particle array
for(int index=0; index< particleCloud_.numberOfParticles(); index++) for(int index=0; index< particleCloud_.numberOfParticles(); index++)

View File

@ -35,9 +35,7 @@ Description
#include "addToRunTimeSelectionTable.H" #include "addToRunTimeSelectionTable.H"
#include "locateModel.H" #include "locateModel.H"
#include "dataExchangeModel.H" #include "dataExchangeModel.H"
#include <math.h>
//#include <mpi.h>
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
namespace Foam namespace Foam
@ -67,16 +65,20 @@ dividedVoidFraction::dividedVoidFraction
voidFractionModel(dict,sm), voidFractionModel(dict,sm),
propsDict_(dict.subDict(typeName + "Props")), propsDict_(dict.subDict(typeName + "Props")),
verbose_(false), verbose_(false),
procBoundaryCorrection_(propsDict_.lookupOrDefault<Switch>("procBoundaryCorrection", false)),
alphaMin_(readScalar(propsDict_.lookup("alphaMin"))), alphaMin_(readScalar(propsDict_.lookup("alphaMin"))),
alphaLimited_(0), alphaLimited_(0),
tooMuch_(0.0), tooMuch_(0.0),
interpolation_(false), interpolation_(false),
cfdemUseOnly_(false) cfdemUseOnly_(false)
{ {
maxCellsPerParticle_ = 29; maxCellsPerParticle_ = numberOfMarkerPoints;
if(alphaMin_ > 1 || alphaMin_ < 0.01){ Warning << "alphaMin should be < 1 and > 0.01 !!!" << endl; } if (alphaMin_ > 1.0 || alphaMin_ < 0.01)
if (propsDict_.found("interpolation")){ Warning << "alphaMin should be < 1 and > 0.01 !!!" << endl;
if (propsDict_.found("interpolation"))
{
interpolation_ = true; interpolation_ = true;
Warning << "interpolation for dividedVoidFraction does not yet work correctly!" << endl; Warning << "interpolation for dividedVoidFraction does not yet work correctly!" << endl;
Info << "Using interpolated voidfraction field - do not use this in combination with interpolation in drag model!" << endl; Info << "Using interpolated voidfraction field - do not use this in combination with interpolation in drag model!" << endl;
@ -84,12 +86,74 @@ dividedVoidFraction::dividedVoidFraction
checkWeightNporosity(propsDict_); checkWeightNporosity(propsDict_);
if (propsDict_.found("verbose")) verbose_=true; if (propsDict_.found("verbose"))
verbose_ = true;
if (propsDict_.found("cfdemUseOnly")) if (propsDict_.found("cfdemUseOnly"))
{ {
cfdemUseOnly_ = readBool(propsDict_.lookup("cfdemUseOnly")); cfdemUseOnly_ = readBool(propsDict_.lookup("cfdemUseOnly"));
} }
if (procBoundaryCorrection_)
{
if (!(particleCloud_.locateM().type() == "engineIB"))
{
FatalError << typeName << ": You are requesting procBoundaryCorrection, this requires the use of engineIB!\n"
<< abort(FatalError);
}
}
else
{
if (particleCloud_.locateM().type() == "engineIB")
{
FatalError << typeName << ": You are using engineIB, this requires using procBoundaryCorrection=true!\n"
<< abort(FatalError);
}
}
// generate marker points on unit sphere
label m = 0;
offsets[m][0] = offsets[m][1] = offsets[m][2] = 0.0;
++m;
// for 2 different radii
scalar r1 = cbrt(1.0/numberOfMarkerPoints);
scalar r2 = cbrt(15.0/numberOfMarkerPoints);
scalar r[] = { 0.75 * (r2*r2*r2*r2 - r1*r1*r1*r1)/(r2*r2*r2 - r1*r1*r1),
0.75 * (1.0 - r2*r2*r2*r2)/(1.0 - r2*r2*r2) };
for (label ir = 0; ir < 2; ++ir)
{
// try 8 subpoints derived from spherical coordinates
for (scalar zeta = M_PI_4; zeta < constant::mathematical::twoPi; zeta += constant::mathematical::piByTwo)
{
for (scalar theta = M_PI_4; theta < constant::mathematical::pi; theta += constant::mathematical::piByTwo)
{
offsets[m][0] = r[ir] * Foam::sin(theta) * Foam::cos(zeta);
offsets[m][1] = r[ir] * Foam::sin(theta) * Foam::sin(zeta);
offsets[m][2] = r[ir] * Foam::cos(theta);
++m;
}
}
// try 2 more subpoints for each coordinate direction (6 total)
for (label j = -1; j <= 1; j += 2)
{
offsets[m][0] = r[ir] * j;
offsets[m][1] = 0.;
offsets[m][2] = 0.;
++m;
offsets[m][0] = 0.;
offsets[m][1] = r[ir] * j;
offsets[m][2] = 0.;
++m;
offsets[m][0] = 0.;
offsets[m][1] = 0.;
offsets[m][2] = r[ir] * j;
++m;
}
}
} }
@ -115,6 +179,7 @@ void dividedVoidFraction::setvoidFraction(double** const& mask,double**& voidfra
scalar cellVol(0.); scalar cellVol(0.);
scalar scaleVol = weight(); scalar scaleVol = weight();
scalar scaleRadius = pow(porosity(),1./3.); scalar scaleRadius = pow(porosity(),1./3.);
const boundBox& globalBb = particleCloud_.mesh().bounds();
for (int index=0; index < particleCloud_.numberOfParticles(); index++) for (int index=0; index < particleCloud_.numberOfParticles(); index++)
{ {
@ -126,8 +191,8 @@ void dividedVoidFraction::setvoidFraction(double** const& mask,double**& voidfra
for (int subcell=0; subcell < cellsPerParticle_[index][0]; subcell++) for (int subcell=0; subcell < cellsPerParticle_[index][0]; subcell++)
{ {
particleWeights[index][subcell]=0; particleWeights[index][subcell] = 0.;
particleVolumes[index][subcell]=0; particleVolumes[index][subcell] = 0.;
} }
particleV[index][0] = 0.; particleV[index][0] = 0.;
@ -140,61 +205,51 @@ void dividedVoidFraction::setvoidFraction(double** const& mask,double**& voidfra
cellVol = 0; cellVol = 0;
//--variables for sub-search //--variables for sub-search
int nPoints = 29; int nPoints = numberOfMarkerPoints;
int nNotFound = 0, nUnEqual = 0, nTotal = 0; int nNotFound = 0, nUnEqual = 0, nTotal = 0;
vector offset(0.,0.,0.); vector offset(0.,0.,0.);
int cellsSet = 0; int cellsSet = 0;
if (procBoundaryCorrection_)
{
label cellWithCenter(-1);
// switch off cellIDs for force calc if steming from parallel search success
cellWithCenter = particleCloud_.locateM().findSingleCell(position,cellID);
particleCloud_.cellIDs()[index][0] = cellWithCenter;
}
if (cellID >= 0) // particel centre is in domain if (cellID >= 0) // particel centre is in domain
{ {
cellVol = particleCloud_.mesh().V()[cellID]; cellVol = particleCloud_.mesh().V()[cellID];
// for 2 different radii if (procBoundaryCorrection_)
const scalar delta_r = 0.293976*radius;
for (scalar r = 0.623926*radius; r < radius; r+=delta_r)
{ {
// try 8 subpoint derived from spherical coordinates offset = radius * offsets[0];
for (scalar zeta=M_PI_4; zeta<2.*M_PI; zeta+=M_PI_2)
{
for (scalar theta=M_PI_4; theta<M_PI; theta+=M_PI_2)
{
offset[0] = r * Foam::sin(theta) * Foam::cos(zeta);
offset[1] = r * Foam::sin(theta) * Foam::sin(zeta);
offset[2] = r * Foam::cos(theta);
#include "setWeightedSource.H" // set source terms at position+offset #include "setWeightedSource.H" // set source terms at position+offset
} }
}
// try 2 more subpoints for each coordinate direction (6 total) for (label i = 1; i < numberOfMarkerPoints; ++i)
for (int j=-1; j<=1; j+=2)
{ {
offset[0] = r * static_cast<double>(j); offset = radius * offsets[i];
offset[1] = 0.; #include "setWeightedSource.H" // set source terms at position+offset
offset[2] = 0.;
#include "setWeightedSource.H" //NP set source terms at position+offset
offset[0] = 0.;
offset[1] = r * static_cast<double>(j);
offset[2] = 0.;
#include "setWeightedSource.H" //NP set source terms at position+offset
offset[0] = 0.;
offset[1] = 0.;
offset[2] = r * static_cast<double>(j);
#include "setWeightedSource.H" //NP set source terms at position+offset
} }
}// end loop radiivoidfractions
if(cellsSet>29 || cellsSet<0) if (cellsSet > maxCellsPerParticle_ || cellsSet < 0)
{ {
Info << "ERROR cellsSet =" << cellsSet << endl; Info << "ERROR cellsSet =" << cellsSet << endl;
} }
if (!procBoundaryCorrection_)
{
// set source for particle center; source 1/nPts+weight of all subpoints that have not been found // set source for particle center; source 1/nPts+weight of all subpoints that have not been found
scalar centreWeight = 1./nPoints*(nPoints-cellsSet); scalar centreWeight = 1./nPoints*(nPoints-cellsSet);
// update voidfraction for each particle read // update voidfraction for each particle read
scalar newAlpha = voidfractionNext_[cellID]- volume*centreWeight/cellVol; scalar newAlpha = voidfractionNext_[cellID]- volume*centreWeight/cellVol;
if(newAlpha > alphaMin_) voidfractionNext_[cellID] = newAlpha; if (newAlpha > alphaMin_)
{
voidfractionNext_[cellID] = newAlpha;
}
else else
{ {
voidfractionNext_[cellID] = alphaMin_; voidfractionNext_[cellID] = alphaMin_;
@ -207,25 +262,11 @@ void dividedVoidFraction::setvoidFraction(double** const& mask,double**& voidfra
// store particleVolume for each particle // store particleVolume for each particle
particleVolumes[index][0] += volume*centreWeight; particleVolumes[index][0] += volume*centreWeight;
particleV[index][0] += volume*centreWeight; particleV[index][0] += volume*centreWeight;
/*//OUTPUT
if (index==0 && verbose_)
{
Info << "centre cellID = " << cellID << endl;
Info << "cellsPerParticle_=" << cellsPerParticle_[index][0] << endl;
for(int i=0;i<cellsPerParticle_[index][0];i++)
{
if(i==0)Info << "cellids, voidfractions, particleWeights, : \n";
Info << particleCloud_.cellIDs()[index][i] << " ," << endl;
Info << voidfractions[index][i] << " ," << endl;
Info << particleWeights[index][i] << " ," << endl;
} }
}*/
}// end if in cell }// end if in cell
//}// end if in mask //}// end if in mask
}// end loop all particles }// end loop all particles
voidfractionNext_.correctBoundaryConditions();
// reset counter of lost volume // reset counter of lost volume
if (verbose_) Pout << "Total particle volume neglected: " << tooMuch_ << endl; if (verbose_) Pout << "Total particle volume neglected: " << tooMuch_ << endl;
@ -236,35 +277,6 @@ void dividedVoidFraction::setvoidFraction(double** const& mask,double**& voidfra
//scalar voidfractionAtPos(0); //scalar voidfractionAtPos(0);
for(int index=0; index < particleCloud_.numberOfParticles(); index++) for(int index=0; index < particleCloud_.numberOfParticles(); index++)
{ {
/*if(interpolation_)
{
label cellI = particleCloud_.cellIDs()[index][0];
if(cellI >= 0)
{
position = particleCloud_.position(index);
voidfractionAtPos=voidfractionInterpolator_.interpolate(position,cellI);
}else{
voidfractionAtPos=-1;
}
for(int subcell=0;subcell<cellsPerParticle_[index][0];subcell++)
{
label cellID = particleCloud_.cellIDs()[index][subcell];
if(cellID >= 0)
{
if(voidfractionAtPos > 0)
voidfractions[index][subcell] = voidfractionAtPos;
else
voidfractions[index][subcell] = voidfractionNext_[cellID];
}
else
{
voidfractions[index][subcell] = -1.;
}
}
}
else*/
{ {
for (int subcell=0; subcell < cellsPerParticle_[index][0]; subcell++) for (int subcell=0; subcell < cellsPerParticle_[index][0]; subcell++)
{ {

View File

@ -57,10 +57,14 @@ class dividedVoidFraction
{ {
private: private:
static const int numberOfMarkerPoints = 29;
dictionary propsDict_; dictionary propsDict_;
bool verbose_; bool verbose_;
Switch procBoundaryCorrection_;
const scalar alphaMin_; // min value of voidFraction const scalar alphaMin_; // min value of voidFraction
mutable bool alphaLimited_; mutable bool alphaLimited_;
@ -71,6 +75,8 @@ private:
bool cfdemUseOnly_; bool cfdemUseOnly_;
vector offsets[numberOfMarkerPoints];
virtual inline scalar Vp(int index, scalar radius, scalar scaleVol) const virtual inline scalar Vp(int index, scalar radius, scalar scaleVol) const
{ {
return 4.188790205*radius*radius*radius*scaleVol; //4/3*pi=4.188790205 return 4.188790205*radius*radius*radius*scaleVol; //4/3*pi=4.188790205

View File

@ -3,6 +3,18 @@
{ {
// locate subPoint // locate subPoint
vector subPosition = position + offset; vector subPosition = position + offset;
if (particleCloud_.checkPeriodicCells())
{
for (int iDir=0; iDir<3; iDir++)
{
if (subPosition[iDir] > globalBb.max()[iDir])
subPosition[iDir] -= globalBb.max()[iDir]-globalBb.min()[iDir];
else if (subPosition[iDir] < globalBb.min()[iDir])
subPosition[iDir] += globalBb.max()[iDir]-globalBb.min()[iDir];
}
}
label partCellId = particleCloud_.locateM().findSingleCell(subPosition,cellID); label partCellId = particleCloud_.locateM().findSingleCell(subPosition,cellID);
//NP fprintf(lmp->screen,"cellID=%d, partCellId=%d\n",static_cast<int>(cellID),static_cast<int>(partCellId)); //NP fprintf(lmp->screen,"cellID=%d, partCellId=%d\n",static_cast<int>(cellID),static_cast<int>(partCellId));

View File

@ -0,0 +1,392 @@
/*---------------------------------------------------------------------------*\
CFDEMcoupling - Open Source CFD-DEM coupling
CFDEMcoupling is part of the CFDEMproject
www.cfdem.com
Christoph Goniva, christoph.goniva@cfdem.com
Copyright 2012- DCS Computing GmbH, Linz
-------------------------------------------------------------------------------
License
This file is part of CFDEMcoupling.
CFDEMcoupling is free software; you can redistribute it and/or modify it
under the terms of the GNU General Public License as published by the
Free Software Foundation; either version 3 of the License, or (at your
option) any later version.
CFDEMcoupling is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
for more details.
You should have received a copy of the GNU General Public License
along with CFDEMcoupling; if not, write to the Free Software Foundation,
Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
Description
This code is designed to realize coupled CFD-DEM simulations using LIGGGHTS
and OpenFOAM(R). Note: this code is not part of OpenFOAM(R) (see DISCLAIMER).
\*---------------------------------------------------------------------------*/
#include "error.H"
#include "trilinearVoidFraction.H"
#include "addToRunTimeSelectionTable.H"
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
namespace Foam
{
// * * * * * * * * * * * * * * Static Data Members * * * * * * * * * * * * * //
defineTypeNameAndDebug(trilinearVoidFraction, 0);
addToRunTimeSelectionTable
(
voidFractionModel,
trilinearVoidFraction,
dictionary
);
// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * //
// Construct from components
trilinearVoidFraction::trilinearVoidFraction
(
const dictionary& dict,
cfdemCloud& sm
)
:
voidFractionModel(dict,sm),
propsDict_(dict.subDict(typeName + "Props")),
alphaMin_(readScalar(propsDict_.lookup("alphaMin"))),
bb_(particleCloud_.mesh().points(),false),
cellVol_(particleCloud_.mesh().V()[0]),
cellLength_(pow(cellVol_,1./3.)),
nCellXYZ_
(
round((bb_.max()[0] - bb_.min()[0]) / cellLength_),
round((bb_.max()[1] - bb_.min()[1]) / cellLength_),
round((bb_.max()[2] - bb_.min()[2]) / cellLength_)
)
{
maxCellsPerParticle_ = 8;
checkWeightNporosity(propsDict_);
if (porosity() != 1.) FatalError << "porosity not used in trilinearVoidFraction" << abort(FatalError);
Warning << "trilinearVoidFraction model is not yet complete and does not work near boundaries" << endl;
}
// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * //
trilinearVoidFraction::~trilinearVoidFraction()
{}
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
void trilinearVoidFraction::setvoidFraction(double** const& mask,double**& voidfractions,double**& particleWeights,double**& particleVolumes,double**& particleV) const
{
reAllocArrays();
scalar radius(-1.);
scalar volume(0.);
const scalar scaleVol = weight();
const scalar fourPiByThree = 4.0*constant::mathematical::pi/3.0;
vector partPos(0.,0.,0.);
vector pt(0.,0.,0.);
vector posShift(0.,0.,0.);
vector offsetCell(0.,0.,0.);
vector offsetOrigin(0.,0.,0.);
label i000(0);
label i100(0);
label i110(0);
label i101(0);
label i111(0);
label i010(0);
label i011(0);
label i001(0);
scalar C000(0.);
scalar C100(0.);
scalar C110(0.);
scalar C101(0.);
scalar C111(0.);
scalar C010(0.);
scalar C011(0.);
scalar C001(0.);
scalar x(0.);
scalar y(0.);
scalar z(0.);
scalar a(0.);
scalar b(0.);
scalar c(0.);
for(int index = 0; index < particleCloud_.numberOfParticles(); ++index)
{
// reset
cellsPerParticle_[index][0] = 8;
//TODO do we need to set particleVolumes, particleV?
// ===
label cellI = particleCloud_.cellIDs()[index][0];
if (cellI >= 0) // particel centre is in domain
{
radius = particleCloud_.radius(index);
volume = fourPiByThree * radius * radius * radius * scaleVol;
// store volume for each particle
particleVolumes[index][0] = volume;
particleV[index][0] = volume;
// find a,b,c
partPos = particleCloud_.position(index);
offsetCell = partPos - particleCloud_.mesh().C()[cellI];
a = offsetCell[0];
b = offsetCell[1];
c = offsetCell[2];
// find "origin" index for mapping
if ( a > 0.)
{
if (b > 0.)
{
if (c > 0.) //FNE
i000 = cellI;
else //BNE
i000 = cellI - nCellXYZ_[0] * nCellXYZ_[1];
}
else
{
if (c > 0.) //FSE
i000 = cellI - nCellXYZ_[0];
else //BSE
i000 = cellI - nCellXYZ_[0] - nCellXYZ_[0] * nCellXYZ_[1];
}
}
else
{
if (b > 0.)
{
if (c > 0.) //FNW
i000 = cellI - 1;
else //BNW
i000 = cellI - 1 - nCellXYZ_[0] * nCellXYZ_[1];
}
else
{
if (c > 0.) //FSW
i000 = cellI - 1 - nCellXYZ_[0];
else //BSW
i000 = cellI - 1 - nCellXYZ_[0] - nCellXYZ_[0] * nCellXYZ_[1];
}
}
// check boundaries
// TODO different handling for periodic and processor boundaries
pt = particleCloud_.mesh().C()[cellI];
posShift = vector::zero;
if (a > 0.)
{
pt += vector(cellLength_,0.,0.);
if (pt[0] > bb_.max()[0])
{
--i000;
posShift[0] = -a;
}
}
else
{
pt -= vector(cellLength_,0.,0.);
if (pt[0] < bb_.min()[0])
{
++i000;
posShift[0] = -a;
}
}
if (b > 0.)
{
pt += vector(0.,cellLength_,0.);
if (pt[1] > bb_.max()[1])
{
i000 -= nCellXYZ_[0];
posShift[1] = -b;
}
}
else
{
pt -= vector(0.,cellLength_,0.);
if (pt[1] < bb_.min()[1])
{
i000 += nCellXYZ_[0];
posShift[1] = -b;
}
}
if (c > 0.)
{
pt += vector(0.,0.,cellLength_);
if (pt[2] > bb_.max()[2])
{
i000 -= nCellXYZ_[0] * nCellXYZ_[1];
posShift[2] = -c;
}
}
else
{
pt -= vector(0.,0.,cellLength_);
if (pt[2] < bb_.min()[2])
{
i000 += nCellXYZ_[0] * nCellXYZ_[1];
posShift[2] = -c;
}
}
// define other 7 indices
i100 = i000 + 1;
i110 = i100 + nCellXYZ_[0];
i010 = i000 + nCellXYZ_[0];
i001 = i000 + nCellXYZ_[0] * nCellXYZ_[1];
i101 = i100 + nCellXYZ_[0] * nCellXYZ_[1];
i111 = i110 + nCellXYZ_[0] * nCellXYZ_[1];
i011 = i010 + nCellXYZ_[0] * nCellXYZ_[1];
// find x,y,z
// TODO changes needed here when generalized for quader cells
offsetOrigin = particleCloud_.mesh().C()[i000] - (partPos + posShift);
x = mag(offsetOrigin[0]) / cellLength_;
y = mag(offsetOrigin[1]) / cellLength_;
z = mag(offsetOrigin[2]) / cellLength_;
// calculate the mapping coeffs
C000 = (1 - x) * (1 - y) * (1 - z);
C100 = x * (1 - y) * (1 - z);
C110 = x * y * (1 - z);
C010 = (1 - x) * y * (1 - z);
C001 = (1 - x) * (1 - y) * z;
C101 = x * (1 - y) * z;
C111 = x * y * z;
C011 = (1 - x) * y * z;
// set weights
particleWeights[index][0] = C000;
particleWeights[index][1] = C100;
particleWeights[index][2] = C110;
particleWeights[index][3] = C010;
particleWeights[index][4] = C001;
particleWeights[index][5] = C101;
particleWeights[index][6] = C111;
particleWeights[index][7] = C011;
// set cellIDs
particleCloud_.cellIDs()[index][0] = i000;
particleCloud_.cellIDs()[index][1] = i100;
particleCloud_.cellIDs()[index][2] = i110;
particleCloud_.cellIDs()[index][3] = i010;
particleCloud_.cellIDs()[index][4] = i001;
particleCloud_.cellIDs()[index][5] = i101;
particleCloud_.cellIDs()[index][6] = i111;
particleCloud_.cellIDs()[index][7] = i011;
//distribute volume
// TODO use different cell volume when generalized for quader cells
voidfractionNext_[i000] -= volume*C000 / cellVol_;
voidfractionNext_[i100] -= volume*C100 / cellVol_;
voidfractionNext_[i010] -= volume*C010 / cellVol_;
voidfractionNext_[i001] -= volume*C001 / cellVol_;
voidfractionNext_[i101] -= volume*C101 / cellVol_;
voidfractionNext_[i011] -= volume*C011 / cellVol_;
voidfractionNext_[i110] -= volume*C110 / cellVol_;
voidfractionNext_[i111] -= volume*C111 / cellVol_;
// debugging
/*Pout << "cellI=" << cellI << endl;
Pout << "a=" << a << endl;
Pout << "b=" << b << endl;
Pout << "c=" << c << endl;
Pout << "x=" << x << endl;
Pout << "y=" << y << endl;
Pout << "z=" << z << endl;
Pout << "i000=" << i000 << endl;
Pout << "i100=" << i100 << endl;
Pout << "i010=" << i010 << endl;
Pout << "i001=" << i001 << endl;
Pout << "i101=" << i101 << endl;
Pout << "i011=" << i011 << endl;
Pout << "i110=" << i110 << endl;
Pout << "i111=" << i111 << endl;
Pout << "C000=" << C000 << endl;
Pout << "C100=" << C100 << endl;
Pout << "C010=" << C010 << endl;
Pout << "C001=" << C001 << endl;
Pout << "C101=" << C101 << endl;
Pout << "C011=" << C011 << endl;
Pout << "C110=" << C110 << endl;
Pout << "C111=" << C111 << endl;
Pout << "sum(Cijk)=" << C000+C100+C010+C001+C101+C011+C110+C111 << endl;*/
/*voidfractionNext_[i000]=0.999;
voidfractionNext_[i100]=0.999;
voidfractionNext_[i010]=0.999;
voidfractionNext_[i001]=0.999;
voidfractionNext_[i101]=0.999;
voidfractionNext_[i011]=0.999;
voidfractionNext_[i110]=0.999;
voidfractionNext_[i111]=0.999;*/
// limit volumefraction
// TODO implement limiter for all 8 indices
/*if(voidfractionNext_[cellI] < alphaMin_ )
{
voidfractionNext_[cellI] = alphaMin_;
alphaLimited = true;
}
if(index==0 && alphaLimited) Info<<"alpha limited to" <<alphaMin_<<endl;*/
// store voidFraction for each particle
voidfractions[index][0] = voidfractionNext_[cellI];
// store cellweight for each particle - this should not live here
particleWeights[index][0] = 1.;
}
}
voidfractionNext_.correctBoundaryConditions();
// bring voidfraction from Eulerian Field to particle array
for (int index = 0; index < particleCloud_.numberOfParticles(); ++index)
{
label cellID = particleCloud_.cellIDs()[index][0];
if (cellID >= 0)
{
voidfractions[index][0] = voidfractionNext_[i000];
voidfractions[index][1] = voidfractionNext_[i100];
voidfractions[index][2] = voidfractionNext_[i110];
voidfractions[index][3] = voidfractionNext_[i010];
voidfractions[index][4] = voidfractionNext_[i001];
voidfractions[index][5] = voidfractionNext_[i101];
voidfractions[index][6] = voidfractionNext_[i111];
voidfractions[index][7] = voidfractionNext_[i011];
}
else
{
for (int i = 0; i < 8; ++i)
voidfractions[index][i] = -1.;
}
}
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
} // End namespace Foam
// ************************************************************************* //

View File

@ -0,0 +1,103 @@
/*---------------------------------------------------------------------------*\
CFDEMcoupling - Open Source CFD-DEM coupling
CFDEMcoupling is part of the CFDEMproject
www.cfdem.com
Christoph Goniva, christoph.goniva@cfdem.com
Copyright 2012- DCS Computing GmbH, Linz
-------------------------------------------------------------------------------
License
This file is part of CFDEMcoupling.
CFDEMcoupling is free software; you can redistribute it and/or modify it
under the terms of the GNU General Public License as published by the
Free Software Foundation; either version 3 of the License, or (at your
option) any later version.
CFDEMcoupling is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
for more details.
You should have received a copy of the GNU General Public License
along with CFDEMcoupling; if not, write to the Free Software Foundation,
Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
Description
This code is designed to realize coupled CFD-DEM simulations using LIGGGHTS
and OpenFOAM(R). Note: this code is not part of OpenFOAM(R) (see DISCLAIMER).
Class
trilinearVoidFraction
SourceFiles
trilinearVoidFraction.C
\*---------------------------------------------------------------------------*/
#ifndef trilinearVoidFraction_H
#define trilinearVoidFraction_H
#include "voidFractionModel.H"
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
namespace Foam
{
/*---------------------------------------------------------------------------*\
Class trilinearVoidFraction Declaration
\*---------------------------------------------------------------------------*/
class trilinearVoidFraction
:
public voidFractionModel
{
private:
dictionary propsDict_;
const scalar alphaMin_;
boundBox bb_;
scalar cellVol_;
scalar cellLength_;
vector nCellXYZ_;
public:
//- Runtime type information
TypeName("trilinear");
// Constructors
//- Construct from components
trilinearVoidFraction
(
const dictionary& dict,
cfdemCloud& sm
);
// Destructor
~trilinearVoidFraction();
// Member Functions
void setvoidFraction(double** const& ,double**&, double**&, double**&, double**&) const;
};
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
} // End namespace Foam
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
#endif
// ************************************************************************* //

View File

@ -32,7 +32,6 @@ Description
#include "error.H" #include "error.H"
#include "voidFractionModel.H" #include "voidFractionModel.H"
#include "centreVoidFraction.H"
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //

View File

@ -100,70 +100,38 @@ voidFractionModel::~voidFractionModel()
} }
// * * * * * * * * * * * * * * public Member Functions * * * * * * * * * * * * * // // * * * * * * * * * * * * * * public Member Functions * * * * * * * * * * * * * //
tmp<volScalarField> Foam::voidFractionModel::voidFractionInterp() const tmp<volScalarField> voidFractionModel::voidFractionInterp() const
{ {
tmp<volScalarField> tsource
(
new volScalarField
(
IOobject
(
"alpha_voidFractionModel",
particleCloud_.mesh().time().timeName(),
particleCloud_.mesh(),
IOobject::NO_READ,
IOobject::NO_WRITE
),
particleCloud_.mesh(),
dimensionedScalar
(
"zero",
dimensionSet(0, 0, 0, 0, 0),
0
)
)
);
scalar tsf = particleCloud_.dataExchangeM().timeStepFraction(); scalar tsf = particleCloud_.dataExchangeM().timeStepFraction();
if(1-tsf < 1e-4 && particleCloud_.dataExchangeM().couplingStep() > 1) //tsf==1
if (1. - tsf < 1e-4 && particleCloud_.dataExchangeM().couplingStep() > 1) //tsf==1
{ {
tsource.ref() = voidfractionPrev_; return tmp<volScalarField>
(
new volScalarField("alpha_voidFractionModel", voidfractionPrev_)
);
} }
else else
{ {
tsource.ref() = (1 - tsf) * voidfractionPrev_ + tsf * voidfractionNext_; return tmp<volScalarField>
(
new volScalarField("alpha_voidFractionModel", (1. - tsf) * voidfractionPrev_ + tsf * voidfractionNext_)
);
} }
return tsource;
} }
void Foam::voidFractionModel::resetVoidFractions() const void voidFractionModel::resetVoidFractions() const
{ {
voidfractionPrev_.ref() = voidfractionNext_.ref(); voidfractionPrev_.ref() = voidfractionNext_.ref();
voidfractionNext_.ref() = 1; voidfractionNext_.ref() = 1.;
} }
/*void Foam::voidFractionModel::undoVoidFractions(double**const& mask) const
{
voidfractionPrev_.internalField() = voidfractionNext_.internalField();
for(int index=0; index< particleCloud_.numberOfParticles(); index++)
{
if(mask[index][0])
{
// undo voidfraction cause by particle
label cellI = particleCloud_.cellIDs()[index][0];
scalar cellVolume=voidfractionNext_.mesh().V()[cellI];
voidfractionNext_[cellI] += particleCloud_.particleVolumes()[index][0]/cellVolume;
}
}
}*/
int** const& voidFractionModel::cellsPerParticle() const int** const& voidFractionModel::cellsPerParticle() const
{ {
return cellsPerParticle_; return cellsPerParticle_;
} }
int Foam::voidFractionModel::maxCellsPerParticle() const int voidFractionModel::maxCellsPerParticle() const
{ {
return maxCellsPerParticle_; return maxCellsPerParticle_;
} }
@ -186,6 +154,60 @@ void voidFractionModel::reAllocArrays(int nP) const
} }
} }
scalar voidFractionModel::pointInParticle(int index, const vector& positionCenter, const vector& point, double scale) const
{
const scalar radius = particleCloud_.radius(index);
if(radius > SMALL)
{
scalar pointDistSq = magSqr(point - positionCenter);
return pointDistSq / (scale*scale * radius*radius) - 1.0;
}
else
{
return 0.;
}
}
//Function to determine minimal distance of point
//to one of the periodic images of a particle
scalar voidFractionModel::minPeriodicDistance(int index,
const vector& cellCentrePosition,
const vector& positionCenter,
const boundBox& globalBb,
vector& minPeriodicPos) const
{
scalar f = VGREAT;
vector positionCenterPeriodic;
for(label xDir=-1; xDir<=1; ++xDir)
{
positionCenterPeriodic[0] = positionCenter[0]
+ static_cast<scalar>(xDir)
* (globalBb.max()[0]-globalBb.min()[0]);
for(label yDir=-1; yDir<=1; ++yDir)
{
positionCenterPeriodic[1] = positionCenter[1]
+ static_cast<scalar>(yDir)
* (globalBb.max()[1]-globalBb.min()[1]);
for(label zDir=-1; zDir<=1; ++zDir)
{
positionCenterPeriodic[2] = positionCenter[2]
+ static_cast<scalar>(zDir)
* (globalBb.max()[2]-globalBb.min()[2]);
if(pointInParticle(index, positionCenterPeriodic, cellCentrePosition) < f)
{
f = pointInParticle(index, positionCenterPeriodic, cellCentrePosition);
minPeriodicPos = positionCenterPeriodic;
}
}
}
}
return f;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
} // End namespace Foam } // End namespace Foam

View File

@ -155,6 +155,17 @@ public:
virtual void setParticleType(label type) const {} virtual void setParticleType(label type) const {}
virtual bool checkParticleType(label) const { return true; } //consider all particles by default virtual bool checkParticleType(label) const { return true; } //consider all particles by default
virtual scalar minPeriodicDistance
(
int index,
const vector& cellCentrePosition,
const vector& positionCenter,
const boundBox& globalBb,
vector& minPeriodicPos
) const;
virtual scalar pointInParticle(int index, const vector& positionCenter, const vector& point, double scale=1.0) const;
}; };