ENH: Improvement to overset that allows multiple motion solvers

to operate with overset

1) Adding zoneMotion to rigidBodyMotion
2) Introducing PID to prescribedRotation restraint
3) Making drivenLinearMotion read total displacement
4) When drivenLinearMotion is used sixDof and rigid-body solvers
   write total displacement
This commit is contained in:
sergio
2021-03-01 19:25:21 -08:00
committed by Andrew Heather
parent 1050314b8c
commit da1e6ea8d0
13 changed files with 188 additions and 67 deletions

View File

@ -97,9 +97,15 @@ int main(int argc, char *argv[])
dimensionedScalar("rAUf", dimTime/rho.dimensions(), 1.0) dimensionedScalar("rAUf", dimTime/rho.dimensions(), 1.0)
); );
if (correctPhi)
{
#include "correctPhi.H" #include "correctPhi.H"
}
#include "createUf.H" #include "createUf.H"
#include "setCellMask.H"
#include "setInterpolatedCells.H"
turbulence->validate(); turbulence->validate();
if (!LTS) if (!LTS)
@ -108,9 +114,6 @@ int main(int argc, char *argv[])
#include "setInitialDeltaT.H" #include "setInitialDeltaT.H"
} }
#include "setCellMask.H"
#include "setInterpolatedCells.H"
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
Info<< "\nStarting time loop\n" << endl; Info<< "\nStarting time loop\n" << endl;

View File

@ -48,7 +48,6 @@ Foam::IOobject Foam::points0MotionSolver::points0IO(const polyMesh& mesh)
"points0", "points0",
IOobject::READ_IF_PRESENT IOobject::READ_IF_PRESENT
); );
IOobject io IOobject io
( (
"points0", "points0",
@ -71,6 +70,19 @@ Foam::IOobject Foam::points0MotionSolver::points0IO(const polyMesh& mesh)
io.rename("points"); io.rename("points");
} }
// Choose the latest points if points0 is not present
// if (!io.typeHeaderOk<pointIOField>())
// {
// const word instance =
// mesh.time().findInstance
// (
// mesh.meshDir(),
// "points",
// IOobject::MUST_READ
// );
// io.instance() = instance;
// io.rename("points");
// }
return io; return io;
} }

View File

@ -5,7 +5,7 @@
\\ / A nd | www.openfoam.com \\ / A nd | www.openfoam.com
\\/ M anipulation | \\/ M anipulation |
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
Copyright (C) 2019-2020 OpenCFD Ltd. Copyright (C) 2019-2021 OpenCFD Ltd.
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
License License
This file is part of OpenFOAM. This file is part of OpenFOAM.
@ -56,26 +56,21 @@ Foam::solidBodyMotionFunctions::drivenLinearMotion::drivenLinearMotion
: :
solidBodyMotionFunction(SBMFCoeffs, runTime), solidBodyMotionFunction(SBMFCoeffs, runTime),
CofGvelocity_(SBMFCoeffs.get<word>("CofGvelocity")), CofGvelocity_(SBMFCoeffs.get<word>("CofGvelocity")),
normal_(SBMFCoeffs.getOrDefault<vector>("normal", Zero)),
CofGvel_ CofGvel_
( (
IOobject IOobject
( (
CofGvelocity_, CofGvelocity_,
time_.timeName(), time_.timeName(),
"uniform",
time_, time_,
IOobject::READ_IF_PRESENT, IOobject::READ_IF_PRESENT,
IOobject::AUTO_WRITE IOobject::AUTO_WRITE
), ),
dimensionedVector(dimless, Zero) dimensionedVector(dimless, Zero)
), )
displacement_(Zero)
{ {
read(SBMFCoeffs); read(SBMFCoeffs);
if (mag(normal_) > SMALL)
{
normal_ /= (mag(normal_) + SMALL);
}
} }
@ -84,24 +79,10 @@ Foam::solidBodyMotionFunctions::drivenLinearMotion::drivenLinearMotion
Foam::septernion Foam::septernion
Foam::solidBodyMotionFunctions::drivenLinearMotion::transformation() const Foam::solidBodyMotionFunctions::drivenLinearMotion::transformation() const
{ {
scalar deltaT = time_.deltaT().value();
vector velocity = CofGvel_.value();
// Take out normal component
if (mag(normal_) > SMALL)
{
velocity = CofGvel_.value() - ((CofGvel_.value() & normal_)*normal_);
}
DebugInFunction << "Vel on plane :" << velocity << endl;
// Translation of centre of gravity with constant velocity
//const vector displacement = velocity*t;
displacement_ += velocity*deltaT;
DebugInFunction << "displacement :" << CofGvel_.value() << endl;
quaternion R(1); quaternion R(1);
septernion TR(septernion(-displacement_)*R); septernion TR(septernion(-CofGvel_.value())*R);
DebugInFunction << "Time = " << time_.value() DebugInFunction << "Time = " << time_.value()
<< " transformation: " << TR << endl; << " transformation: " << TR << endl;

View File

@ -66,15 +66,9 @@ class drivenLinearMotion
//- Name of the meshObject to dum CofG velocity //- Name of the meshObject to dum CofG velocity
word CofGvelocity_; word CofGvelocity_;
//- Normal plane direction to restrict movement on a plane
vector normal_;
//- Uniform vector to follow //- Uniform vector to follow
uniformDimensionedVectorField CofGvel_; uniformDimensionedVectorField CofGvel_;
//- Last displacement
mutable vector displacement_;
// Private Member Functions // Private Member Functions

View File

@ -32,15 +32,12 @@ Description
const cellCellStencilObject& overlap = Stencil::New(mesh); const cellCellStencilObject& overlap = Stencil::New(mesh);
const labelList& cellTypes = overlap.cellTypes(); const labelList& cellTypes = overlap.cellTypes();
//label nHoles = 0;
cellMask.primitiveFieldRef() = 1.0; cellMask.primitiveFieldRef() = 1.0;
forAll(cellMask, cellI) forAll(cellMask, cellI)
{ {
if (cellTypes[cellI] == cellCellStencil::HOLE) if (cellTypes[cellI] == cellCellStencil::HOLE)
{ {
cellMask[cellI] = 0.0; cellMask[cellI] = 0.0;
//nHoles++;
} }
} }
cellMask.correctBoundaryConditions(); cellMask.correctBoundaryConditions();

View File

@ -5,7 +5,7 @@
\\ / A nd | www.openfoam.com \\ / A nd | www.openfoam.com
\\/ M anipulation | \\/ M anipulation |
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
Copyright (C) 2018-2020 OpenCFD Ltd. Copyright (C) 2018-2021 OpenCFD Ltd.
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
License License
This file is part of OpenFOAM. This file is part of OpenFOAM.
@ -61,7 +61,11 @@ Foam::RBD::restraints::prescribedRotation::prescribedRotation
) )
: :
restraint(name, dict, model), restraint(name, dict, model),
omegaSet_(model_.time(), "omega") omegaSet_(model_.time(), "omega"),
omega_(Zero),
prevMom_(Zero),
error0_(Zero),
integral0_(Zero)
{ {
read(dict); read(dict);
} }
@ -123,23 +127,31 @@ void Foam::RBD::restraints::prescribedRotation::restrain
// Adding rotation to a given body // Adding rotation to a given body
vector omega = model_.v(model_.master(bodyID_)).w(); vector omega = model_.v(model_.master(bodyID_)).w();
scalar Inertia = mag(model_.I(model_.master(bodyID_)).Ic()); scalar Inertia = mag(model_.I(model_.master(bodyID_)).Ic());
// from the definition of the angular momentum: // from the definition of the angular momentum:
// moment = Inertia*ddt(omega) // moment = Inertia*ddt(omega)
const scalar relax = 0.5;
vector moment vector error = omegaSet_.value(model_.time().value()) - omega;
( vector integral = integral0_ + error;
( vector derivative = (error - error0_);
relax
* Inertia vector moment = ((p_*error + i_*integral + d_*derivative) & a ) * a;
* (omegaSet_.value(model_.time().value()) - omega) moment = moment*Inertia/model_.time().deltaTValue();
/ model_.time().deltaTValue()
& a // vector moment
) // (
* a // (
); // Inertia
// * (omegaSet_.value(model_.time().value()) - omega)
// / model_.time().deltaTValue()/relax_
// & a
// )
// * a
// );
moment = relax_*moment + (1- relax_)*prevMom_;
if (model_.debug) if (model_.debug)
{ {
@ -149,12 +161,20 @@ void Foam::RBD::restraints::prescribedRotation::restrain
<< " moment " << moment << endl << " moment " << moment << endl
<< " oldDir " << oldDir << endl << " oldDir " << oldDir << endl
<< " newDir " << newDir << endl << " newDir " << newDir << endl
<< " inertia " << Inertia << endl
<< " error " << error << endl
<< " integral " << integral << endl
<< " derivative " << derivative << endl
<< " refDir " << refDir << " refDir " << refDir
<< endl; << endl;
} }
// Accumulate the force for the restrained body // Accumulate the force for the restrained body
fx[bodyIndex_] += spatialVector(moment, Zero); fx[bodyIndex_] += model_.X0(bodyID_).T() & spatialVector(moment, Zero);
prevMom_ = moment;
error0_ = error;
integral0_ = integral;
} }
@ -180,6 +200,12 @@ bool Foam::RBD::restraints::prescribedRotation::read
const scalar magAxis(mag(axis_)); const scalar magAxis(mag(axis_));
coeffs_.readEntry("relax", relax_);
coeffs_.readEntry("p", p_);
coeffs_.readEntry("i", i_);
coeffs_.readEntry("d", d_);
if (magAxis > VSMALL) if (magAxis > VSMALL)
{ {
axis_ /= magAxis; axis_ /= magAxis;

View File

@ -5,7 +5,7 @@
\\ / A nd | www.openfoam.com \\ / A nd | www.openfoam.com
\\/ M anipulation | \\/ M anipulation |
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
Copyright (C) 2018 OpenCFD Ltd. Copyright (C) 2021 OpenCFD Ltd.
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
License License
This file is part of OpenFOAM. This file is part of OpenFOAM.
@ -44,6 +44,10 @@ Usage
referenceOrientation | Orientation | no | I referenceOrientation | Orientation | no | I
axis | Rotation axis (in reference) | yes | axis | Rotation axis (in reference) | yes |
omega | Angular velocity (rad/s) | yes | omega | Angular velocity (rad/s) | yes |
relax | Relax moment with prevoius iter | yes
p | Propoptional corrector for PDI | yes
d | Differencial corrector for PDI | yes
i | Integral corrector for PDI | yes
\endtable \endtable
SourceFiles SourceFiles
@ -85,6 +89,26 @@ class prescribedRotation
//- Rotational velocity [rad/sec] //- Rotational velocity [rad/sec]
TimeFunction1<vector> omegaSet_; TimeFunction1<vector> omegaSet_;
//- Cache omega
mutable vector omega_;
//- Cache previous momentum
mutable vector prevMom_;
//- Relax momentum
scalar relax_;
//- PID constants
mutable vector error0_;
mutable vector integral0_;
mutable scalar p_;
mutable scalar i_;
mutable scalar d_;
public: public:
@ -137,7 +161,7 @@ public:
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
} // End namespace RBD } // End namespace restraints
} // End namespace RBD } // End namespace RBD
} // End namespace Foam } // End namespace Foam

View File

@ -186,6 +186,23 @@ void Foam::RBD::rigidBodyMotion::status(const label bodyID) const
} }
const Foam::vector Foam::RBD::rigidBodyMotion::vCofR(const label bodyID) const
{
const spatialVector velCofR(v(bodyID, Zero));
return velCofR.l();
}
const Foam::vector Foam::RBD::rigidBodyMotion::cCofR(const label bodyID) const
{
const spatialTransform CofR(X0(bodyID));
return CofR.r();
}
Foam::tmp<Foam::pointField> Foam::RBD::rigidBodyMotion::transformPoints Foam::tmp<Foam::pointField> Foam::RBD::rigidBodyMotion::transformPoints
( (
const label bodyID, const label bodyID,

View File

@ -189,6 +189,12 @@ public:
//- Report the status of the motion of the given body //- Report the status of the motion of the given body
void status(const label bodyID) const; void status(const label bodyID) const;
//- Report linear velocity of the given body
const vector vCofR(const label bodyID) const;
//- Report CofR of the given body
const vector cCofR(const label bodyID) const;
// Transformations // Transformations

View File

@ -6,7 +6,7 @@
\\/ M anipulation | \\/ M anipulation |
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
Copyright (C) 2016-2017 OpenFOAM Foundation Copyright (C) 2016-2017 OpenFOAM Foundation
Copyright (C) 2016-2020 OpenCFD Ltd. Copyright (C) 2016-2021 OpenCFD Ltd.
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
License License
This file is part of OpenFOAM. This file is part of OpenFOAM.
@ -120,7 +120,10 @@ Foam::rigidBodyMeshMotion::rigidBodyMeshMotion
rhoInf_(1.0), rhoInf_(1.0),
rhoName_(coeffDict().getOrDefault<word>("rho", "rho")), rhoName_(coeffDict().getOrDefault<word>("rho", "rho")),
ramp_(Function1<scalar>::NewIfPresent("ramp", coeffDict())), ramp_(Function1<scalar>::NewIfPresent("ramp", coeffDict())),
curTimeIndex_(-1) curTimeIndex_(-1),
CofGvelocity_(coeffDict().getOrDefault<word>("CofGvelocity", "none")),
bodyIdCofG_(coeffDict().getOrDefault<label>("bodyIdCofG", -1))
//points0_(points0IO(mesh))
{ {
if (rhoName_ == "rhoInf") if (rhoName_ == "rhoInf")
{ {
@ -208,7 +211,24 @@ Foam::rigidBodyMeshMotion::rigidBodyMeshMotion
Foam::tmp<Foam::pointField> Foam::tmp<Foam::pointField>
Foam::rigidBodyMeshMotion::curPoints() const Foam::rigidBodyMeshMotion::curPoints() const
{ {
return points0() + pointDisplacement_.primitiveField(); //return points0() + pointDisplacement_.primitiveField();
tmp<pointField> newPoints(points0() + pointDisplacement_.primitiveField());
if (moveAllCells())
{
return newPoints;
}
else
{
tmp<pointField> ttransformedPts(new pointField(mesh().points()));
pointField& transformedPts = ttransformedPts.ref();
UIndirectList<point>(transformedPts, pointIDs()) =
pointField(newPoints.ref(), pointIDs());
return ttransformedPts;
}
} }
@ -240,6 +260,8 @@ void Foam::rigidBodyMeshMotion::solve()
ramp*t.lookupObject<uniformDimensionedVectorField>("g").value(); ramp*t.lookupObject<uniformDimensionedVectorField>("g").value();
} }
vector oldPos = model_.cCofR(bodyIdCofG_);
if (test_) if (test_)
{ {
const label nIter(coeffDict().get<label>("nIter")); const label nIter(coeffDict().get<label>("nIter"));
@ -288,6 +310,36 @@ void Foam::rigidBodyMeshMotion::solve()
fx fx
); );
} }
if (CofGvelocity_ != "none")
{
if (bodyIdCofG_ != -1)
{
if
(
db().time().foundObject<uniformDimensionedVectorField>
(
CofGvelocity_
)
)
{
uniformDimensionedVectorField& disp =
db().time().lookupObjectRef<uniformDimensionedVectorField>
(
CofGvelocity_
);
disp.value() += model_.cCofR(bodyIdCofG_) - oldPos;
}
}
else
{
FatalErrorInFunction
<< "CofGvelocity is different of none." << endl
<< "The model need the entry body reference Id: bodyIdCofG."
<< exit(FatalError);
}
}
} }
if (Pstream::master() && model_.report()) if (Pstream::master() && model_.report())
@ -320,8 +372,8 @@ void Foam::rigidBodyMeshMotion::solve()
pointDisplacement_.primitiveFieldRef() = pointDisplacement_.primitiveFieldRef() =
model_.transformPoints(bodyIDs, weights, points0()) - points0(); model_.transformPoints(bodyIDs, weights, points0()) - points0();
}
}
// Displacement has changed. Update boundary conditions // Displacement has changed. Update boundary conditions
pointConstraints::New pointConstraints::New
( (

View File

@ -6,7 +6,7 @@
\\/ M anipulation | \\/ M anipulation |
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
Copyright (C) 2016-2017 OpenFOAM Foundation Copyright (C) 2016-2017 OpenFOAM Foundation
Copyright (C) 2020 OpenCFD Ltd. Copyright (C) 2021 OpenCFD Ltd.
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
License License
This file is part of OpenFOAM. This file is part of OpenFOAM.
@ -128,6 +128,13 @@ class rigidBodyMeshMotion
//- Current time index (used for updating) //- Current time index (used for updating)
label curTimeIndex_; label curTimeIndex_;
//- Name of the uniformVectorField for CofG velocity
word CofGvelocity_;
//- Body Id for the body to write CofG velocity
label bodyIdCofG_;
// Private Member Functions // Private Member Functions

View File

@ -243,6 +243,8 @@ void Foam::sixDoFRigidBodyMotionSolver::solve()
forcesDict.add("rho", rhoName_); forcesDict.add("rho", rhoName_);
forcesDict.add("CofR", motion_.centreOfRotation()); forcesDict.add("CofR", motion_.centreOfRotation());
vector oldPos = motion_.centreOfRotation();
functionObjects::forces f("forces", db(), forcesDict); functionObjects::forces f("forces", db(), forcesDict);
f.calcForcesMoment(); f.calcForcesMoment();
@ -270,12 +272,13 @@ void Foam::sixDoFRigidBodyMotionSolver::solve()
) )
) )
{ {
uniformDimensionedVectorField& vel = uniformDimensionedVectorField& disp =
db().time().lookupObjectRef<uniformDimensionedVectorField> db().time().lookupObjectRef<uniformDimensionedVectorField>
( (
CofGvelocity_ CofGvelocity_
); );
vel = motion_.v();
disp += (motion_.centreOfRotation() - oldPos);
} }
} }
} }

View File

@ -27,7 +27,6 @@ solvers
cellSet c0; cellSet c0;
CofGvelocity CofG; CofGvelocity CofG;
normal (0 0 1);
} }
cube cube
@ -101,7 +100,7 @@ solvers
sixDoFRigidBodyMotionRestraint linearSpring; sixDoFRigidBodyMotionRestraint linearSpring;
anchor (0 0.5 0.4); anchor (0 0.5 0.4);
refAttachmentPt (0.5 0.5 0.4); refAttachmentPt (0.5 0.5 0.4);
stiffness 100; stiffness 300;
damping 0; damping 0;
restLength 0; restLength 0;
} }