ENH: rigidbodyDynamics: prescribed rotation + testcase

See:
src/rigidBodyDynamics/restraints/prescribedRotation
tutorials/multiphase/overInterDyMFoam/boatAndPropeller
This commit is contained in:
Matej Forman
2018-04-19 17:54:24 +01:00
committed by mattijs
parent 5848b0afd5
commit 5b9c4ceae5
38 changed files with 2526 additions and 9 deletions

View File

@ -32,6 +32,7 @@ restraints/linearSpring/linearSpring.C
restraints/linearDamper/linearDamper.C
restraints/linearAxialAngularSpring/linearAxialAngularSpring.C
restraints/sphericalAngularDamper/sphericalAngularDamper.C
restraints/prescribedRotation/prescribedRotation.C
rigidBodyModel/rigidBodyModel.C
rigidBodyModel/forwardDynamics.C

View File

@ -0,0 +1,203 @@
/*---------------------------------------------------------------------------*\
========= |
\\ / F ield | OpenFOAM: The Open Source CFD Toolbox
\\ / O peration |
\\ / A nd | Copyright (C) 2018 OpenCFD ltd.
\\/ M anipulation |
-------------------------------------------------------------------------------
License
This file is part of OpenFOAM.
OpenFOAM 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.
OpenFOAM 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 OpenFOAM. If not, see <http://www.gnu.org/licenses/>.
\*---------------------------------------------------------------------------*/
#include "prescribedRotation.H"
#include "rigidBodyModel.H"
#include "addToRunTimeSelectionTable.H"
#include "Time.H"
// * * * * * * * * * * * * * * Static Data Members * * * * * * * * * * * * * //
namespace Foam
{
namespace RBD
{
namespace restraints
{
defineTypeNameAndDebug(prescribedRotation, 0);
addToRunTimeSelectionTable
(
restraint,
prescribedRotation,
dictionary
);
}
}
}
// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * //
Foam::RBD::restraints::prescribedRotation::prescribedRotation
(
const word& name,
const dictionary& dict,
const rigidBodyModel& model
)
:
restraint(name, dict, model),
omegaSet_(model_.time(), "omega")
{
read(dict);
}
// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * //
Foam::RBD::restraints::prescribedRotation::~prescribedRotation()
{}
// * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * * //
void Foam::RBD::restraints::prescribedRotation::restrain
(
scalarField& tau,
Field<spatialVector>& fx
) const
{
vector refDir = rotationTensor(vector(1, 0, 0), axis_) & vector(0, 1, 0);
vector oldDir = refQ_ & refDir;
vector newDir = model_.X0(bodyID_).E() & refDir;
if (mag(oldDir & axis_) > 0.95 || mag(newDir & axis_) > 0.95)
{
// Directions close to the axis, changing reference
refDir = rotationTensor(vector(1, 0, 0), axis_) & vector(0, 0, 1);
oldDir = refQ_ & refDir;
newDir = model_.X0(bodyID_).E() & refDir;
}
// Removing axis component from oldDir and newDir and normalising
oldDir -= (axis_ & oldDir)*axis_;
oldDir /= (mag(oldDir) + VSMALL);
newDir -= (axis_ & newDir)*axis_;
newDir /= (mag(newDir) + VSMALL);
scalar theta = mag(acos(min(oldDir & newDir, 1.0)));
// Temporary axis with sign information
vector a = (oldDir ^ newDir);
// Ensure a is in direction of axis
a = (a & axis_)*axis_;
scalar magA = mag(a);
if (magA > VSMALL)
{
a /= magA;
}
else
{
a = Zero;
}
// Adding rotation to a given body
vector omega = model_.v(model_.master(bodyID_)).w();
scalar Inertia = mag(model_.I(model_.master(bodyID_)).Ic());
// from the definition of the angular momentum:
// moment = Inertia*ddt(omega)
// with time step 1:
// moment = Inertia*(omega_wanted - omega)
vector moment
(
(Inertia * (omegaSet_.value(model_.time().value()) - omega) & a) * a
);
if (model_.debug)
{
Info<< " angle " << theta*sign(a & axis_) << endl
<< " moment " << moment << endl
<< " oldDir " << oldDir << endl
<< " newDir " << newDir << endl
<< " refDir " << refDir
<< endl;
}
// Accumulate the force for the restrained body
fx[bodyIndex_] += spatialVector(moment, Zero);
}
bool Foam::RBD::restraints::prescribedRotation::read
(
const dictionary& dict
)
{
restraint::read(dict);
refQ_ = coeffs_.lookupOrDefault<tensor>("referenceOrientation", I);
if (mag(mag(refQ_) - sqrt(3.0)) > 1e-9)
{
FatalErrorInFunction
<< "referenceOrientation " << refQ_ << " is not a rotation tensor. "
<< "mag(referenceOrientation) - sqrt(3) = "
<< mag(refQ_) - sqrt(3.0) << nl
<< exit(FatalError);
}
axis_ = coeffs_.lookup("axis");
scalar magAxis(mag(axis_));
if (magAxis > VSMALL)
{
axis_ /= magAxis;
}
else
{
FatalErrorInFunction
<< "axis has zero length"
<< abort(FatalError);
}
// Read the actual entry
omegaSet_.reset(coeffs_);
return true;
}
void Foam::RBD::restraints::prescribedRotation::write
(
Ostream& os
) const
{
restraint::write(os);
os.writeEntry("referenceOrientation", refQ_);
os.writeEntry("axis", axis_);
omegaSet_.writeData(os);
}
// ************************************************************************* //

View File

@ -0,0 +1,145 @@
/*---------------------------------------------------------------------------*\
========= |
\\ / F ield | OpenFOAM: The Open Source CFD Toolbox
\\ / O peration |
\\ / A nd | Copyright (C) 2018 OpenCFD Ltd.
\\/ M anipulation |
-------------------------------------------------------------------------------
License
This file is part of OpenFOAM.
OpenFOAM 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.
OpenFOAM 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 OpenFOAM. If not, see <http://www.gnu.org/licenses/>.
Class
Foam::RBD::restraints::prescribedRotation
Group
grpRigidBodyDynamicsRestraints
Description
Restraint setting angular velocity of the rigid body.
Developed from the linear axial angular spring restraint.
Adds a rotation along given axis to the body.
Used for a combination of 6DOF bodies where one is driven by 6DOF and
the other attached to it using specified rotation
in the local reference frame.
Usage
\table
Property | Description | Required | Default value
referenceOrientation | Orientation | no | I
axis | Rotation axis (in reference) | yes |
omega | Angular velocity (rad/s) | yes |
\endtable
SourceFiles
prescribedRotation.C
\*---------------------------------------------------------------------------*/
#ifndef prescribedRotation_H
#define prescribedRotation_H
#include "rigidBodyRestraint.H"
#include "TimeFunction1.H"
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
namespace Foam
{
namespace RBD
{
namespace restraints
{
/*---------------------------------------------------------------------------*\
Class prescribedRotation Declaration
\*---------------------------------------------------------------------------*/
class prescribedRotation
:
public restraint
{
// Private data
//- Reference orientation where there is no moment
tensor refQ_;
//- Global unit axis around which the motion is sprung
vector axis_;
//- Rotational velocity [rad/sec]
TimeFunction1<vector> omegaSet_;
public:
//- Runtime type information
TypeName("prescribedRotation");
// Constructors
//- Construct from components
prescribedRotation
(
const word& name,
const dictionary& dict,
const rigidBodyModel& model
);
//- Construct and return a clone
virtual autoPtr<restraint> clone() const
{
return autoPtr<restraint>
(
new prescribedRotation(*this)
);
}
//- Destructor
virtual ~prescribedRotation();
// Member Functions
//- Accumulate the retraint internal joint forces into the tau field and
// external forces into the fx field
virtual void restrain
(
scalarField& tau,
Field<spatialVector>& fx
) const;
//- Update properties from given dictionary
virtual bool read(const dictionary& dict);
//- Write
virtual void write(Ostream&) const;
};
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
} // End namespace RBD
} // End namespace RBD
} // End namespace Foam
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
#endif
// ************************************************************************* //

View File

@ -163,16 +163,22 @@ Foam::label Foam::RBD::rigidBodyModel::join_
// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * * //
Foam::RBD::rigidBodyModel::rigidBodyModel()
Foam::RBD::rigidBodyModel::rigidBodyModel(const Time& time)
:
time_(time),
g_(Zero)
{
initializeRootBody();
}
Foam::RBD::rigidBodyModel::rigidBodyModel(const dictionary& dict)
Foam::RBD::rigidBodyModel::rigidBodyModel
(
const Time& time,
const dictionary& dict
)
:
time_(time),
g_(Zero)
{
initializeRootBody();

View File

@ -58,6 +58,10 @@ SourceFiles
namespace Foam
{
// Forward declaration of friend functions and operators
class Time;
namespace RBD
{
@ -93,6 +97,9 @@ class rigidBodyModel
protected:
//- Reference to time database
const Time& time_;
// Protected data representing the model structure
//- List of the bodies.
@ -211,10 +218,10 @@ public:
// Constructors
//- Null-constructor which adds the single root-body at the origin
rigidBodyModel();
rigidBodyModel(const Time& time);
//- Construct from dictionary
rigidBodyModel(const dictionary& dict);
rigidBodyModel(const Time& time, const dictionary& dict);
//- Destructor
@ -223,6 +230,9 @@ public:
// Member Functions
//- Return the time
inline const Time& time() const;
//- Return the number of bodies in the model (bodies().size())
inline label nBodies() const;

View File

@ -25,6 +25,12 @@ License
// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * //
inline const Foam::Time& Foam::RBD::rigidBodyModel::time() const
{
return time_;
}
inline Foam::label Foam::RBD::rigidBodyModel::nBodies() const
{
return bodies_.size();

View File

@ -42,9 +42,9 @@ void Foam::RBD::rigidBodyMotion::initialize()
// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * //
Foam::RBD::rigidBodyMotion::rigidBodyMotion()
Foam::RBD::rigidBodyMotion::rigidBodyMotion(const Time& time)
:
rigidBodyModel(),
rigidBodyModel(time),
motionState_(*this),
motionState0_(*this),
aRelax_(1.0),
@ -55,10 +55,11 @@ Foam::RBD::rigidBodyMotion::rigidBodyMotion()
Foam::RBD::rigidBodyMotion::rigidBodyMotion
(
const Time& time,
const dictionary& dict
)
:
rigidBodyModel(dict),
rigidBodyModel(time, dict),
motionState_(*this, dict),
motionState0_(motionState_),
X00_(X0_.size()),
@ -78,11 +79,12 @@ Foam::RBD::rigidBodyMotion::rigidBodyMotion
Foam::RBD::rigidBodyMotion::rigidBodyMotion
(
const Time& time,
const dictionary& dict,
const dictionary& stateDict
)
:
rigidBodyModel(dict),
rigidBodyModel(time, dict),
motionState_(*this, stateDict),
motionState0_(motionState_),
X00_(X0_.size()),

View File

@ -55,6 +55,10 @@ SourceFiles
namespace Foam
{
// Forward declarations
class Time;
namespace RBD
{
@ -112,17 +116,19 @@ public:
// Constructors
//- Construct null
rigidBodyMotion();
rigidBodyMotion(const Time& time);
//- Construct from dictionary
rigidBodyMotion
(
const Time& time,
const dictionary& dict
);
//- Construct from constant and state dictionaries
rigidBodyMotion
(
const Time& time,
const dictionary& dict,
const dictionary& stateDict
);

View File

@ -90,6 +90,7 @@ Foam::rigidBodyMeshMotion::rigidBodyMeshMotion
displacementMotionSolver(mesh, dict, typeName),
model_
(
mesh.time(),
coeffDict(),
IOobject
(

View File

@ -73,6 +73,7 @@ Foam::rigidBodyMeshMotionSolver::rigidBodyMeshMotionSolver
motionSolver(mesh, dict, typeName),
model_
(
mesh.time(),
coeffDict(),
IOobject
(

View File

@ -0,0 +1,58 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class volVectorField;
object U;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
dimensions [0 1 -1 0 0 0 0];
internalField uniform (0 0 0);
boundaryField
{
#includeEtc "caseDicts/setConstraintTypes"
defaultFaces
{
//type slip;
type uniformFixedValue;
uniformValue (0 0 0);
}
"(hullWall|propellerWall|rudderWall)"
{
type movingWallVelocity;
value uniform (0 0 0);
}
atmosphere
{
type pressureInletOutletVelocity;
value uniform (0 0 0);
}
//
// right1
// {
// type zeroGradient; //calculated;
// value $internalField;
// }
"overset.*"
{
type overset;
value uniform (0 0 0);
}
}
// ************************************************************************* //

View File

@ -0,0 +1,58 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: v1612+ |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class volScalarField;
location "0";
object alpha.water;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
dimensions [0 0 0 0 0 0 0];
internalField uniform 0;
boundaryField
{
#includeEtc "caseDicts/setConstraintTypes"
"overset.*"
{
type overset;
value uniform 1;
}
hullWall
{
type zeroGradient;
}
propellerWall
{
type zeroGradient;
}
rudderWall
{
type zeroGradient;
}
atmosphere
{
type inletOutlet;
inletValue uniform 0;
value uniform 0;
}
defaultFaces
{
type zeroGradient;
}
}
// ************************************************************************* //

View File

@ -0,0 +1,55 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: v1612+ |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class volScalarField;
location "0";
object alpha.water;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
dimensions [0 0 0 0 0 0 0];
internalField uniform 0;
boundaryField
{
"overset.*"
{
type overset;
value uniform 1;
}
hullWall
{
type zeroGradient;
}
propellerWall
{
type zeroGradient;
}
rudderWall
{
type zeroGradient;
}
atmosphere
{
type inletOutlet;
inletValue uniform 0;
value uniform 0;
}
defaultFaces
{
type zeroGradient;
}
}
// ************************************************************************* //

View File

@ -0,0 +1,60 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: v1706 |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class pointScalarField;
location "0";
object motionScale;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
dimensions [0 0 0 0 0 0 0];
internalField uniform 0;
boundaryField
{
overset1
{
type calculated;
}
overset2
{
type calculated;
}
overset3
{
type calculated;
}
hullWall
{
type calculated;
}
propellerWall
{
type calculated;
}
rudderWall
{
type calculated;
}
atmosphere
{
type calculated;
}
defaultFaces
{
type calculated;
}
}
// ************************************************************************* //

View File

@ -0,0 +1,59 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class volScalarField;
object p_rgh;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
dimensions [1 -1 -2 0 0 0 0];
internalField uniform 0;
boundaryField
{
#includeEtc "caseDicts/setConstraintTypes"
"(hullWall|propellerWall|rudderWall|defaultFaces)"
{
type fixedFluxPressure;
}
atmosphere
{
type totalPressure;
p0 uniform 0;
U U;
phi phi;
rho rho;
psi none;
gamma 1;
value uniform 0;
}
defaultFaces
{
type fixedFluxPressure;
}
//
// right1
// {
// type fixedValue; //calculated;
// value $internalField;
// }
"overset.*"
{
patchType overset;
type fixedFluxPressure;
}
}
// ************************************************************************* //

View File

@ -0,0 +1,56 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class pointVectorField;
object pointDisplacement;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
dimensions [0 1 0 0 0 0 0];
internalField uniform (0 0 0);
boundaryField
{
".*"
{
type uniformFixedValue;
uniformValue (0 0 0);
}
"(hullWall|propellerWall|rudderWall)"
{
type calculated;
value uniform (0 0 0);
}
oversetPatch
{
patchType overset;
type zeroGradient;
}
"overset.*"
{
patchType overset;
type zeroGradient;
}
atmosphere
{
type fixedValue;
value uniform (0 0 0);
}
defaultFaces
{
type fixedValue;
value uniform (0 0 0);
}
}
// ************************************************************************* //

View File

@ -0,0 +1,64 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: v1706 |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class volScalarField;
location "0";
object zoneID;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
dimensions [0 0 0 0 0 0 0];
internalField uniform 0;
boundaryField
{
#includeEtc "caseDicts/setConstraintTypes"
overset1
{
type overset;
value uniform 0;
}
overset2
{
type overset;
value uniform 0;
}
overset3
{
type overset;
value uniform 0;
}
hullWall
{
type zeroGradient;
}
propellerWall
{
type zeroGradient;
}
rudderWall
{
type zeroGradient;
}
atmosphere
{
type zeroGradient;
}
defaultFaces
{
type zeroGradient;
}
}
// ************************************************************************* //

View File

@ -0,0 +1,12 @@
#!/bin/sh
cd ${0%/*} || exit 1 # Run from this directory
. $WM_PROJECT_DIR/bin/tools/CleanFunctions
cleanCase
rm -f constant/polyMesh/boundary
rm -f constant/polyMesh/zoneID
rm -f constant/cellInterpolationWeight
rm -rf 0
#------------------------------------------------------------------------------

View File

@ -0,0 +1,10 @@
#!/bin/sh
cd ${0%/*} || exit 1 # Run from this directory
. $WM_PROJECT_DIR/bin/tools/RunFunctions
./Allrun.pre
runApplication decomposePar
runParallel overInterDyMFoam
#------------------------------------------------------------------------------

View File

@ -0,0 +1,37 @@
#!/bin/sh
cd ${0%/*} || exit 1 # Run from this directory
. $WM_PROJECT_DIR/bin/tools/RunFunctions
runApplication blockMesh
#runApplication -s 1 topoSet -dict ./system/topoSetDictRefine
#runApplication -s 1 refineMesh -overwrite -dict ./system/refineMeshDict
runApplication -s 1 topoSet -dict ./system/topoSetDictRefine
runApplication -s 1 refineMesh -overwrite -dict ./system/refineMeshDict
runApplication -s 2 topoSet -dict ./system/topoSetDictRefine
runApplication -s 2 refineMesh -overwrite -dict ./system/refineMeshDict
# Select cellSets
runApplication -s 3 topoSet -dict ./system/topoSetDictHull
runApplication -s 3 subsetMesh keepBox -patch hullWall -overwrite
# Select cellSets
runApplication -s 4 topoSet -dict ./system/topoSetDictPropeller
runApplication -s 4 subsetMesh keepBox -patch propellerWall -overwrite
# Select cellSets
runApplication -s 5 topoSet -dict ./system/topoSetDictRudder
runApplication -s 5 subsetMesh keepBox -patch rudderWall -overwrite
restore0Dir
# Use cellSets to write zoneID
runApplication -s 1 setFields -dict system/setFieldsDict
runApplication -s 2 setFields -dict system/setFieldsDictWaterLevel
touch rbm.foam
#------------------------------------------------------------------------------

View File

@ -0,0 +1,135 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus.develop |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object dynamicMeshDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
motionSolverLibs ("librigidBodyMeshMotion.so");
dynamicFvMesh dynamicOversetFvMesh;
motionSolver rigidBodyMotion;
// rigidBodyMotionCoeffs
// {
report on;
solver
{
type Newmark;
gamma 0.1; // Velocity integration coefficient
beta 0.1; // Position integration coefficient
}
accelerationRelaxation 1.0;
bodies
{
hull
{
type rigidBody;
parent root;
// Cuboid mass
mass 9;
rho 1;
inertia (0.05 0 0 0.05 0 0.05);
centreOfMass (0.21 -0.07 0);
transform (1 0 0 0 1 0 0 0 1) (0.21 0 0);
joint
{
type composite;
joints
(
{
type Pxyz;
}
{
type Rxyz;
}
);
}
patches (hullWall);
innerDistance 100;
outerDistance 200;
} // end hull
propeller
{
type rigidBody;
parent hull;
centreOfMass (-0.228 0.0 0);
mass 1;
rho 1;
inertia (0.001 0 0 0.001 0 0.001);
transform (1 0 0 0 1 0 0 0 1) (-0.228 0 0);
patches (propellerWall);
innerDistance 100;
outerDistance 200;
joint
{
type Rx;
}
} //end propeller
rudder
{
type rigidBody;
parent hull;//root;
centreOfMass (-0.265 0 0);
mass 1;
rho 1;
inertia (0.001 0 0 0.001 0 0.001);
transform (1 0 0 0 1 0 0 0 1) (-0.265 0 0);
patches (rudderWall);
innerDistance 100;
outerDistance 200;
joint
{
type Ry;
}
}
}
restraints
{
rudderRotation
{
type prescribedRotation;
body rudder;
referenceOrientation (1 0 0 0 1 0 0 0 1);
axis (0 1 0);
omega (0 26 0);
}
propellerRotation
{
type prescribedRotation;
body propeller;
referenceOrientation (1 0 0 0 1 0 0 0 1);
axis (1 0 0);
omega table
(
(0 (16 0 0))
);
}
}
// } // end of rigidBodyMotionCoeffs
// ************************************************************************* //

View File

@ -0,0 +1,20 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class uniformDimensionedVectorField;
object g;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
dimensions [0 1 -2 0 0 0 0];
value (0 -9 0);//( 0 -9.81 0 );
// ************************************************************************* //

View File

@ -0,0 +1,35 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object transportProperties;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
phases (water air);
water
{
transportModel Newtonian;
nu nu [ 0 2 -1 0 0 0 0 ] 1e-06;
rho rho [ 1 -3 0 0 0 0 0 ] 998.2;
}
air
{
transportModel Newtonian;
nu nu [ 0 2 -1 0 0 0 0 ] 1.48e-05;
rho rho [ 1 -3 0 0 0 0 0 ] 1;
}
sigma sigma [ 1 0 -2 0 0 0 0 ] 0;
// ************************************************************************* //

View File

@ -0,0 +1,19 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object turbulenceProperties;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
simulationType laminar;
// ************************************************************************* //

View File

@ -0,0 +1,158 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object blockMeshDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
scale 1;
vertices
(
// backgroundMesh
( -1.00 -1 -1) // 0
( 1.00 -1 -1)
( 1.00 1.0 -1)
( -1.00 1.0 -1)
( -1.00 -1 1) // 4
( 1.00 -1 1)
( 1.00 1.0 1)
( -1.00 1.0 1)
// hullBox
( 0.0 -0.20 -0.2) // 8
( 0.80 -0.20 -0.2)
( 0.80 0.20 -0.2) // 10
( 0.0 0.20 -0.2)
( 0.0 -0.20 0.2) // 12
( 0.80 -0.20 0.2)
( 0.80 0.20 0.2) // 14
( 0.0 0.20 0.2)
// propeller
( -0.03 -0.08 -0.08) // 16
( 0.04 -0.08 -0.08)
( 0.04 0.08 -0.08) // 18
( -0.03 0.08 -0.08)
( -0.03 -0.08 0.08) // 20
( 0.04 -0.08 0.08)
( 0.04 0.08 0.08) // 22
( -0.03 0.08 0.08)
// rudder
( -0.15 -0.1 -0.05) // 24
( -0.028 -0.1 -0.05)
( -0.028 0.1 -0.05) // 26
( -0.15 0.1 -0.05)
( -0.15 -0.1 0.05) // 28
( -0.028 -0.1 0.05)
( -0.028 0.1 0.05) // 30
( -0.15 0.1 0.05)
);
blocks
(
hex (0 1 2 3 4 5 6 7) background (80 80 40) simpleGrading (1 1 1)
hex (8 9 10 11 12 13 14 15) hullBox (20 20 20) simpleGrading (1 1 1)
hex (16 17 18 19 20 21 22 23) propeller (10 20 20) simpleGrading (1 1 1)
hex (24 25 26 27 28 29 30 31) rudder (20 20 20) simpleGrading (1 1 1)
);
edges
(
);
boundary
(
overset1 //oversetHull
{
type overset;
faces
(
( 8 12 15 11)
(10 14 13 9)
(11 15 14 10)
( 9 13 12 8)
( 9 8 11 10)
(12 13 14 15)
);
}
overset2 //oversetPropeller
{
type overset;
faces
(
(16 20 23 19)
(18 22 21 17)
(19 23 22 18)
(17 21 20 16)
(20 21 22 23)
(19 18 17 16)
);
}
overset3 //oversetRudder
{
type overset;
faces
(
(24 28 31 27)
(26 30 29 25)
(28 29 30 31)
(25 24 27 26)
(27 31 30 26)
(24 25 29 28)
);
}
// Populated by subsetMesh
hullWall
{
type wall;
faces ();
}
propellerWall
{
type wall;
faces ();
}
rudderWall
{
type wall;
faces ();
}
atmosphere
{
type patch;
faces
(
(3 7 6 2)
// (1 5 4 0)
);
}
defaultFaces
{
type wall;
faces
();
}
);
// ************************************************************************* //

View File

@ -0,0 +1,58 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object controlDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
libs ("liboverset.so" "librigidBodyDynamics.so");
application overInterDyMFoam;
startFrom startTime;
startTime 0;
stopAt endTime;
endTime 1;
deltaT 0.0001;
writeControl adjustableRunTime;
writeInterval 0.005;
purgeWrite 0;
writeFormat binary;
writePrecision 10;
writeCompression off;
timeFormat general;
timePrecision 6;
runTimeModifiable true;
adjustTimeStep yes;
//maxCo 1;
maxCo 5.0;
maxAlphaCo 5.0;
maxDeltaT 1;
// ************************************************************************* //

View File

@ -0,0 +1,30 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
note "mesh decomposition control dictionary";
object decomposeParDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
numberOfSubdomains 4;
method hierarchical;
coeffs
{
n (2 2 1);
// delta 0.001;
// order xyz;
}
// ************************************************************************* //

View File

@ -0,0 +1,72 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object fvSchemes;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
ddtSchemes
{
default Euler;
}
gradSchemes
{
default Gauss linear;
}
divSchemes
{
div(rhoPhi,U) Gauss upwind ;//limitedLinearV 1;
div(U) Gauss upwind;//linear;
div(phi,alpha) Gauss vanLeer;
div(phirb,alpha) Gauss linear;
div(((rho*nuEff)*dev2(T(grad(U))))) Gauss linear;
div(phi,k) Gauss upwind;
div(phi,epsilon) Gauss upwind;
div(phi,omega) Gauss upwind;
}
laplacianSchemes
{
default Gauss linear corrected;
}
interpolationSchemes
{
default linear;
}
snGradSchemes
{
default corrected;
}
oversetInterpolation
{
method inverseDistance;
}
oversetInterpolationRequired
{
alpha.water;
}
fluxRequired
{
// default no;
// p_rgh;
// pcorr;
// alpha.water;
}
// ************************************************************************* //

View File

@ -0,0 +1,69 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object fvSchemes;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
ddtSchemes
{
default Euler;
}
gradSchemes
{
default Gauss linear;
}
divSchemes
{
div(rhoPhi,U) Gauss limitedLinearV 1;
div(U) Gauss linear;
div(phi,alpha) Gauss vanLeer;
div(phirb,alpha) Gauss linear;
div(((rho*nuEff)*dev2(T(grad(U))))) Gauss linear;
div(phi,k) Gauss upwind;
div(phi,epsilon) Gauss upwind;
div(phi,omega) Gauss upwind;
}
laplacianSchemes
{
default Gauss linear corrected;
}
interpolationSchemes
{
default linear;
}
snGradSchemes
{
default corrected;
}
oversetInterpolation
{
method inverseDistance;
}
fluxRequired
{
default no;
p;
// p_rgh;
// pcorr;
// alpha.water;
}
// ************************************************************************* //

View File

@ -0,0 +1,112 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object fvSolution;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
solvers
{
"cellDisplacement.*"
{
solver PCG;
preconditioner DIC;
tolerance 1e-06;
relTol 0;
maxIter 100;
}
"alpha.water.*"
{
nAlphaCorr 3;
nAlphaSubCycles 2;
cAlpha 1;
icAlpha 0;
MULESCorr yes;
nLimiterIter 5;
alphaApplyPrevCorr no;
solver smoothSolver;
smoother symGaussSeidel;
tolerance 1e-8;
relTol 0;
}
"pcorr.*"
{
solver PCG;
preconditioner DIC;
tolerance 1e-9;
relTol 0;
}
p_rgh
{
solver PBiCGStab;
preconditioner DILU;
tolerance 1e-9;
relTol 0.01;
}
p_rghFinal
{
$p_rgh;
relTol 0;
}
"(U|k|omega|epsilon).*"
{
solver smoothSolver;
smoother symGaussSeidel;
tolerance 1e-08;
relTol 0;
}
}
PIMPLE
{
momentumPredictor no;//yes;
nOuterCorrectors 2;
nCorrectors 2;
nNonOrthogonalCorrectors 0;
ddtCorr yes;
correctPhi no;
massFluxInterpolation no;
moveMeshOuterCorrectors no;
turbOnFinalIterOnly no;
oversetAdjustPhi no;
}
relaxationFactors
{
fields
{
}
equations
{
".*" 1;
}
}
cache
{
grad(U);
}
// ************************************************************************* //

View File

@ -0,0 +1,43 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
location "system";
object refineMeshDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
set refineSet;
coordinateSystem global;
globalCoeffs
{
tan1 (1 0 0);
tan2 (0 1 0);
}
/*
patchLocalCoeffs
{
patch outside;
tan1 (1 0 0);
}*/
directions ( tan1 tan2 );
useHexTopology no;
geometricCut yes;
writeMesh no;
// ************************************************************************* //

View File

@ -0,0 +1,67 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object setFieldsDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
defaultFieldValues
(
volScalarFieldValue zoneID 123
);
regions
(
// Set cell values
// (does zerogradient on boundaries)
cellToCell
{
set bgr0;
fieldValues
(
volScalarFieldValue zoneID 0
);
}
cellToCell
{
set hullBox0;
fieldValues
(
volScalarFieldValue zoneID 1
);
}
cellToCell
{
set propeller0;
fieldValues
(
volScalarFieldValue zoneID 2
);
}
cellToCell
{
set rudder0;
fieldValues
(
volScalarFieldValue zoneID 3
);
}
);
// ************************************************************************* //

View File

@ -0,0 +1,38 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object setFieldsDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
defaultFieldValues
(
volScalarFieldValue alpha.water 0
);
regions
(
boxToCell
{
box ( -100 -100 -100 ) ( 100 0.0 100 );
fieldValues ( volScalarFieldValue alpha.water 1 );
}
boxToFace
{
box ( -100 -100 -100 ) ( 100 0.0 100 );
fieldValues ( volScalarFieldValue alpha.water 1 );
}
);
// ************************************************************************* //

View File

@ -0,0 +1,138 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object topoSetDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
actions
(
{
name bgr0; // all around bgr
// set hullBox0set;
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name background;
}
}
{
name hullBox0; // all around bgr
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name hullBox;
}
}
{
name propeller0; // all around bgr
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name propeller;
}
}
{
name rudder0; // all around bgr
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name rudder;
}
}
{
name box; //all cells
type cellSet;
action new;
source cellToCell;
sourceInfo
{
set hullBox0;
}
}
{
name box; // hole in mesh
type cellSet;
action subset;
source boxToCell;
sourceInfo
{
boxes
(
(0.05 -0.082 -0.1)(0.52 0.052 0.1) //hullBox
// (0 -1 -1)(5 1 1) //hullBox
// (-0.02 -0.05 -0.03)( -0.01 0.05 0.03) //propeller
// (-0.08 -0.08 -0.03)(-0.06 0.08 0.03) //rudder
);
}
}
{
name box;
type cellSet;
action invert;
}
{
name keepBox; //all cells
type cellSet;
action new;
source cellToCell;
sourceInfo
{
set box;
}
}
{
name keepBox; //all cells
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set propeller0;
}
}
{
name keepBox; //all cells
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set rudder0;
}
}
{
name keepBox; //all cells
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set bgr0;
}
}
);
// ************************************************************************* //

View File

@ -0,0 +1,109 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object topoSetDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
actions
(
{
name hullBox0; // all around bgr
type cellSet;
action new;
source regionToCell;
sourceInfo
{
insidePoints ((0.3 0.001 0.001));
}
}
// Select box to remove from region 1 and 2
// {
// name box; //all but hullBox0 region
// type cellSet;
// action new;
// source cellToCell;
// sourceInfo
// {
// set c0;
// }
// }
{
name box; // all cells including hullBox0
type cellSet;
action new; // was: add;
source cellToCell;
sourceInfo
{
set hullBox0;
}
}
{
name box;
type cellSet;
action subset;
source boxToCell;
sourceInfo
{
boxes
(
(0.0501 -0.1 -0.1)(0.5 0.1 0.1) //hullBox
// (0 -1 -1)(5 1 1) //hullBox
// (-0.02 -0.05 -0.03)( -0.01 0.05 0.03) //propeller
// (-0.08 -0.08 -0.03)(-0.06 0.08 0.03) //rudder
);
}
}
{
name box;
type cellSet;
action invert;
}
{
name c0; //copy
type cellSet;
action new;
source cellToCell;
sourceInfo
{
set hullBox0;
}
}
{
name c0; //all cells but hullBox0 region
type cellSet;
action invert;
}
{
name box; // all cells including hullBox0
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set c0;
}
}
);
// ************************************************************************* //

View File

@ -0,0 +1,261 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object topoSetDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
actions
(
{
name bgr0; // all around bgr
// set hullBox0set;
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name background;
}
}
{
name hullBox0; // all around hull
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name hullBox;
}
}
{
name propeller0; // all around propeller
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name propeller;
}
}
{
name rudder0; // all around rudder
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name rudder;
}
}
{
name box; //all cells
type cellSet;
action new;
source cellToCell;
sourceInfo
{
set propeller0;
}
}
{
name box; // hole in mesh
type cellSet;
action subset;
source boxToCell;
sourceInfo
{
boxes
(
// (0.15 -0.1 -0.1)(0.5 0.1 0.1) //hullBox
(-0.0199 -0.0499 -0.0499)( -0.00998 0.0499 0.0499) //propeller
// (-0.10 -0.0749 -0.00499)(-0.050 0.0749 0.00499) //rudder
);
}
}
{
name box;
type cellSet;
action invert;
}
{
name keepBox; //all cells
type cellSet;
action new;
source cellToCell;
sourceInfo
{
set box;
}
}
{
name keepBox; //all cells
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set rudder0;
}
}
{
name keepBox; //all cells
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set hullBox0;
}
}
{
name keepBox; //all cells
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set bgr0;
}
}
);
// /*--------------------------------*- C++ -*----------------------------------*\
// | ========= | |
// | \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
// | \\ / O peration | Version: plus-overset |
// | \\ / A nd | Web: www.OpenFOAM.com |
// | \\/ M anipulation | |
// \*---------------------------------------------------------------------------*/
// FoamFile
// {
// version 2.0;
// format ascii;
// class dictionary;
// object topoSetDict;
// }
// // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
//
// actions
// (
// {
// name propeller0; // all around bgr
// type cellSet;
// action new;
// source zoneToCell;
// sourceInfo
// {
// name propeller;
// // insidePoints ((-0.02 0.0001 0.0001));
// }
// }
// {
// name c0; //copy
// type cellSet;
// action new;
// source cellToCell;
// sourceInfo
// {
// set propeller0;
// }
// }
//
// {
// name c0; //all around hullBox0
// type cellSet;
// action invert;
// }
//
// /*
//
// {
// name c1;
// type cellSet;
// action new;
// source regionsToCell;
// sourceInfo
// {
// insidePoints ((-0.01 0.0 0.0));
// set c0;
// }
// }
//
//
//
//
//
// {
// name c1;
// type cellSet;
// action delete;
// source cellToCell;
// sourceInfo
// {
// set c2;
// }
// }
// */
// // Select box to remove from region 1 and 2
//
// {
// name box;
// type cellSet;
// action new;
// source cellToCell;
// sourceInfo
// {
// set c0;
// }
// }
//
//
// {
// name box;
// type cellSet;
// action add;
// source cellToCell;
// sourceInfo
// {
// set propeller0;
// }
// }
//
// {
// name box;
// type cellSet;
// action subset;
// source boxToCell;
// sourceInfo
// {
// boxes
// (
// // (0 -0.1 -0.1)(0.5 0.1 0.1) //hullBox
// (-0.0199 -0.0499 -0.0499)( -0.00998 0.0499 0.0499) //propeller
// // (-0.08 -0.08 -0.03)(-0.06 0.08 0.03) //rudder
// );
// }
// }
//
// {
// name box;
// type cellSet;
// action invert;
// }
// );
//
// // ************************************************************************* //

View File

@ -0,0 +1,39 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object topoSetDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
actions
(
{
name refineSet;
type cellSet;
action new;
source boxToCell;
sourceInfo
{
boxes
(
(-0.2 -0.2 -0.2)(0.0 0.2 0.2) //hullBox
// (0 -1 -1)(5 1 1) //hullBox
// (-0.02 -0.05 -0.03)( -0.01 0.05 0.03) //propeller
// (-0.08 -0.08 -0.03)(-0.06 0.08 0.03) //rudder
);
}
}
);
// ************************************************************************* //

View File

@ -0,0 +1,264 @@
/*--------------------------------*- C++ -*----------------------------------*\
| ========= | |
| \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
| \\ / O peration | Version: plus-overset |
| \\ / A nd | Web: www.OpenFOAM.com |
| \\/ M anipulation | |
\*---------------------------------------------------------------------------*/
FoamFile
{
version 2.0;
format ascii;
class dictionary;
object topoSetDict;
}
// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
actions
(
{
name bgr0; // all around bgr
// set hullBox0set;
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name background;
}
}
{
name hullBox0; // all around hull
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name hullBox;
}
}
{
name propeller0; // all around propeller
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name propeller;
}
}
{
name rudder0; // all around rudder
type cellSet;
action new;
source zoneToCell;
sourceInfo
{
name rudder;
}
}
{
name box; //all cells
type cellSet;
action new;
source cellToCell;
sourceInfo
{
set rudder0;
}
}
{
name box; // hole in mesh
type cellSet;
action subset;
source boxToCell;
sourceInfo
{
boxes
(
// (0.15 -0.1 -0.1)(0.5 0.1 0.1) //hullBox
// (-0.02 -0.05 -0.03)( -0.01 0.05 0.03) //propeller
(-0.10 -0.0749 -0.00499)(-0.050 0.0749 0.00499) //rudder
);
}
}
{
name box;
type cellSet;
action invert;
}
{
name keepBox; //all cells
type cellSet;
action new;
source cellToCell;
sourceInfo
{
set box;
}
}
{
name keepBox; //all cells
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set propeller0;
}
}
{
name keepBox; //all cells
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set hullBox0;
}
}
{
name keepBox; //all cells
type cellSet;
action add;
source cellToCell;
sourceInfo
{
set bgr0;
}
}
);
// ************************************************************************* //
// /*--------------------------------*- C++ -*----------------------------------*\
// | ========= | |
// | \\ / F ield | OpenFOAM: The Open Source CFD Toolbox |
// | \\ / O peration | Version: plus-overset |
// | \\ / A nd | Web: www.OpenFOAM.com |
// | \\/ M anipulation | |
// \*---------------------------------------------------------------------------*/
// FoamFile
// {
// version 2.0;
// format ascii;
// class dictionary;
// object topoSetDict;
// }
// // * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * //
//
// actions
// (
// {
// name rudder0; // all around bgr
// type cellSet;
// action new;
// source zoneToCell;
// sourceInfo
// {
// name rudder;
// //insidePoints ((-0.11 0.0 0.0));
// }
// }
// {
// name c0; //copy
// type cellSet;
// action new;
// source cellToCell;
// sourceInfo
// {
// set rudder0;
// }
// }
//
// {
// name c0; //all around hullBox0
// type cellSet;
// action invert;
// }
//
// /*
//
// {
// name c1;
// type cellSet;
// action new;
// source regionsToCell;
// sourceInfo
// {
// insidePoints ((-0.01 0.0 0.0));
// set c0;
// }
// }
//
//
//
//
//
// {
// name c1;
// type cellSet;
// action delete;
// source cellToCell;
// sourceInfo
// {
// set c2;
// }
// }
// */
// // Select box to remove from region 1 and 2
//
// {
// name box;
// type cellSet;
// action new;
// source cellToCell;
// sourceInfo
// {
// set c0;
// }
// }
//
// {
// name box;
// type cellSet;
// action add;
// source cellToCell;
// sourceInfo
// {
// set rudder0;
// }
// }
//
//
// {
// name box;
// type cellSet;
// action subset;
// source boxToCell;
// sourceInfo
// {
// boxes
// (
// // (0 -0.1 -0.1)(0.5 0.1 0.1) //hullBox
// // (-0.02 -0.05 -0.03)( -0.01 0.05 0.03) //propeller
// (-0.10 -0.0749 -0.00499)(-0.050 0.0749 0.00499) //rudder
// );
// }
// }
//
// {
// name box;
// type cellSet;
// action invert;
// }
// );
//
// // ************************************************************************* //