ENH: use tmp field factory methods [1] (#2723)

- src/OpenFOAM, src/meshTools, src/mesh, src/dynamicMesh, src/sampling
  src/topoChanger src/overset src/fvMotionSolver
This commit is contained in:
Mark Olesen
2024-01-23 09:03:59 +01:00
parent ac574a6ccb
commit 21196d8c0b
30 changed files with 128 additions and 254 deletions

View File

@ -46,7 +46,8 @@ Foam::tmp<GeoField> Foam::uniformInterpolate
field0.time().timeName(), field0.time().timeName(),
field0.db(), field0.db(),
IOobject::NO_READ, IOobject::NO_READ,
IOobject::AUTO_WRITE IOobject::AUTO_WRITE,
IOobject::REGISTER
), ),
weights[0]*(*fields[indices[0]]) weights[0]*(*fields[indices[0]])
); );

View File

@ -90,16 +90,11 @@ template<class Type, class DType, class LUType>
Foam::tmp<Foam::Field<Type>> Foam::tmp<Foam::Field<Type>>
Foam::LduMatrix<Type, DType, LUType>::H(const Field<Type>& psi) const Foam::LduMatrix<Type, DType, LUType>::H(const Field<Type>& psi) const
{ {
tmp<Field<Type>> tHpsi auto tHpsi = tmp<Field<Type>>::New(lduAddr().size(), Foam::zero{});
(
new Field<Type>(lduAddr().size(), Zero)
);
if (lowerPtr_ || upperPtr_) if (lowerPtr_ || upperPtr_)
{ {
Field<Type> & Hpsi = tHpsi(); Type* __restrict__ HpsiPtr = tHpsi.ref().begin();
Type* __restrict__ HpsiPtr = Hpsi.begin();
const Type* __restrict__ psiPtr = psi.begin(); const Type* __restrict__ psiPtr = psi.begin();

View File

@ -35,7 +35,7 @@ Description
template<class Type> template<class Type>
Foam::tmp<Foam::Field<Type>> Foam::lduMatrix::H(const Field<Type>& psi) const Foam::tmp<Foam::Field<Type>> Foam::lduMatrix::H(const Field<Type>& psi) const
{ {
auto tHpsi = tmp<Field<Type>>::New(lduAddr().size(), Zero); auto tHpsi = tmp<Field<Type>>::New(lduAddr().size(), Foam::zero{});
if (lowerPtr_ || upperPtr_) if (lowerPtr_ || upperPtr_)
{ {

View File

@ -1195,7 +1195,7 @@ void Foam::polyMesh::movePoints(const pointField& newPoints)
{ {
if (debug) if (debug)
{ {
Info<< "tmp<scalarField> polyMesh::movePoints(const pointField&) : " Info<< "void polyMesh::movePoints(const pointField&) : "
<< " Storing current points for time " << time().value() << " Storing current points for time " << time().value()
<< " index " << time().timeIndex() << endl; << " index " << time().timeIndex() << endl;
} }

View File

@ -333,8 +333,8 @@ const Foam::vectorField::subField Foam::polyPatch::faceAreas() const
Foam::tmp<Foam::vectorField> Foam::polyPatch::faceCellCentres() const Foam::tmp<Foam::vectorField> Foam::polyPatch::faceCellCentres() const
{ {
tmp<vectorField> tcc(new vectorField(size())); auto tcc = tmp<vectorField>::New(size());
vectorField& cc = tcc.ref(); auto& cc = tcc.ref();
// get reference to global cell centres // get reference to global cell centres
const vectorField& gcc = boundaryMesh_.mesh().cellCentres(); const vectorField& gcc = boundaryMesh_.mesh().cellCentres();
@ -352,8 +352,8 @@ Foam::tmp<Foam::vectorField> Foam::polyPatch::faceCellCentres() const
Foam::tmp<Foam::scalarField> Foam::polyPatch::areaFraction() const Foam::tmp<Foam::scalarField> Foam::polyPatch::areaFraction() const
{ {
tmp<scalarField> tfraction(new scalarField(size())); auto tfraction = tmp<scalarField>::New(size());
scalarField& fraction = tfraction.ref(); auto& fraction = tfraction.ref();
const vectorField::subField faceAreas = this->faceAreas(); const vectorField::subField faceAreas = this->faceAreas();
const pointField& points = this->points(); const pointField& points = this->points();

View File

@ -295,46 +295,31 @@ void Foam::interfaceTrackingFvMesh::makeControlPoints()
<< abort(FatalError); << abort(FatalError);
} }
IOobject controlPointsHeader IOobject pointsIO
( (
"controlPoints", "controlPoints",
mesh().time().timeName(), mesh().time().timeName(),
mesh(), mesh(),
IOobject::MUST_READ IOobject::MUST_READ,
IOobject::AUTO_WRITE,
IOobject::REGISTER
); );
if (controlPointsHeader.typeHeaderOk<vectorIOField>()) if (pointsIO.typeHeaderOk<vectorIOField>())
{ {
Info<< "Reading control points" << endl; Info<< "Reading control points" << endl;
controlPointsPtr_ = controlPointsPtr_ = new vectorIOField(pointsIO);
new vectorIOField
(
IOobject
(
"controlPoints",
mesh().time().timeName(),
mesh(),
IOobject::MUST_READ,
IOobject::AUTO_WRITE
)
);
} }
else else
{ {
pointsIO.readOpt(IOobject::NO_READ);
Info<< "Creating new control points" << endl; Info<< "Creating new control points" << endl;
controlPointsPtr_ = controlPointsPtr_ = new vectorIOField
new vectorIOField (
( pointsIO,
IOobject aMesh().areaCentres().internalField()
( );
"controlPoints",
mesh().time().timeName(),
mesh(),
IOobject::NO_READ,
IOobject::AUTO_WRITE
),
aMesh().areaCentres().internalField()
);
initializeControlPointsPosition(); initializeControlPointsPosition();
} }

View File

@ -47,8 +47,8 @@ Foam::tmp<Foam::vectorField> Foam::layerAdditionRemoval::extrusionDir() const
const pointField& points = mesh.points(); const pointField& points = mesh.points();
const labelList& mp = masterFaceLayer.meshPoints(); const labelList& mp = masterFaceLayer.meshPoints();
tmp<vectorField> textrusionDir(new vectorField(mp.size())); auto textrusionDir = tmp<vectorField>::New(mp.size());
vectorField& extrusionDir = textrusionDir.ref(); auto& extrusionDir = textrusionDir.ref();
if (setLayerPairing()) if (setLayerPairing())
{ {

View File

@ -339,8 +339,8 @@ Foam::displacementInterpolationMotionSolver::curPoints() const
<< " points." << exit(FatalError); << " points." << exit(FatalError);
} }
tmp<pointField> tcurPoints(new pointField(points0())); auto tcurPoints = tmp<pointField>::New(points0());
pointField& curPoints = tcurPoints.ref(); auto& curPoints = tcurPoints.ref();
// Interpolate the displacement of the face zones. // Interpolate the displacement of the face zones.
vectorField zoneDisp(displacements_.size(), Zero); vectorField zoneDisp(displacements_.size(), Zero);

View File

@ -6,7 +6,7 @@
\\/ M anipulation | \\/ M anipulation |
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
Copyright (C) 2011-2016 OpenFOAM Foundation Copyright (C) 2011-2016 OpenFOAM Foundation
Copyright (C) 2015-2019 OpenCFD Ltd. Copyright (C) 2015-2023 OpenCFD Ltd.
------------------------------------------------------------------------------- -------------------------------------------------------------------------------
License License
This file is part of OpenFOAM. This file is part of OpenFOAM.
@ -338,14 +338,9 @@ void Foam::displacementLayeredMotionMotionSolver::cellZoneSolve
patchi, patchi,
new pointVectorField new pointVectorField
( (
IOobject mesh().newIOobject
( (
mesh().cellZones()[cellZoneI].name() + "_" + fz.name(), mesh().cellZones()[cellZoneI].name() + "_" + fz.name()
mesh().time().timeName(),
mesh(),
IOobject::NO_READ,
IOobject::NO_WRITE,
IOobject::NO_REGISTER
), ),
pointDisplacement_ // to inherit the boundary conditions pointDisplacement_ // to inherit the boundary conditions
) )
@ -429,20 +424,18 @@ void Foam::displacementLayeredMotionMotionSolver::cellZoneSolve
if (debug) if (debug)
{ {
// Normalised distance // Normalised distance
pointScalarField distance auto tdistance = pointScalarField::New
( (
IOobject IOobject::scopedName
( (
mesh().cellZones()[cellZoneI].name() + ":distance", mesh().cellZones()[cellZoneI].name(),
mesh().time().timeName(), "distance"
mesh(),
IOobject::NO_READ,
IOobject::NO_WRITE,
IOobject::NO_REGISTER
), ),
IOobject::NO_REGISTER,
pointMesh::New(mesh()), pointMesh::New(mesh()),
dimensionedScalar(dimLength, Zero) dimensionedScalar(dimLength, Zero)
); );
auto& distance = tdistance.ref();
for (const label pointi : isZonePoint) for (const label pointi : isZonePoint)
{ {

View File

@ -664,8 +664,8 @@ Foam::tmp<Foam::labelField> Foam::pairPatchAgglomeration::agglomerateOneLevel
{ {
const label nFineFaces = patch.size(); const label nFineFaces = patch.size();
tmp<labelField> tcoarseCellMap(new labelField(nFineFaces, -1)); auto tcoarseCellMap = tmp<labelField>::New(nFineFaces, -1);
labelField& coarseCellMap = tcoarseCellMap.ref(); auto& coarseCellMap = tcoarseCellMap.ref();
const labelListList& faceFaces = patch.faceFaces(); const labelListList& faceFaces = patch.faceFaces();

View File

@ -186,8 +186,8 @@ Foam::displacementComponentLaplacianFvMotionSolver::curPoints() const
} }
else else
{ {
tmp<pointField> tcurPoints(new pointField(fvMesh_.points())); auto tcurPoints = tmp<pointField>::New(fvMesh_.points());
pointField& curPoints = tcurPoints.ref(); auto& curPoints = tcurPoints.ref();
curPoints.replace curPoints.replace
( (

View File

@ -104,7 +104,7 @@ Foam::velocityComponentLaplacianFvMotionSolver::curPoints() const
pointMotionU_ pointMotionU_
); );
tmp<pointField> tcurPoints(new pointField(fvMesh_.points())); auto tcurPoints = tmp<pointField>::New(fvMesh_.points());
tcurPoints.ref().replace tcurPoints.ref().replace
( (

View File

@ -301,28 +301,18 @@ void Foam::surfaceAlignedSBRStressFvMotionSolver::solve()
// Calculate rotations on surface intersection // Calculate rotations on surface intersection
calculateCellRot(); calculateCellRot();
tmp<volVectorField> tUd auto tUd = volVectorField::New
( (
new volVectorField "Ud",
IOobject::NO_REGISTER,
fvMesh_,
dimensionedVector(dimLength, Zero),
cellMotionBoundaryTypes<vector>
( (
IOobject pointDisplacement().boundaryField()
(
"Ud",
fvMesh_.time().timeName(),
fvMesh_,
IOobject::NO_READ,
IOobject::NO_WRITE
),
fvMesh_,
dimensionedVector(dimLength, Zero),
cellMotionBoundaryTypes<vector>
(
pointDisplacement().boundaryField()
)
) )
); );
auto& Ud = tUd.ref();
volVectorField& Ud = tUd.ref();
const vectorList& C = fvMesh_.C(); const vectorList& C = fvMesh_.C();
forAll(Ud, i) forAll(Ud, i)
@ -346,23 +336,14 @@ void Foam::surfaceAlignedSBRStressFvMotionSolver::solve()
const volTensorField gradD("gradD", fvc::grad(Ud)); const volTensorField gradD("gradD", fvc::grad(Ud));
tmp<volScalarField> tmu auto tmu = volScalarField::New
( (
new volScalarField "mu",
( IOobject::NO_REGISTER,
IOobject fvMesh_,
( dimensionedScalar(dimless, Zero)
"mu",
fvMesh_.time().timeName(),
fvMesh_,
IOobject::NO_READ,
IOobject::NO_WRITE
),
fvMesh_,
dimensionedScalar(dimless, Zero)
)
); );
volScalarField& mu = tmu.ref(); auto& mu = tmu.ref();
const scalarList& V = fvMesh_.V(); const scalarList& V = fvMesh_.V();
mu.primitiveFieldRef() = (1.0/V); mu.primitiveFieldRef() = (1.0/V);

View File

@ -113,8 +113,8 @@ Foam::tmp<Foam::scalarField> Foam::snappyLayerDriver::avgPointData
const scalarField& pointFld const scalarField& pointFld
) )
{ {
tmp<scalarField> tfaceFld(new scalarField(pp.size(), Zero)); auto tfaceFld = tmp<scalarField>::New(pp.size(), Zero);
scalarField& faceFld = tfaceFld.ref(); auto& faceFld = tfaceFld.ref();
forAll(pp.localFaces(), facei) forAll(pp.localFaces(), facei)
{ {

View File

@ -257,8 +257,8 @@ Foam::tmp<Foam::pointField> Foam::snappySnapDriver::smoothInternalDisplacement
// Add coupled contributions // Add coupled contributions
weightedPosition::syncPoints(mesh, sumLocation); weightedPosition::syncPoints(mesh, sumLocation);
tmp<pointField> tdisplacement(new pointField(mesh.nPoints(), Zero)); auto tdisplacement = tmp<pointField>::New(mesh.nPoints(), Zero);
pointField& displacement = tdisplacement.ref(); auto& displacement = tdisplacement.ref();
label nAdapted = 0; label nAdapted = 0;
@ -490,8 +490,8 @@ Foam::tmp<Foam::pointField> Foam::snappySnapDriver::smoothPatchDisplacement
// Displacement to calculate. // Displacement to calculate.
tmp<pointField> tpatchDisp(new pointField(meshPoints.size(), Zero)); auto tpatchDisp = tmp<pointField>::New(meshPoints.size(), Zero);
pointField& patchDisp = tpatchDisp.ref(); auto& patchDisp = tpatchDisp.ref();
forAll(pointFaces, i) forAll(pointFaces, i)
{ {
@ -571,8 +571,8 @@ Foam::tmp<Foam::pointField> Foam::snappySnapDriver::smoothPatchDisplacement
// const labelListList& pointEdges = pp.pointEdges(); // const labelListList& pointEdges = pp.pointEdges();
// const edgeList& edges = pp.edges(); // const edgeList& edges = pp.edges();
// //
// tmp<pointField> tavg(new pointField(pointEdges.size(), Zero)); // auto tavg = tmp<pointField>::New(pointEdges.size(), Zero);
// pointField& avg = tavg(); // auto& avg = tavg.ref();
// //
// forAll(pointEdges, verti) // forAll(pointEdges, verti)
// { // {
@ -658,8 +658,8 @@ Foam::tmp<Foam::scalarField> Foam::snappySnapDriver::edgePatchDist
); );
// Copy edge values into scalarField // Copy edge values into scalarField
tmp<scalarField> tedgeDist(new scalarField(mesh.nEdges())); auto tedgeDist = tmp<scalarField>::New(mesh.nEdges());
scalarField& edgeDist = tedgeDist.ref(); auto& edgeDist = tedgeDist.ref();
forAll(allEdgeInfo, edgei) forAll(allEdgeInfo, edgei)
{ {
@ -1057,7 +1057,7 @@ Foam::tmp<Foam::pointField> Foam::snappySnapDriver::avgCellCentres
// Add coupled contributions // Add coupled contributions
weightedPosition::syncPoints(mesh, pp.meshPoints(), avgBoundary); weightedPosition::syncPoints(mesh, pp.meshPoints(), avgBoundary);
tmp<pointField> tavgBoundary(new pointField(avgBoundary.size())); auto tavgBoundary = tmp<pointField>::New(avgBoundary.size());
weightedPosition::getPoints(avgBoundary, tavgBoundary.ref()); weightedPosition::getPoints(avgBoundary, tavgBoundary.ref());
return tavgBoundary; return tavgBoundary;
@ -1073,8 +1073,8 @@ Foam::tmp<Foam::pointField> Foam::snappySnapDriver::avgCellCentres
// // ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ // // ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
// // (Ripped from snappyLayerDriver) // // (Ripped from snappyLayerDriver)
// //
// tmp<scalarField> tedgeLen(new scalarField(pp.nPoints())); // auto tedgeLen = tmp<scalarField>::New(pp.nPoints());
// scalarField& edgeLen = tedgeLen(); // auto& edgeLen = tedgeLen.ref();
// { // {
// const fvMesh& mesh = meshRefiner_.mesh(); // const fvMesh& mesh = meshRefiner_.mesh();
// const scalar edge0Len = meshRefiner_.meshCutter().level0EdgeLength(); // const scalar edge0Len = meshRefiner_.meshCutter().level0EdgeLength();

View File

@ -41,15 +41,8 @@ Foam::cellQuality::cellQuality(const polyMesh& mesh)
Foam::tmp<Foam::scalarField> Foam::cellQuality::nonOrthogonality() const Foam::tmp<Foam::scalarField> Foam::cellQuality::nonOrthogonality() const
{ {
tmp<scalarField> tresult auto tresult = tmp<scalarField>::New(mesh_.nCells(), Zero);
( auto& result = tresult.ref();
new scalarField
(
mesh_.nCells(), 0.0
)
);
scalarField& result = tresult.ref();
scalarField sumArea(mesh_.nCells(), Zero); scalarField sumArea(mesh_.nCells(), Zero);
@ -103,14 +96,8 @@ Foam::tmp<Foam::scalarField> Foam::cellQuality::nonOrthogonality() const
Foam::tmp<Foam::scalarField> Foam::cellQuality::skewness() const Foam::tmp<Foam::scalarField> Foam::cellQuality::skewness() const
{ {
tmp<scalarField> tresult auto tresult = tmp<scalarField>::New(mesh_.nCells(), Zero);
( auto& result = tresult.ref();
new scalarField
(
mesh_.nCells(), 0.0
)
);
scalarField& result = tresult.ref();
scalarField sumArea(mesh_.nCells(), Zero); scalarField sumArea(mesh_.nCells(), Zero);
@ -182,15 +169,8 @@ Foam::tmp<Foam::scalarField> Foam::cellQuality::skewness() const
Foam::tmp<Foam::scalarField> Foam::cellQuality::faceNonOrthogonality() const Foam::tmp<Foam::scalarField> Foam::cellQuality::faceNonOrthogonality() const
{ {
tmp<scalarField> tresult auto tresult = tmp<scalarField>::New(mesh_.nFaces(), Zero);
( auto& result = tresult.ref();
new scalarField
(
mesh_.nFaces(), 0.0
)
);
scalarField& result = tresult.ref();
const vectorField& centres = mesh_.cellCentres(); const vectorField& centres = mesh_.cellCentres();
const vectorField& areas = mesh_.faceAreas(); const vectorField& areas = mesh_.faceAreas();
@ -242,15 +222,8 @@ Foam::tmp<Foam::scalarField> Foam::cellQuality::faceNonOrthogonality() const
Foam::tmp<Foam::scalarField> Foam::cellQuality::faceSkewness() const Foam::tmp<Foam::scalarField> Foam::cellQuality::faceSkewness() const
{ {
tmp<scalarField> tresult auto tresult = tmp<scalarField>::New(mesh_.nFaces(), Zero);
( auto& result = tresult.ref();
new scalarField
(
mesh_.nFaces(), 0.0
)
);
scalarField& result = tresult.ref();
const vectorField& cellCtrs = mesh_.cellCentres(); const vectorField& cellCtrs = mesh_.cellCentres();
const vectorField& faceCtrs = mesh_.faceCentres(); const vectorField& faceCtrs = mesh_.faceCentres();

View File

@ -143,8 +143,8 @@ Foam::tmp<Foam::scalarField> Foam::edgeMeshTools::featureProximity
const scalar searchDistance const scalar searchDistance
) )
{ {
tmp<scalarField> tfld(new scalarField(surf.size(), searchDistance)); auto tfld = tmp<scalarField>::New(surf.size(), searchDistance);
scalarField& featureProximity = tfld.ref(); auto& featureProximity = tfld.ref();
Info<< "Extracting proximity of close feature points and " Info<< "Extracting proximity of close feature points and "
<< "edges to the surface" << endl; << "edges to the surface" << endl;

View File

@ -354,9 +354,8 @@ Foam::tmp<Foam::tensorField> Foam::momentOfInertia::meshInertia
const polyMesh& mesh const polyMesh& mesh
) )
{ {
tmp<tensorField> tTf = tmp<tensorField>(new tensorField(mesh.nCells())); auto tTf = tmp<tensorField>::New(mesh.nCells());
auto& tf = tTf.ref();
tensorField& tf = tTf.ref();
forAll(tf, cI) forAll(tf, cI)
{ {

View File

@ -103,8 +103,8 @@ Foam::triSurfaceTools::writeCloseness
{ {
Pair<tmp<scalarField>> tpair Pair<tmp<scalarField>> tpair
( (
tmp<scalarField>(new scalarField(surf.size(), GREAT)), tmp<scalarField>::New(surf.size(), GREAT),
tmp<scalarField>(new scalarField(surf.size(), GREAT)) tmp<scalarField>::New(surf.size(), GREAT)
); );
Info<< "Extracting internal and external closeness of surface." << endl; Info<< "Extracting internal and external closeness of surface." << endl;

View File

@ -158,22 +158,15 @@ Foam::cellCellStencil::createField
const UList<Type>& psi const UList<Type>& psi
) )
{ {
auto tfld = tmp<volScalarField>::New auto tfld = volScalarField::New
( (
IOobject name,
( IOobject::NO_REGISTER,
name,
mesh.time().timeName(),
mesh,
IOobject::NO_READ,
IOobject::NO_WRITE,
IOobject::NO_REGISTER
),
mesh, mesh,
dimensionedScalar(dimless, Zero), dimensionedScalar(dimless, Zero),
fvPatchFieldBase::zeroGradientType() fvPatchFieldBase::zeroGradientType()
); );
volScalarField& fld = tfld.ref(); auto& fld = tfld.ref();
forAll(psi, cellI) forAll(psi, cellI)
{ {

View File

@ -585,10 +585,7 @@ template<class Type>
Foam::tmp<Foam::Field<Type>> Foam::oversetFvPatchField<Type>:: Foam::tmp<Foam::Field<Type>> Foam::oversetFvPatchField<Type>::
patchNeighbourField() const patchNeighbourField() const
{ {
return tmp<Field<Type>> return tmp<Field<Type>>::New(this->size(), Zero);
(
new Field<Type>(this->size(), Zero)
);
} }

View File

@ -195,10 +195,7 @@ public:
const tmp<scalarField>& const tmp<scalarField>&
) const ) const
{ {
return tmp<Field<Type>> return tmp<Field<Type>>::New(this->size(), Foam::zero{});
(
new Field<Type>(this->size(), Zero)
);
} }
//- Return the matrix source coefficients corresponding to the //- Return the matrix source coefficients corresponding to the
@ -208,30 +205,21 @@ public:
const tmp<scalarField>& const tmp<scalarField>&
) const ) const
{ {
return tmp<Field<Type>> return tmp<Field<Type>>::New(this->size(), Foam::zero{});
(
new Field<Type>(this->size(), Zero)
);
} }
//- Return the matrix diagonal coefficients corresponding to the //- Return the matrix diagonal coefficients corresponding to the
//- evaluation of the gradient of this patchField //- evaluation of the gradient of this patchField
tmp<Field<Type>> gradientInternalCoeffs() const tmp<Field<Type>> gradientInternalCoeffs() const
{ {
return tmp<Field<Type>> return tmp<Field<Type>>::New(this->size(), Foam::zero{});
(
new Field<Type>(this->size(), Zero)
);
} }
//- Return the matrix source coefficients corresponding to the //- Return the matrix source coefficients corresponding to the
//- evaluation of the gradient of this patchField //- evaluation of the gradient of this patchField
tmp<Field<Type>> gradientBoundaryCoeffs() const tmp<Field<Type>> gradientBoundaryCoeffs() const
{ {
return tmp<Field<Type>> return tmp<Field<Type>>::New(this->size(), Foam::zero{});
(
new Field<Type>(this->size(), Zero)
);
} }
//- Manipulate matrix //- Manipulate matrix

View File

@ -238,8 +238,8 @@ Foam::tmp<Foam::pointField> Foam::RBD::rigidBodyMotion::transformPoints
// to the current state in the global frame // to the current state in the global frame
spatialTransform X(X0(bodyID).inv() & X00(bodyID)); spatialTransform X(X0(bodyID).inv() & X00(bodyID));
tmp<pointField> tpoints(new pointField(initialPoints.size())); auto tpoints = tmp<pointField>::New(initialPoints.size());
pointField& points = tpoints.ref(); auto& points = tpoints.ref();
forAll(points, i) forAll(points, i)
{ {
@ -265,8 +265,8 @@ Foam::tmp<Foam::pointField> Foam::RBD::rigidBodyMotion::transformPoints
// interpolation // interpolation
septernion s(X); septernion s(X);
tmp<pointField> tpoints(new pointField(initialPoints)); auto tpoints = tmp<pointField>::New(initialPoints);
pointField& points = tpoints.ref(); auto& points = tpoints.ref();
forAll(points, i) forAll(points, i)
{ {
@ -314,8 +314,8 @@ Foam::tmp<Foam::pointField> Foam::RBD::rigidBodyMotion::transformPoints
ss[bi] = septernion(X); ss[bi] = septernion(X);
} }
tmp<pointField> tpoints(new pointField(initialPoints)); auto tpoints = tmp<pointField>::New(initialPoints);
pointField& points = tpoints.ref(); auto& points = tpoints.ref();
List<scalar> w(ss.size()); List<scalar> w(ss.size());

View File

@ -224,8 +224,8 @@ Foam::rigidBodyMeshMotion::curPoints() const
} }
else else
{ {
tmp<pointField> ttransformedPts(new pointField(mesh().points())); auto ttransformedPts = tmp<pointField>::New(mesh().points());
pointField& transformedPts = ttransformedPts.ref(); auto& transformedPts = ttransformedPts.ref();
UIndirectList<point>(transformedPts, pointIDs()) = UIndirectList<point>(transformedPts, pointIDs()) =
pointField(newPoints.ref(), pointIDs()); pointField(newPoints.ref(), pointIDs());

View File

@ -218,14 +218,7 @@ Foam::tmp<Foam::Field<Type>> Foam::meshToMesh::mapSrcToTgt
const CombineOp& cop const CombineOp& cop
) const ) const
{ {
tmp<Field<Type>> tresult auto tresult = tmp<Field<Type>>::New(tgtToSrcCellAddr_.size(), Zero);
(
new Field<Type>
(
tgtToSrcCellAddr_.size(),
Zero
)
);
mapSrcToTgt(srcField, cop, tresult.ref()); mapSrcToTgt(srcField, cop, tresult.ref());
@ -423,14 +416,7 @@ Foam::tmp<Foam::Field<Type>> Foam::meshToMesh::mapTgtToSrc
const CombineOp& cop const CombineOp& cop
) const ) const
{ {
tmp<Field<Type>> tresult auto tresult = tmp<Field<Type>>::New(srcToTgtCellAddr_.size(), Zero);
(
new Field<Type>
(
srcToTgtCellAddr_.size(),
Zero
)
);
mapTgtToSrc(tgtField, cop, tresult.ref()); mapTgtToSrc(tgtField, cop, tresult.ref());
@ -645,13 +631,13 @@ Foam::meshToMesh::mapSrcToTgt
auto tresult = auto tresult =
tmp<VolumeField<Type>>::New tmp<VolumeField<Type>>::New
( (
IOobject tgtMesh.newIOobject
( (
type() + ":interpolate(" + field.name() + ")", IOobject::scopedName
tgtMesh.time().timeName(), (
tgtMesh, type(),
IOobject::NO_READ, "interpolate(" + field.name() + ")"
IOobject::NO_WRITE )
), ),
tgtMesh, tgtMesh,
field.dimensions(), field.dimensions(),
@ -876,13 +862,13 @@ Foam::meshToMesh::mapTgtToSrc
auto tresult = auto tresult =
tmp<VolumeField<Type>>::New tmp<VolumeField<Type>>::New
( (
IOobject srcMesh.newIOobject
( (
type() + ":interpolate(" + field.name() + ")", IOobject::scopedName
srcMesh.time().timeName(), (
srcMesh, type(),
IOobject::NO_READ, "interpolate(" + field.name() + ")"
IOobject::NO_WRITE )
), ),
srcMesh, srcMesh,
field.dimensions(), field.dimensions(),

View File

@ -464,20 +464,12 @@ void Foam::sampledCuttingPlane::createGeometry()
( (
new volScalarField new volScalarField
( (
IOobject mesh.newIOobject("cellDistance"),
(
"cellDistance",
mesh.time().timeName(),
mesh.time(),
IOobject::NO_READ,
IOobject::NO_WRITE,
IOobject::NO_REGISTER
),
mesh, mesh,
dimensionedScalar(dimLength, Zero) dimensionedScalar(dimLength, Zero)
) )
); );
const volScalarField& cellDistance = cellDistancePtr_(); const auto& cellDistance = *cellDistancePtr_;
setDistanceFields(plane_); setDistanceFields(plane_);
@ -485,20 +477,15 @@ void Foam::sampledCuttingPlane::createGeometry()
{ {
Pout<< "Writing cell distance:" << cellDistance.objectPath() << endl; Pout<< "Writing cell distance:" << cellDistance.objectPath() << endl;
cellDistance.write(); cellDistance.write();
pointScalarField pointDist auto tpointDist = pointScalarField::New
( (
IOobject "pointDistance",
( IOobject::NO_REGISTER,
"pointDistance",
mesh.time().timeName(),
mesh.time(),
IOobject::NO_READ,
IOobject::NO_WRITE,
IOobject::NO_REGISTER
),
pointMesh::New(mesh), pointMesh::New(mesh),
dimensionedScalar(dimLength, Zero) dimensionedScalar(dimLength, Zero)
); );
auto& pointDist = tpointDist.ref();
pointDist.primitiveFieldRef() = pointDistance_; pointDist.primitiveFieldRef() = pointDistance_;
Pout<< "Writing point distance:" << pointDist.objectPath() << endl; Pout<< "Writing point distance:" << pointDist.objectPath() << endl;

View File

@ -393,8 +393,8 @@ Foam::tmp<Foam::pointField> Foam::sixDoFRigidBodyMotion::transform
quaternion(Q().T() & initialQ()) quaternion(Q().T() & initialQ())
); );
tmp<pointField> tpoints(new pointField(initialPoints)); auto tpoints = tmp<pointField>::New(initialPoints);
pointField& points = tpoints.ref(); auto& points = tpoints.ref();
forAll(points, pointi) forAll(points, pointi)
{ {

View File

@ -173,8 +173,8 @@ Foam::sixDoFRigidBodyMotionSolver::curPoints() const
if (!moveAllCells()) if (!moveAllCells())
{ {
tmp<pointField> ttransformedPts(new pointField(mesh().points())); auto ttransformedPts = tmp<pointField>::New(mesh().points());
pointField& transformedPts = ttransformedPts.ref(); auto& transformedPts = ttransformedPts.ref();
UIndirectList<point>(transformedPts, pointIDs()) = UIndirectList<point>(transformedPts, pointIDs()) =
pointField(newPoints.ref(), pointIDs()); pointField(newPoints.ref(), pointIDs());

View File

@ -275,12 +275,8 @@ bool Foam::linearValveLayersFvMesh::attached() const
Foam::tmp<Foam::pointField> Foam::linearValveLayersFvMesh::newPoints() const Foam::tmp<Foam::pointField> Foam::linearValveLayersFvMesh::newPoints() const
{ {
tmp<pointField> tnewPoints auto tnewPoints = tmp<pointField>::New(points());
( auto& np = tnewPoints();
new pointField(points())
);
pointField& np = tnewPoints();
const word layerPatchName const word layerPatchName
( (

View File

@ -70,8 +70,8 @@ Foam::tmp<Foam::scalarField> Foam::movingConeTopoFvMesh::vertexMarkup
Info<< "Updating vertex markup. curLeft: " Info<< "Updating vertex markup. curLeft: "
<< curLeft << " curRight: " << curRight << endl; << curLeft << " curRight: " << curRight << endl;
tmp<scalarField> tvertexMarkup(new scalarField(p.size())); auto tvertexMarkup = tmp<scalarField>::New(p.size());
scalarField& vertexMarkup = tvertexMarkup.ref(); auto& vertexMarkup = tvertexMarkup.ref();
forAll(p, pI) forAll(p, pI)
{ {