multiphaseSystem.C
Go to the documentation of this file.
1 /*---------------------------------------------------------------------------*\
2  ========= |
3  \\ / F ield | OpenFOAM: The Open Source CFD Toolbox
4  \\ / O peration |
5  \\ / A nd | www.openfoam.com
6  \\/ M anipulation |
7 -------------------------------------------------------------------------------
8  Copyright (C) 2011-2018 OpenFOAM Foundation
9  Copyright (C) 2020 OpenCFD Ltd.
10 -------------------------------------------------------------------------------
11 License
12  This file is part of OpenFOAM.
13 
14  OpenFOAM is free software: you can redistribute it and/or modify it
15  under the terms of the GNU General Public License as published by
16  the Free Software Foundation, either version 3 of the License, or
17  (at your option) any later version.
18 
19  OpenFOAM is distributed in the hope that it will be useful, but WITHOUT
20  ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
21  FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
22  for more details.
23 
24  You should have received a copy of the GNU General Public License
25  along with OpenFOAM. If not, see <http://www.gnu.org/licenses/>.
26 
27 \*---------------------------------------------------------------------------*/
28 
29 #include "multiphaseSystem.H"
30 #include "alphaContactAngleFvPatchScalarField.H"
32 #include "Time.H"
33 #include "subCycle.H"
34 #include "MULES.H"
35 #include "surfaceInterpolate.H"
36 #include "fvcGrad.H"
37 #include "fvcSnGrad.H"
38 #include "fvcDiv.H"
39 #include "fvcFlux.H"
40 #include "fvcAverage.H"
41 
42 #include "unitConversion.H"
43 
44 // * * * * * * * * * * * * * Private Member Functions * * * * * * * * * * * //
45 
46 void Foam::multiphaseSystem::calcAlphas()
47 {
48  scalar level = 0.0;
49  alphas_ == 0.0;
50 
51  for (const phaseModel& phase : phases_)
52  {
53  alphas_ += level * phase;
54  level += 1.0;
55  }
56 }
57 
58 
59 void Foam::multiphaseSystem::solveAlphas()
60 {
61  PtrList<surfaceScalarField> alphaPhiCorrs(phases_.size());
62  int phasei = 0;
63 
64  for (phaseModel& phase : phases_)
65  {
66  volScalarField& alpha1 = phase;
67 
68  alphaPhiCorrs.set
69  (
70  phasei,
72  (
73  "phi" + alpha1.name() + "Corr",
74  fvc::flux
75  (
76  phi_,
77  phase,
78  "div(phi," + alpha1.name() + ')'
79  )
80  )
81  );
82 
83  surfaceScalarField& alphaPhiCorr = alphaPhiCorrs[phasei];
84 
85  for (phaseModel& phase2 : phases_)
86  {
88 
89  if (&phase2 == &phase) continue;
90 
91  surfaceScalarField phir(phase.phi() - phase2.phi());
92 
93  const auto cAlpha = cAlphas_.cfind(interfacePair(phase, phase2));
94 
95  if (cAlpha.found())
96  {
98  (
99  (mag(phi_) + mag(phir))/mesh_.magSf()
100  );
101 
102  phir += min(cAlpha()*phic, max(phic))*nHatf(phase, phase2);
103  }
104 
105  const word phirScheme
106  (
107  "div(phir," + alpha2.name() + ',' + alpha1.name() + ')'
108  );
109 
110  alphaPhiCorr += fvc::flux
111  (
112  -fvc::flux(-phir, phase2, phirScheme),
113  phase,
114  phirScheme
115  );
116  }
117 
118  phase.correctInflowOutflow(alphaPhiCorr);
119 
121  (
122  1.0/mesh_.time().deltaT().value(),
123  geometricOneField(),
124  phase,
125  phi_,
126  alphaPhiCorr,
127  zeroField(),
128  zeroField(),
129  oneField(),
130  zeroField(),
131  true
132  );
133 
134  ++phasei;
135  }
136 
137  MULES::limitSum(alphaPhiCorrs);
138 
139  volScalarField sumAlpha
140  (
141  IOobject
142  (
143  "sumAlpha",
144  mesh_.time().timeName(),
145  mesh_
146  ),
147  mesh_,
148  dimensionedScalar("sumAlpha", dimless, 0)
149  );
150 
151  phasei = 0;
152 
153  for (phaseModel& phase : phases_)
154  {
155  surfaceScalarField& alphaPhi = alphaPhiCorrs[phasei];
156  alphaPhi += upwind<scalar>(mesh_, phi_).flux(phase);
158 
160  (
161  geometricOneField(),
162  phase,
163  alphaPhi
164  );
165 
166  phase.alphaPhi() = alphaPhi;
167 
168  Info<< phase.name() << " volume fraction, min, max = "
169  << phase.weightedAverage(mesh_.V()).value()
170  << ' ' << min(phase).value()
171  << ' ' << max(phase).value()
172  << endl;
173 
174  sumAlpha += phase;
175 
176  ++phasei;
177  }
178 
179  Info<< "Phase-sum volume fraction, min, max = "
180  << sumAlpha.weightedAverage(mesh_.V()).value()
181  << ' ' << min(sumAlpha).value()
182  << ' ' << max(sumAlpha).value()
183  << endl;
184 
185  // Correct the sum of the phase-fractions to avoid 'drift'
186  volScalarField sumCorr(1.0 - sumAlpha);
187  for (phaseModel& phase : phases_)
188  {
189  volScalarField& alpha = phase;
190  alpha += alpha*sumCorr;
191  }
192 
193  calcAlphas();
194 }
195 
196 
197 Foam::tmp<Foam::surfaceVectorField> Foam::multiphaseSystem::nHatfv
198 (
199  const volScalarField& alpha1,
200  const volScalarField& alpha2
201 ) const
202 {
203  /*
204  // Cell gradient of alpha
205  volVectorField gradAlpha =
206  alpha2*fvc::grad(alpha1) - alpha1*fvc::grad(alpha2);
207 
208  // Interpolated face-gradient of alpha
209  surfaceVectorField gradAlphaf = fvc::interpolate(gradAlpha);
210  */
211 
212  surfaceVectorField gradAlphaf
213  (
216  );
217 
218  // Face unit interface normal
219  return gradAlphaf/(mag(gradAlphaf) + deltaN_);
220 }
221 
222 
223 Foam::tmp<Foam::surfaceScalarField> Foam::multiphaseSystem::nHatf
224 (
225  const volScalarField& alpha1,
226  const volScalarField& alpha2
227 ) const
228 {
229  // Face unit interface normal flux
230  return nHatfv(alpha1, alpha2) & mesh_.Sf();
231 }
232 
233 
234 // Correction for the boundary condition on the unit normal nHat on
235 // walls to produce the correct contact angle.
236 
237 // The dynamic contact angle is calculated from the component of the
238 // velocity on the direction of the interface, parallel to the wall.
239 
240 void Foam::multiphaseSystem::correctContactAngle
241 (
242  const phaseModel& phase1,
243  const phaseModel& phase2,
244  surfaceVectorField::Boundary& nHatb
245 ) const
246 {
247  const volScalarField::Boundary& gbf
248  = phase1.boundaryField();
249 
250  const fvBoundaryMesh& boundary = mesh_.boundary();
251 
252  forAll(boundary, patchi)
253  {
254  if (isA<alphaContactAngleFvPatchScalarField>(gbf[patchi]))
255  {
256  const alphaContactAngleFvPatchScalarField& acap =
257  refCast<const alphaContactAngleFvPatchScalarField>(gbf[patchi]);
258 
259  vectorField& nHatPatch = nHatb[patchi];
260 
261  vectorField AfHatPatch
262  (
263  mesh_.Sf().boundaryField()[patchi]
264  /mesh_.magSf().boundaryField()[patchi]
265  );
266 
267  const auto tp =
268  acap.thetaProps().cfind(interfacePair(phase1, phase2));
269 
270  if (!tp.found())
271  {
273  << "Cannot find interface " << interfacePair(phase1, phase2)
274  << "\n in table of theta properties for patch "
275  << acap.patch().name()
276  << exit(FatalError);
277  }
278 
279  bool matched = (tp.key().first() == phase1.name());
280 
281  const scalar theta0 = degToRad(tp().theta0(matched));
282  scalarField theta(boundary[patchi].size(), theta0);
283 
284  scalar uTheta = tp().uTheta();
285 
286  // Calculate the dynamic contact angle if required
287  if (uTheta > SMALL)
288  {
289  const scalar thetaA = degToRad(tp().thetaA(matched));
290  const scalar thetaR = degToRad(tp().thetaR(matched));
291 
292  // Calculated the component of the velocity parallel to the wall
293  vectorField Uwall
294  (
295  phase1.U().boundaryField()[patchi].patchInternalField()
296  - phase1.U().boundaryField()[patchi]
297  );
298  Uwall -= (AfHatPatch & Uwall)*AfHatPatch;
299 
300  // Find the direction of the interface parallel to the wall
301  vectorField nWall
302  (
303  nHatPatch - (AfHatPatch & nHatPatch)*AfHatPatch
304  );
305 
306  // Normalise nWall
307  nWall /= (mag(nWall) + SMALL);
308 
309  // Calculate Uwall resolved normal to the interface parallel to
310  // the interface
311  scalarField uwall(nWall & Uwall);
312 
313  theta += (thetaA - thetaR)*tanh(uwall/uTheta);
314  }
315 
316 
317  // Reset nHatPatch to correspond to the contact angle
318 
319  scalarField a12(nHatPatch & AfHatPatch);
320 
321  scalarField b1(cos(theta));
322 
323  scalarField b2(nHatPatch.size());
324 
325  forAll(b2, facei)
326  {
327  b2[facei] = cos(acos(a12[facei]) - theta[facei]);
328  }
329 
330  scalarField det(1.0 - a12*a12);
331 
332  scalarField a((b1 - a12*b2)/det);
333  scalarField b((b2 - a12*b1)/det);
334 
335  nHatPatch = a*AfHatPatch + b*nHatPatch;
336 
337  nHatPatch /= (mag(nHatPatch) + deltaN_.value());
338  }
339  }
340 }
341 
342 
343 Foam::tmp<Foam::volScalarField> Foam::multiphaseSystem::K
344 (
345  const phaseModel& phase1,
346  const phaseModel& phase2
347 ) const
348 {
349  tmp<surfaceVectorField> tnHatfv = nHatfv(phase1, phase2);
350 
351  correctContactAngle(phase1, phase2, tnHatfv.ref().boundaryFieldRef());
352 
353  // Simple expression for curvature
354  return -fvc::div(tnHatfv & mesh_.Sf());
355 }
356 
357 
358 // * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * //
359 
361 (
362  const volVectorField& U,
363  const surfaceScalarField& phi
364 )
365 :
367  (
368  IOobject
369  (
370  "transportProperties",
371  U.time().constant(),
372  U.db(),
375  )
376  ),
377 
378  phases_(lookup("phases"), phaseModel::iNew(U.mesh())),
379 
380  mesh_(U.mesh()),
381  phi_(phi),
382 
383  alphas_
384  (
385  IOobject
386  (
387  "alphas",
388  mesh_.time().timeName(),
389  mesh_,
392  ),
393  mesh_,
394  dimensionedScalar("alphas", dimless, 0.0)
395  ),
396 
397  sigmas_(lookup("sigmas")),
398  dimSigma_(1, 0, -2, 0, 0),
399  cAlphas_(lookup("interfaceCompression")),
400  Cvms_(lookup("virtualMass")),
401  deltaN_
402  (
403  "deltaN",
404  1e-8/cbrt(average(mesh_.V()))
405  )
406 {
407  calcAlphas();
408  alphas_.write();
409 
410  interfaceDictTable dragModelsDict(lookup("drag"));
411 
412  forAllConstIters(dragModelsDict, iter)
413  {
414  dragModels_.set
415  (
416  iter.key(),
418  (
419  iter(),
420  *phases_.lookup(iter.key().first()),
421  *phases_.lookup(iter.key().second())
422  ).ptr()
423  );
424  }
425 
426  for (const phaseModel& phase1 : phases_)
427  {
428  for (const phaseModel& phase2 : phases_)
429  {
430  if (&phase2 == &phase1)
431  {
432  continue;
433  }
434 
435  const interfacePair key(phase1, phase2);
436 
437  if (sigmas_.found(key) && !cAlphas_.found(key))
438  {
440  << "Compression coefficient not specified for phase pair ("
441  << phase1.name() << ' ' << phase2.name()
442  << ") for which a surface tension coefficient is specified"
443  << endl;
444  }
445  }
446  }
447 }
448 
449 
450 // * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * * //
451 
453 {
454  auto iter = phases_.cbegin();
455 
456  tmp<volScalarField> trho = iter()*iter().rho();
457  volScalarField& rho = trho.ref();
458 
459  for (++iter; iter != phases_.cend(); ++iter)
460  {
461  rho += iter()*iter().rho();
462  }
463 
464  return trho;
465 }
466 
467 
469 Foam::multiphaseSystem::rho(const label patchi) const
470 {
471  auto iter = phases_.cbegin();
472 
473  tmp<scalarField> trho = iter().boundaryField()[patchi]*iter().rho().value();
474  scalarField& rho = trho.ref();
475 
476  for (++iter; iter != phases_.cend(); ++iter)
477  {
478  rho += iter().boundaryField()[patchi]*iter().rho().value();
479  }
480 
481  return trho;
482 }
483 
484 
486 {
487  auto iter = phases_.cbegin();
488 
489  tmp<volScalarField> tmu = iter()*(iter().rho()*iter().nu());
490  volScalarField& mu = tmu.ref();
491 
492  for (++iter; iter != phases_.cend(); ++iter)
493  {
494  mu += iter()*(iter().rho()*iter().nu());
495  }
496 
497  return tmu/rho();
498 }
499 
500 
502 Foam::multiphaseSystem::nu(const label patchi) const
503 {
504  auto iter = phases_.cbegin();
505 
506  tmp<scalarField> tmu =
507  iter().boundaryField()[patchi]
508  *(iter().rho().value()*iter().nu().value());
509  scalarField& mu = tmu.ref();
510 
511  for (++iter; iter != phases_.cend(); ++iter)
512  {
513  mu +=
514  iter().boundaryField()[patchi]
515  *(iter().rho().value()*iter().nu().value());
516  }
517 
518  return tmu/rho(patchi);
519 }
520 
521 
523 (
524  const phaseModel& phase
525 ) const
526 {
528  (
529  new volScalarField
530  (
531  IOobject
532  (
533  "Cvm",
534  mesh_.time().timeName(),
535  mesh_
536  ),
537  mesh_,
539  )
540  );
541 
542  for (const phaseModel& phase2 : phases_)
543  {
544  if (&phase2 == &phase)
545  {
546  continue;
547  }
548 
549  auto iterCvm = Cvms_.cfind(interfacePair(phase, phase2));
550 
551  if (iterCvm.found())
552  {
553  tCvm.ref() += iterCvm()*phase2.rho()*phase2;
554  }
555  else
556  {
557  iterCvm = Cvms_.cfind(interfacePair(phase2, phase));
558 
559  if (iterCvm.found())
560  {
561  tCvm.ref() += iterCvm()*phase.rho()*phase2;
562  }
563  }
564  }
565 
566  return tCvm;
567 }
568 
569 
571 (
572  const phaseModel& phase
573 ) const
574 {
576  (
577  new volVectorField
578  (
579  IOobject
580  (
581  "Svm",
582  mesh_.time().timeName(),
583  mesh_
584  ),
585  mesh_,
587  (
588  "Svm",
589  dimensionSet(1, -2, -2, 0, 0),
590  Zero
591  )
592  )
593  );
594 
595  for (const phaseModel& phase2 : phases_)
596  {
597  if (&phase2 == &phase)
598  {
599  continue;
600  }
601 
602  auto Cvm = Cvms_.cfind(interfacePair(phase, phase2));
603 
604  if (Cvm.found())
605  {
606  tSvm.ref() += Cvm()*phase2.rho()*phase2*phase2.DDtU();
607  }
608  else
609  {
610  Cvm = Cvms_.cfind(interfacePair(phase2, phase));
611 
612  if (Cvm.found())
613  {
614  tSvm.ref() += Cvm()*phase.rho()*phase2*phase2.DDtU();
615  }
616  }
617  }
618 
619  volVectorField::Boundary& SvmBf =
620  tSvm.ref().boundaryFieldRef();
621 
622  // Remove virtual mass at fixed-flux boundaries
623  forAll(phase.phi().boundaryField(), patchi)
624  {
625  if
626  (
627  isA<fixedValueFvsPatchScalarField>
628  (
629  phase.phi().boundaryField()[patchi]
630  )
631  )
632  {
633  SvmBf[patchi] = Zero;
634  }
635  }
636 
637  return tSvm;
638 }
639 
640 
643 {
644  autoPtr<dragCoeffFields> dragCoeffsPtr(new dragCoeffFields);
645 
646  forAllConstIters(dragModels_, iter)
647  {
648  const dragModel& dm = *iter();
649 
650  volScalarField* Kptr =
651  (
652  max
653  (
654  // fvc::average(dm.phase1()*dm.phase2()),
655  // fvc::average(dm.phase1())*fvc::average(dm.phase2()),
656  dm.phase1()*dm.phase2(),
658  )
659  *dm.K
660  (
661  max
662  (
663  mag(dm.phase1().U() - dm.phase2().U()),
664  dm.residualSlip()
665  )
666  )
667  ).ptr();
668 
669  volScalarField::Boundary& Kbf = Kptr->boundaryFieldRef();
670 
671  // Remove drag at fixed-flux boundaries
672  forAll(dm.phase1().phi().boundaryField(), patchi)
673  {
674  if
675  (
676  isA<fixedValueFvsPatchScalarField>
677  (
678  dm.phase1().phi().boundaryField()[patchi]
679  )
680  )
681  {
682  Kbf[patchi] = 0.0;
683  }
684  }
685 
686  dragCoeffsPtr().set(iter.key(), Kptr);
687  }
688 
689  return dragCoeffsPtr;
690 }
691 
692 
694 (
695  const phaseModel& phase,
697 ) const
698 {
699  tmp<volScalarField> tdragCoeff
700  (
701  new volScalarField
702  (
703  IOobject
704  (
705  "dragCoeff",
706  mesh_.time().timeName(),
707  mesh_
708  ),
709  mesh_,
711  (
712  "dragCoeff",
713  dimensionSet(1, -3, -1, 0, 0),
714  0
715  )
716  )
717  );
718 
719  dragModelTable::const_iterator dmIter = dragModels_.begin();
721  for
722  (
723  ;
724  dmIter.good() && dcIter.good();
725  ++dmIter, ++dcIter
726  )
727  {
728  if
729  (
730  &phase == &dmIter()->phase1()
731  || &phase == &dmIter()->phase2()
732  )
733  {
734  tdragCoeff.ref() += *dcIter();
735  }
736  }
737 
738  return tdragCoeff;
739 }
740 
741 
743 (
744  const phaseModel& phase1
745 ) const
746 {
747  tmp<surfaceScalarField> tSurfaceTension
748  (
750  (
751  IOobject
752  (
753  "surfaceTension",
754  mesh_.time().timeName(),
755  mesh_
756  ),
757  mesh_,
759  (
760  "surfaceTension",
761  dimensionSet(1, -2, -2, 0, 0),
762  0
763  )
764  )
765  );
766  tSurfaceTension.ref().setOriented();
767 
768  for (const phaseModel& phase2 : phases_)
769  {
770  if (&phase2 == &phase1)
771  {
772  continue;
773  }
774 
775  const auto sigma = sigmas_.cfind(interfacePair(phase1, phase2));
776 
777  if (sigma.found())
778  {
779  tSurfaceTension.ref() +=
780  dimensionedScalar("sigma", dimSigma_, *sigma)
782  (
785  );
786  }
787  }
788 
789  return tSurfaceTension;
790 }
791 
792 
795 {
796  tmp<volScalarField> tnearInt
797  (
798  new volScalarField
799  (
800  IOobject
801  (
802  "nearInterface",
803  mesh_.time().timeName(),
804  mesh_
805  ),
806  mesh_,
807  dimensionedScalar("nearInterface", dimless, 0.0)
808  )
809  );
810 
811  for (const phaseModel& phase : phases_)
812  {
813  tnearInt.ref() =
814  max(tnearInt(), pos0(phase - 0.01)*pos0(0.99 - phase));
815  }
816 
817  return tnearInt;
818 }
819 
820 
822 {
823  for (phaseModel& phase : phases_)
824  {
825  phase.correct();
826  }
827 
828  const Time& runTime = mesh_.time();
829 
830  const dictionary& alphaControls = mesh_.solverDict("alpha");
831  label nAlphaSubCycles(alphaControls.get<label>("nAlphaSubCycles"));
832 
833  if (nAlphaSubCycles > 1)
834  {
835  dimensionedScalar totalDeltaT = runTime.deltaT();
836 
837  PtrList<volScalarField> alpha0s(phases_.size());
838  PtrList<surfaceScalarField> alphaPhiSums(phases_.size());
839 
840  label phasei = 0;
841  for (phaseModel& phase : phases_)
842  {
844 
845  alpha0s.set
846  (
847  phasei,
848  new volScalarField(alpha.oldTime())
849  );
850 
851  alphaPhiSums.set
852  (
853  phasei,
855  (
856  IOobject
857  (
858  "phiSum" + alpha.name(),
859  runTime.timeName(),
860  mesh_
861  ),
862  mesh_,
863  dimensionedScalar("0", dimensionSet(0, 3, -1, 0, 0), 0)
864  )
865  );
866 
867  ++phasei;
868  }
869 
870  for
871  (
872  subCycleTime alphaSubCycle
873  (
874  const_cast<Time&>(runTime),
876  );
877  !(++alphaSubCycle).end();
878  )
879  {
880  solveAlphas();
881 
882  label phasei = 0;
883  for (const phaseModel& phase : phases_)
884  {
885  alphaPhiSums[phasei] += phase.alphaPhi()/nAlphaSubCycles;
886 
887  ++phasei;
888  }
889  }
890 
891  phasei = 0;
892  for (phaseModel& phase : phases_)
893  {
895 
896  phase.alphaPhi() = alphaPhiSums[phasei];
897 
898  // Correct the time index of the field
899  // to correspond to the global time
900  alpha.timeIndex() = runTime.timeIndex();
901 
902  // Reset the old-time field value
903  alpha.oldTime() = alpha0s[phasei];
904  alpha.oldTime().timeIndex() = runTime.timeIndex();
905 
906  ++phasei;
907  }
908  }
909  else
910  {
911  solveAlphas();
912  }
913 }
914 
915 
917 {
918  if (regIOobject::read())
919  {
920  bool readOK = true;
921 
922  PtrList<entry> phaseData(lookup("phases"));
923  label phasei = 0;
924 
925  for (phaseModel& phase : phases_)
926  {
927  readOK &= phase.read(phaseData[phasei++].dict());
928  }
929 
930  lookup("sigmas") >> sigmas_;
931  lookup("interfaceCompression") >> cAlphas_;
932  lookup("virtualMass") >> Cvms_;
933 
934  return readOK;
935  }
936  else
937  {
938  return false;
939  }
940 }
941 
942 
943 // ************************************************************************* //
Foam::IOobject::NO_WRITE
Definition: IOobject.H:195
Foam::IOdictionary
IOdictionary is derived from dictionary and IOobject to give the dictionary automatic IO functionalit...
Definition: IOdictionary.H:54
runTime
engineTime & runTime
Definition: createEngineTime.H:13
Foam::phaseModel
Single incompressible phase derived from the phase-fraction. Used as part of the multiPhaseMixture fo...
Definition: phaseModel.H:54
Foam::fvc::snGrad
tmp< GeometricField< Type, fvsPatchField, surfaceMesh > > snGrad(const GeometricField< Type, fvPatchField, volMesh > &vf, const word &name)
Definition: fvcSnGrad.C:47
Foam::scalarField
Field< scalar > scalarField
Specialisation of Field<T> for scalar.
Definition: primitiveFieldsFwd.H:52
Foam::multiphaseSystem::nearInterface
tmp< volScalarField > nearInterface() const
Indicator of the proximity of the interface.
Definition: multiphaseSystem.C:794
Foam::IOobject
Defines the attributes of an object for which implicit objectRegistry management is supported,...
Definition: IOobject.H:169
Foam::phase::read
bool read(const dictionary &phaseDict)
Read base transportProperties dictionary.
Foam::IOobject::AUTO_WRITE
Definition: IOobject.H:194
Foam::fvc::flux
tmp< surfaceScalarField > flux(const volVectorField &vvf)
Return the face-flux field obtained from the given volVectorField.
Foam::MULES::explicitSolve
void explicitSolve(const RdeltaTType &rDeltaT, const RhoType &rho, volScalarField &psi, const surfaceScalarField &phiPsi, const SpType &Sp, const SuType &Su)
Definition: MULESTemplates.C:41
Foam::dragModel::phase1
const phaseModel & phase1() const
Definition: dragModel.H:111
Foam::fvc::grad
tmp< GeometricField< typename outerProduct< vector, Type >::type, fvPatchField, volMesh >> grad(const GeometricField< Type, fvsPatchField, surfaceMesh > &ssf)
Definition: fvcGrad.C:54
Foam::Time
Class to control time during OpenFOAM simulations that is also the top-level objectRegistry.
Definition: Time.H:73
Foam::multiphaseSystem::solve
void solve()
Solve for the mixture phase-fractions.
Definition: multiphaseSystem.C:821
Foam::tmp::good
bool good() const noexcept
True if pointer/reference is non-null.
Definition: tmp.H:169
Foam::MULES::limit
void limit(const RdeltaTType &rDeltaT, const RhoType &rho, const volScalarField &psi, const surfaceScalarField &phi, surfaceScalarField &phiPsi, const SpType &Sp, const SuType &Su, const PsiMaxType &psiMax, const PsiMinType &psiMin, const bool returnCorr)
Definition: MULESTemplates.C:581
Foam::TimeState::deltaT
dimensionedScalar deltaT() const
Return time step.
Definition: TimeStateI.H:55
Foam::multiphaseSystem::rho
tmp< volScalarField > rho() const
Return the mixture density.
Definition: multiphaseSystem.C:452
Foam::constant::physicoChemical::mu
const dimensionedScalar mu
Atomic mass unit.
Definition: createFieldRefs.H:4
Foam::phase
Single incompressible phase derived from the phase-fraction. Used as part of the multiPhaseMixture fo...
Definition: phase.H:54
Foam::tmp
A class for managing temporary objects.
Definition: PtrList.H:61
Foam::Zero
static constexpr const zero Zero
Global zero (0)
Definition: zero.H:131
Foam::dimDensity
const dimensionSet dimDensity
Foam::phaseModel::alphaPhi
const surfaceScalarField & alphaPhi() const
Definition: phaseModel.H:202
alpha2
const volScalarField & alpha2
Definition: setRegionFluidFields.H:9
subCycle.H
Foam::constant::atomic::alpha
const dimensionedScalar alpha
Fine-structure constant: default SI units: [].
Definition: readThermalProperties.H:212
fvcSnGrad.H
Calculate the snGrad of the given volField.
Foam::vtk::Tools::zeroField
vtkSmartPointer< vtkFloatArray > zeroField(const word &name, const label size)
Create named field initialized to zero.
Definition: foamVtkToolsTemplates.C:327
Foam::Time::timeName
static word timeName(const scalar t, const int precision=precision_)
Definition: Time.C:780
Foam::multiphaseSystem::interfacePair
Name pair for the interface.
Definition: multiphaseSystem.H:73
Foam::regIOobject::read
virtual bool read()
Read object.
Definition: regIOobjectRead.C:191
Foam::glTF::key
auto key(const Type &t) -> typename std::enable_if< std::is_enum< Type >::value, typename std::underlying_type< Type >::type >::type
Definition: foamGltfBase.H:108
fvcDiv.H
Calculate the divergence of the given field.
Foam::dimensioned::name
const word & name() const
Return const reference to name.
Definition: dimensionedType.C:406
multiphaseSystem.H
unitConversion.H
Unit conversion functions.
Foam::fvc::div
tmp< GeometricField< Type, fvPatchField, volMesh > > div(const GeometricField< Type, fvsPatchField, surfaceMesh > &ssf)
Definition: fvcDiv.C:49
phasei
label phasei
Definition: pEqn.H:27
Foam::endl
Ostream & endl(Ostream &os)
Add newline and flush stream.
Definition: Ostream.H:369
Foam::multiphaseSystem::phase
const phaseModel & phase(const label i) const
Constant access phase model i.
Definition: multiphaseSystem.C:446
Foam::pos0
dimensionedScalar pos0(const dimensionedScalar &ds)
Definition: dimensionedScalar.C:188
alpha1
const volScalarField & alpha1
Definition: setRegionFluidFields.H:8
Foam::dictionary::get
T get(const word &keyword, enum keyType::option matchOpt=keyType::REGEX) const
Definition: dictionaryTemplates.C:107
Foam::dimensionSet
Dimension set for the base types, which can be used to implement rigorous dimension checking for alge...
Definition: dimensionSet.H:108
Foam::multiphaseSystem::surfaceTension
tmp< surfaceScalarField > surfaceTension(const phaseModel &phase) const
Definition: multiphaseSystem.C:743
nAlphaSubCycles
label nAlphaSubCycles(alphaControls.get< label >("nAlphaSubCycles"))
Foam::subCycleTime
A class for managing sub-cycling times.
Definition: subCycleTime.H:50
rho
rho
Definition: readInitialConditions.H:88
Foam::dragModel::phase2
const phaseModel & phase2() const
Definition: dragModel.H:116
Foam::min
label min(const labelHashSet &set, label minValue=labelMax)
Find the min value in labelHashSet, optionally limited by second argument.
Definition: hashSets.C:33
forAll
#define forAll(list, i)
Loop across all elements in list.
Definition: stdFoam.H:296
Foam::vectorField
Field< vector > vectorField
Specialisation of Field<T> for vector.
Definition: primitiveFieldsFwd.H:54
phic
surfaceScalarField phic(mixture.cAlpha() *mag(alphaPhic/mesh.magSf()))
K
CGAL::Exact_predicates_exact_constructions_kernel K
Definition: CGALTriangulation3DKernel.H:58
Foam::phase::correct
void correct()
Correct the phase properties.
trho
tmp< volScalarField > trho
Definition: setRegionSolidFields.H:4
Foam::TimeState::timeIndex
label timeIndex() const noexcept
Return current time index.
Definition: TimeStateI.H:37
Foam::autoPtr::set
void set(T *p) noexcept
Deprecated(2018-02) Identical to reset().
Definition: autoPtr.H:288
Foam::tmp::ref
T & ref() const
Definition: tmpI.H:227
phir
surfaceScalarField phir(fvc::flux(UdmModel.Udm()))
Foam::constant::physicoChemical::b
const dimensionedScalar b
Wien displacement law constant: default SI units: [m.K].
Definition: createFields.H:27
Foam::Field< scalar >
Foam::tanh
dimensionedScalar tanh(const dimensionedScalar &ds)
Definition: dimensionedScalar.C:272
alphaPhi
surfaceScalarField alphaPhi(phi.name()+alpha1.name(), fvc::flux(phi, alpha1, alphaScheme))
Foam::Info
messageStream Info
Information stream (stdout output on master, null elsewhere)
Foam::phaseModel::DDtU
const volVectorField & DDtU() const
Definition: phaseModel.H:182
Foam::MULES::limitSum
void limitSum(UPtrList< scalarField > &phiPsiCorrs)
Definition: MULES.C:34
Foam::multiphaseSystem::dragCoeffs
autoPtr< dragCoeffFields > dragCoeffs() const
Return the drag coefficients for all of the interfaces.
Definition: multiphaseSystem.C:642
dragCoeffs
autoPtr< multiphaseSystem::dragCoeffFields > dragCoeffs(fluid.dragCoeffs())
Foam::dimensionedScalar
dimensioned< scalar > dimensionedScalar
Dimensioned scalar obtained from generic dimensioned type.
Definition: dimensionedScalarFwd.H:42
Foam::PtrList
A list of pointers to objects of type <T>, with allocation/deallocation management of the pointers....
Definition: List.H:59
phi
surfaceScalarField & phi
Definition: setRegionFluidFields.H:8
Foam::volScalarField
GeometricField< scalar, fvPatchField, volMesh > volScalarField
Definition: volFieldsFwd.H:57
Foam::autoPtr::ptr
T * ptr() noexcept
Same as release().
Definition: autoPtr.H:172
Foam::max
label max(const labelHashSet &set, label maxValue=labelMin)
Find the max value in labelHashSet, optionally limited by second argument.
Definition: hashSets.C:47
Foam::radiation::lookup
Lookup type of boundary radiation properties.
Definition: lookup.H:63
Foam::phaseModel::iNew
Return a pointer to a new phase created on freestore.
Definition: phaseModel.H:109
dict
dictionary dict
Definition: searchingEngine.H:14
Foam::dragModel::New
static autoPtr< dragModel > New(const dictionary &dict, const phaseModel &phase1, const phaseModel &phase2)
Definition: dragModel.C:60
fixedValueFvsPatchFields.H
phase2
phaseModel & phase2
Definition: setRegionFluidFields.H:6
Foam::multiphaseSystem::read
bool read()
Read base transportProperties dictionary.
Definition: multiphaseSystem.C:916
Foam::FatalError
error FatalError
Foam::dictionary
A list of keyword definitions, which are a keyword followed by a number of values (eg,...
Definition: dictionary.H:123
Foam::dimensioned< vector >
stdFoam::end
constexpr auto end(C &c) -> decltype(c.end())
Return iterator to the end of the container c.
Definition: stdFoam.H:121
Foam::fvc::interpolate
static tmp< GeometricField< Type, fvsPatchField, surfaceMesh > > interpolate(const GeometricField< Type, fvPatchField, volMesh > &tvf, const surfaceScalarField &faceFlux, Istream &schemeData)
Interpolate field onto faces using scheme given by Istream.
Foam::phaseModel::phi
const surfaceScalarField & phi() const
Definition: phaseModel.H:192
Foam::degToRad
constexpr scalar degToRad(const scalar deg) noexcept
Conversion from degrees to radians.
Definition: unitConversion.H:48
Foam::exit
errorManipArg< error, int > exit(error &err, const int errNo=1)
Definition: errorManip.H:130
Foam::HashTable
A HashTable similar to std::unordered_map.
Definition: HashTable.H:105
Foam::HashPtrTable< dragModel, interfacePair, interfacePair::symmHash >::const_iterator
typename parent_type::const_iterator const_iterator
Definition: HashPtrTable.H:89
Foam::phaseModel::name
const word & name() const
Definition: phaseModel.H:140
Time.H
Foam::autoPtr
Pointer management similar to std::unique_ptr, with some additional methods and type checking.
Definition: HashPtrTable.H:53
U
U
Definition: pEqn.H:72
FatalErrorInFunction
#define FatalErrorInFunction
Report an error message using Foam::FatalError.
Definition: error.H:453
Foam::phaseModel::U
const volVectorField & U() const
Definition: phaseModel.H:172
Foam::phaseModel::correctInflowOutflow
void correctInflowOutflow(surfaceScalarField &alphaPhi) const
Ensure that the flux at inflow/outflow BCs is preserved.
Definition: phaseModel.C:239
forAllConstIters
forAllConstIters(mixture.phases(), phase)
Definition: pEqn.H:28
Foam::dragModel::residualPhaseFraction
const dimensionedScalar & residualPhaseFraction() const
Definition: dragModel.H:121
Foam::HashPtrTable
A HashTable of pointers to objects of type <T>, with deallocation management of the pointers.
Definition: HashPtrTable.H:54
Foam::surfaceScalarField
GeometricField< scalar, fvsPatchField, surfaceMesh > surfaceScalarField
Definition: surfaceFieldsFwd.H:54
Foam::GeometricField::ref
Internal & ref(const bool updateAccessTime=true)
Return a reference to the dimensioned internal field.
Definition: GeometricField.C:749
Foam::dragModel::K
virtual tmp< volScalarField > K(const volScalarField &Ur) const =0
The drag function K used in the momentum eq.
Foam::GeometricField::boundaryFieldRef
Boundary & boundaryFieldRef(const bool updateAccessTime=true)
Return a reference to the boundary field.
Definition: GeometricField.C:783
Foam::acos
dimensionedScalar acos(const dimensionedScalar &ds)
Definition: dimensionedScalar.C:268
fvcGrad.H
Calculate the gradient of the given field.
Foam::mag
dimensioned< typename typeOfMag< Type >::type > mag(const dimensioned< Type > &dt)
fvcFlux.H
Calculate the face-flux of the given field.
Foam::dragModel::residualSlip
const dimensionedScalar & residualSlip() const
Definition: dragModel.H:126
Foam::constant::electromagnetic::e
const dimensionedScalar e
Elementary charge.
Definition: createFields.H:11
Foam::IOobject::MUST_READ_IF_MODIFIED
Definition: IOobject.H:186
Foam::multiphaseSystem::dragCoeff
tmp< volScalarField > dragCoeff(const phaseModel &phase, const dragCoeffFields &dragCoeffs) const
Return the sum of the drag coefficients for the given phase.
Definition: multiphaseSystem.C:694
Foam::dragModel
Definition: dragModel.H:51
Foam::phaseModel::rho
const dimensionedScalar & rho() const
Definition: phaseModel.H:167
Foam::multiphaseSystem::Svm
tmp< volVectorField > Svm(const phaseModel &phase) const
Return the virtual-mass source for the given phase.
Definition: multiphaseSystem.C:571
Foam::det
dimensionedScalar det(const dimensionedSphericalTensor &dt)
Definition: dimensionedSphericalTensor.C:62
sigma
dimensionedScalar sigma("sigma", dimMass/sqr(dimTime), transportProperties)
phase1
phaseModel & phase1
Definition: setRegionFluidFields.H:5
Foam::multiphaseSystem::nu
tmp< volScalarField > nu() const
Return the mixture laminar viscosity.
Definition: multiphaseSystem.C:485
Foam::multiphaseSystem::Cvm
tmp< volScalarField > Cvm(const phaseModel &phase) const
Return the virtual-mass coefficient for the given phase.
Definition: multiphaseSystem.C:523
Foam::surfaceVectorField
GeometricField< vector, fvsPatchField, surfaceMesh > surfaceVectorField
Definition: surfaceFieldsFwd.H:59
Foam::cbrt
dimensionedScalar cbrt(const dimensionedScalar &ds)
Definition: dimensionedScalar.C:155
fvcAverage.H
Area-weighted average a surfaceField creating a volField.
Foam::GeometricField< vector, fvPatchField, volMesh >
MULES.H
MULES: Multidimensional universal limiter for explicit solution.
Foam::IOobject::NO_READ
Definition: IOobject.H:188
WarningInFunction
#define WarningInFunction
Report a warning using Foam::Warning.
Definition: messageStream.H:328
Foam::objectRegistry::time
const Time & time() const noexcept
Return time registry.
Definition: objectRegistry.H:178
boundary
faceListList boundary
Definition: createBlockMesh.H:4
Foam::multiphaseSystem::multiphaseSystem
multiphaseSystem(const volVectorField &U, const surfaceScalarField &phi)
Construct from components.
Definition: multiphaseSystem.C:361
Foam::GeometricField::boundaryField
const Boundary & boundaryField() const
Return const-reference to the boundary field.
Definition: GeometricFieldI.H:62
Foam::average
dimensioned< Type > average(const DimensionedField< Type, GeoMesh > &df)
Definition: DimensionedFieldFunctions.C:328
Foam::dimless
const dimensionSet dimless
Dimensionless.
Definition: dimensionSets.C:189
Foam::phase::rho
const dimensionedScalar & rho() const
Return const-access to phase1 density.
Definition: phase.H:140
Foam::cos
dimensionedScalar cos(const dimensionedScalar &ds)
Definition: dimensionedScalar.C:265
alphaControls
const dictionary & alphaControls
Definition: alphaControls.H:1