diff --git a/applications/test/rigidBodyDynamics/spring/spring b/applications/test/rigidBodyDynamics/spring/spring index 3024b0622b795eeeecca0f66da91cf3b5dd6a393..bae00a11ac5c3dc7422d5227e3d9cfcd4f7136b2 100644 --- a/applications/test/rigidBodyDynamics/spring/spring +++ b/applications/test/rigidBodyDynamics/spring/spring @@ -1,3 +1,11 @@ +solver +{ + type Newmark; +} + +// It is necessary to iterate for the Newmark solver +nIter 2; + bodies { weight diff --git a/applications/test/rigidBodyDynamics/spring/spring.C b/applications/test/rigidBodyDynamics/spring/spring.C index d427a620bada87f31975d6a07d69d76135d7c6d4..e6f36524c6bf308b0e3fec0dded54753498a7536 100644 --- a/applications/test/rigidBodyDynamics/spring/spring.C +++ b/applications/test/rigidBodyDynamics/spring/spring.C @@ -29,7 +29,7 @@ Description \*---------------------------------------------------------------------------*/ -#include "rigidBodyModel.H" +#include "rigidBodyMotion.H" #include "masslessBody.H" #include "sphere.H" #include "joints.H" @@ -45,18 +45,19 @@ using namespace RBD; int main(int argc, char *argv[]) { + dictionary springDict(IFstream("spring")()); + // Create the spring model from dictionary - rigidBodyModel spring(dictionary(IFstream("spring")())); + rigidBodyMotion spring(springDict); - Info<< spring << endl; + label nIter(readLabel(springDict.lookup("nIter"))); - // Create the joint-space state fields - rigidBodyModelState springState(spring); - scalarField& q = springState.q(); - scalarField& qDot = springState.qDot(); - scalarField& qDdot = springState.qDdot(); + Info<< spring << endl; + // Create the joint-space force field scalarField tau(spring.nDoF(), Zero); + + // Create the external body force field Field<spatialVector> fx(spring.nBodies(), Zero); OFstream qFile("qVsTime"); @@ -66,27 +67,23 @@ int main(int argc, char *argv[]) scalar deltaT = 0.002; for (scalar t=0; t<4; t+=deltaT) { - qDot += 0.5*deltaT*qDdot; - q += deltaT*qDot; - - // Update the body-state prior to the evaluation of the restraints - spring.forwardDynamicsCorrection(springState); - - // Accumulate the restraint forces - fx = Zero; - spring.applyRestraints(fx); - - // Calculate the body acceleration for the given state - // and restraint forces - spring.forwardDynamics(springState, tau, fx); - - // Update the velocity - qDot += 0.5*deltaT*qDdot; + spring.newTime(); + + for (label i=0; i<nIter; i++) + { + spring.update + ( + deltaT, + deltaT, + tau, + fx + ); + } // Write the results for graph generation // using 'gnuplot spring.gnuplot' - qFile << t << " " << q[0] << endl; - qDotFile << t << " " << qDot[0] << endl; + qFile << t << " " << spring.state().q()[0] << endl; + qDotFile << t << " " << spring.state().qDot()[0] << endl; } Info<< "\nEnd\n" << endl; diff --git a/src/rigidBodyDynamics/Make/files b/src/rigidBodyDynamics/Make/files index 761aec2db192e4d33cba91c2718e66aaac8bb08d..6352eabd93f979c26b9fe4cb0102f020ef26db80 100644 --- a/src/rigidBodyDynamics/Make/files +++ b/src/rigidBodyDynamics/Make/files @@ -38,4 +38,13 @@ rigidBodyModel/forwardDynamics.C rigidBodyModelState/rigidBodyModelState.C rigidBodyModelState/rigidBodyModelStateIO.C +rigidBodyMotion/rigidBodyMotion.C +rigidBodyMotion/rigidBodyMotionIO.C + +rigidBodySolvers/rigidBodySolver/rigidBodySolver.C +rigidBodySolvers/rigidBodySolver/newRigidBodySolver.C +rigidBodySolvers/symplectic/symplectic.C +rigidBodySolvers/Newmark/Newmark.C +rigidBodySolvers/CrankNicolson/CrankNicolson.C + LIB = $(FOAM_LIBBIN)/librigidBodyDynamics diff --git a/src/rigidBodyDynamics/rigidBodyModelState/rigidBodyModelState.H b/src/rigidBodyDynamics/rigidBodyModelState/rigidBodyModelState.H index 770011cc90793edcf6d560d032e8c1f73e08975d..512ce312355f75203c727b22dd99e0c48f21a468 100644 --- a/src/rigidBodyDynamics/rigidBodyModelState/rigidBodyModelState.H +++ b/src/rigidBodyDynamics/rigidBodyModelState/rigidBodyModelState.H @@ -22,7 +22,7 @@ License along with OpenFOAM. If not, see <http://www.gnu.org/licenses/>. Class - Foam::rigidBodyModelState + Foam::RBD::rigidBodyModelState Description Holds the motion state of rigid-body model. diff --git a/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotion.C b/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotion.C new file mode 100644 index 0000000000000000000000000000000000000000..d8d0f9dcbd9d8007f36793722d693ff0cbac8d05 --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotion.C @@ -0,0 +1,177 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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 "rigidBodyMotion.H" +#include "rigidBodySolver.H" + +// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodyMotion::rigidBodyMotion() +: + rigidBodyModel(), + motionState_(*this), + motionState0_(*this), + aRelax_(1.0), + aDamp_(1.0), + report_(false), + solver_(NULL) +{} + + +Foam::RBD::rigidBodyMotion::rigidBodyMotion +( + const dictionary& dict +) +: + rigidBodyModel(dict), + motionState_(*this), + motionState0_(motionState_), + aRelax_(dict.lookupOrDefault<scalar>("accelerationRelaxation", 1.0)), + aDamp_(dict.lookupOrDefault<scalar>("accelerationDamping", 1.0)), + report_(dict.lookupOrDefault<Switch>("report", false)), + solver_(rigidBodySolver::New(*this, dict.subDict("solver"))) +{} + + +Foam::RBD::rigidBodyMotion::rigidBodyMotion +( + const dictionary& dict, + const dictionary& stateDict +) +: + rigidBodyModel(dict), + motionState_(*this, stateDict), + motionState0_(motionState_), + aRelax_(dict.lookupOrDefault<scalar>("accelerationRelaxation", 1.0)), + aDamp_(dict.lookupOrDefault<scalar>("accelerationDamping", 1.0)), + report_(dict.lookupOrDefault<Switch>("report", false)), + solver_(rigidBodySolver::New(*this, dict.subDict("solver"))) +{} + + +// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodyMotion::~rigidBodyMotion() +{} + + +// * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * * // + +void Foam::RBD::rigidBodyMotion::update +( + scalar deltaT, + scalar deltaT0, + const scalarField& tau, + const Field<spatialVector>& fx +) +{ + if (Pstream::master()) + { + solver_->solve(deltaT, deltaT0, tau, fx); + + if (report_) + { + status(); + } + } + + Pstream::scatter(motionState_); +} + + +void Foam::RBD::rigidBodyMotion::status() const +{ + /* + Info<< "Rigid body motion" << nl + << " Centre of rotation: " << centreOfRotation() << nl + << " Centre of mass: " << centreOfMass() << nl + << " Orientation: " << orientation() << nl + << " Linear velocity: " << v() << nl + << " Angular velocity: " << omega() + << endl; + */ +} + +/* +Foam::tmp<Foam::pointField> Foam::RBD::rigidBodyMotion::transform +( + const pointField& initialPoints +) const +{ + return + ( + centreOfRotation() + + (Q() & initialQ_.T() & (initialPoints - initialCentreOfRotation_)) + ); +} + + +Foam::tmp<Foam::pointField> Foam::RBD::rigidBodyMotion::transform +( + const pointField& initialPoints, + const scalarField& scale +) const +{ + // Calculate the transformation septerion from the initial state + septernion s + ( + centreOfRotation() - initialCentreOfRotation(), + quaternion(Q() & initialQ().T()) + ); + + tmp<pointField> tpoints(new pointField(initialPoints)); + pointField& points = tpoints.ref(); + + forAll(points, pointi) + { + // Move non-stationary points + if (scale[pointi] > SMALL) + { + // Use solid-body motion where scale = 1 + if (scale[pointi] > 1 - SMALL) + { + points[pointi] = transform(initialPoints[pointi]); + } + // Slerp septernion interpolation + else + { + septernion ss(slerp(septernion::I, s, scale[pointi])); + + points[pointi] = + initialCentreOfRotation() + + ss.transform + ( + initialPoints[pointi] + - initialCentreOfRotation() + ); + } + } + } + + return tpoints; +} +*/ + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotion.H b/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotion.H new file mode 100644 index 0000000000000000000000000000000000000000..632ec8b46e7fe19866f447a2063b6a94d76dfda9 --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotion.H @@ -0,0 +1,198 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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::rigidBodyMotion + +Description + Six degree of freedom motion for a rigid body. + + Angular momentum stored in body fixed reference frame. Reference + orientation of the body (where Q = I) must align with the cartesian axes + such that the Inertia tensor is in principle component form. Can add + restraints (e.g. a spring) and constraints (e.g. motion may only be on a + plane). + + The time-integrator for the motion is run-time selectable with options for + symplectic (explicit), Crank-Nicolson and Newmark schemes. + +SourceFiles + rigidBodyMotionI.H + rigidBodyMotion.C + rigidBodyMotionIO.C + +\*---------------------------------------------------------------------------*/ + +#ifndef rigidBodyMotion_H +#define rigidBodyMotion_H + +#include "rigidBodyModel.H" +#include "rigidBodyModelState.H" +#include "pointField.H" +#include "Switch.H" + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +namespace Foam +{ +namespace RBD +{ + +// Forward declarations +class rigidBodySolver; + +/*---------------------------------------------------------------------------*\ + Class rigidBodyMotion Declaration +\*---------------------------------------------------------------------------*/ + +class rigidBodyMotion +: + public rigidBodyModel +{ + friend class rigidBodySolver; + + // Private data + + //- Motion state data object + rigidBodyModelState motionState_; + + //- Motion state data object for previous time-step + rigidBodyModelState motionState0_; + + //- Acceleration relaxation coefficient + scalar aRelax_; + + //- Acceleration damping coefficient (for steady-state simulations) + scalar aDamp_; + + //- Switch to turn reporting of motion data on and off + Switch report_; + + //- Motion solver + autoPtr<rigidBodySolver> solver_; + + + //- Construct as copy + rigidBodyMotion(const rigidBodyMotion&); + + +public: + + // Constructors + + //- Construct null + rigidBodyMotion(); + + //- Construct from dictionary + rigidBodyMotion + ( + const dictionary& dict + ); + + //- Construct from constant and state dictionaries + rigidBodyMotion + ( + const dictionary& dict, + const dictionary& stateDict + ); + + + //- Destructor + ~rigidBodyMotion(); + + + // Member Functions + + // Access + + //- Return the report Switch + inline bool report() const; + + //- Return the motion state + inline const rigidBodyModelState& state() const; + + + // Edit + + //- Store the motion state at the beginning of the time-step + inline void newTime(); + + + // Update state + + //- Integration of velocities, orientation and position. + void update + ( + scalar deltaT, + scalar deltaT0, + const scalarField& tau, + const Field<spatialVector>& fx + ); + + //- Report the status of the motion + void status() const; + + + // Transformations + + /* + //- Transform the given initial state point by the current motion + // state + inline point transform(const point& initialPoints) const; + + //- Transform the given initial state pointField by the current + // motion state + tmp<pointField> transform(const pointField& initialPoints) const; + + //- Transform the given initial state pointField by the current + // motion state scaled by the given scale + tmp<pointField> transform + ( + const pointField& initialPoints, + const scalarField& scale + ) const; + */ + + //- Write + void write(Ostream&) const; + + //- Read coefficients dictionary and update system parameters, + // constraints and restraints but not the current state + bool read(const dictionary& dict); +}; + + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +} // End namespace RBD +} // End namespace Foam + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +#include "rigidBodyMotionI.H" + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +#endif + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotionI.H b/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotionI.H new file mode 100644 index 0000000000000000000000000000000000000000..9052f9386df383bddfa78d0ba6d72a38d4db0c56 --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotionI.H @@ -0,0 +1,61 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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/>. + +\*---------------------------------------------------------------------------*/ + +// * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * * // + +inline bool Foam::RBD::rigidBodyMotion::report() const +{ + return report_; +} + + +inline const Foam::RBD::rigidBodyModelState& +Foam::RBD::rigidBodyMotion::state() const +{ + return motionState_; +} + + +inline void Foam::RBD::rigidBodyMotion::newTime() +{ + motionState0_ = motionState_; +} + +/* +inline Foam::point Foam::RBD::rigidBodyMotion::transform +( + const point& initialPoint +) const +{ + return + ( + centreOfRotation() + + (Q() & initialQ_.T() & (initialPoint - initialCentreOfRotation_)) + ); +} +*/ + + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotionIO.C b/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotionIO.C new file mode 100644 index 0000000000000000000000000000000000000000..915af7f56f1a5fd3dd467a889f74fdf6709c1f08 --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodyMotion/rigidBodyMotionIO.C @@ -0,0 +1,56 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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 "rigidBodyMotion.H" +#include "IOstreams.H" + +// * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * * // + +bool Foam::RBD::rigidBodyMotion::read(const dictionary& dict) +{ + rigidBodyModel::read(dict); + + aRelax_ = dict.lookupOrDefault<scalar>("accelerationRelaxation", 1.0); + aDamp_ = dict.lookupOrDefault<scalar>("accelerationDamping", 1.0); + report_ = dict.lookupOrDefault<Switch>("report", false); + + return true; +} + + +void Foam::RBD::rigidBodyMotion::write(Ostream& os) const +{ + rigidBodyModel::write(os); + + os.writeKeyword("accelerationRelaxation") + << aRelax_ << token::END_STATEMENT << nl; + os.writeKeyword("accelerationDamping") + << aDamp_ << token::END_STATEMENT << nl; + os.writeKeyword("report") + << report_ << token::END_STATEMENT << nl; +} + + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/CrankNicolson/CrankNicolson.C b/src/rigidBodyDynamics/rigidBodySolvers/CrankNicolson/CrankNicolson.C new file mode 100644 index 0000000000000000000000000000000000000000..694e1f003c28539d6a07049b7e3702ab46d7bdeb --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/CrankNicolson/CrankNicolson.C @@ -0,0 +1,92 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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 "CrankNicolson.H" +#include "addToRunTimeSelectionTable.H" + +// * * * * * * * * * * * * * * Static Data Members * * * * * * * * * * * * * // + +namespace Foam +{ +namespace RBD +{ +namespace rigidBodySolvers +{ + defineTypeNameAndDebug(CrankNicolson, 0); + addToRunTimeSelectionTable(rigidBodySolver, CrankNicolson, dictionary); +} +} +} + + +// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodySolvers::CrankNicolson::CrankNicolson +( + rigidBodyMotion& body, + const dictionary& dict +) +: + rigidBodySolver(body), + aoc_(dict.lookupOrDefault<scalar>("aoc", 0.5)), + voc_(dict.lookupOrDefault<scalar>("voc", 0.5)) +{} + + +// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodySolvers::CrankNicolson::~CrankNicolson() +{} + + +// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // + +void Foam::RBD::rigidBodySolvers::CrankNicolson::solve +( + scalar deltaT, + scalar deltaT0, + const scalarField& tau, + const Field<spatialVector>& fx +) +{ + // Accumulate the restraint forces + Field<spatialVector> rfx(fx); + model_.applyRestraints(rfx); + + // Calculate the accelerations for the given state and forces + model_.forwardDynamics(state(), tau, rfx); + + // Correct velocity + qDot() = qDot0() + aDamp()*deltaT*(aoc_*qDdot() + (1 - aoc_)*qDdot0()); + + // Correct position + q() = q0() + deltaT*(voc_*qDot() + (1 - voc_)*qDot0()); + + // Update the body-state + model_.forwardDynamicsCorrection(state()); +} + + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/CrankNicolson/CrankNicolson.H b/src/rigidBodyDynamics/rigidBodySolvers/CrankNicolson/CrankNicolson.H new file mode 100644 index 0000000000000000000000000000000000000000..048e6f967cce88e1b8152da2374b1ece4dd3eb4d --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/CrankNicolson/CrankNicolson.H @@ -0,0 +1,128 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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::rigidBodySolvers::CrankNicolson + +Description + Crank-Nicolson 2nd-order time-integrator for 6DoF solid-body motion. + + The off-centering coefficients for acceleration (velocity integration) and + velocity (position/orientation integration) may be specified but default + values of 0.5 for each are used if they are not specified. With the default + off-centering this scheme is equivalent to the Newmark scheme with default + coefficients. + + Example specification in dynamicMeshDict: + \verbatim + solver + { + type CrankNicolson; + aoc 0.5; // Acceleration off-centering coefficient + voc 0.5; // Velocity off-centering coefficient + } + \endverbatim + +SeeAlso + Foam::RBD::rigidBodySolvers::Newmark + +SourceFiles + CrankNicolson.C + +\*---------------------------------------------------------------------------*/ + +#ifndef CrankNicolson_H +#define CrankNicolson_H + +#include "rigidBodySolver.H" + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +namespace Foam +{ +namespace RBD +{ +namespace rigidBodySolvers +{ + +/*---------------------------------------------------------------------------*\ + Class CrankNicolson Declaration +\*---------------------------------------------------------------------------*/ + +class CrankNicolson +: + public rigidBodySolver +{ + // Private data + + //- Acceleration off-centering coefficient (default: 0.5) + const scalar aoc_; + + //- Velocity off-centering coefficient (default: 0.5) + const scalar voc_; + + +public: + + //- Runtime type information + TypeName("CrankNicolson"); + + + // Constructors + + //- Construct for the given body from dictionary + CrankNicolson + ( + rigidBodyMotion& body, + const dictionary& dict + ); + + + //- Destructor + virtual ~CrankNicolson(); + + + // Member Functions + + //- Integrate the rigid-body joint-state one time-step + virtual void solve + ( + scalar deltaT, + scalar deltaT0, + const scalarField& tau, + const Field<spatialVector>& fx + ); +}; + + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +} // End namespace rigidBodySolvers +} // End namespace RBD +} // End namespace Foam + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +#endif + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/Newmark/Newmark.C b/src/rigidBodyDynamics/rigidBodySolvers/Newmark/Newmark.C new file mode 100644 index 0000000000000000000000000000000000000000..8d8b8c767b6bfc91fa3cd67860ed813c9992ab3f --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/Newmark/Newmark.C @@ -0,0 +1,101 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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 "Newmark.H" +#include "addToRunTimeSelectionTable.H" + +// * * * * * * * * * * * * * * Static Data Members * * * * * * * * * * * * * // + +namespace Foam +{ +namespace RBD +{ +namespace rigidBodySolvers +{ + defineTypeNameAndDebug(Newmark, 0); + addToRunTimeSelectionTable(rigidBodySolver, Newmark, dictionary); +} +} +} + + +// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodySolvers::Newmark::Newmark +( + rigidBodyMotion& body, + const dictionary& dict +) +: + rigidBodySolver(body), + gamma_(dict.lookupOrDefault<scalar>("gamma", 0.5)), + beta_ + ( + max + ( + 0.25*sqr(gamma_ + 0.5), + dict.lookupOrDefault<scalar>("beta", 0.25) + ) + ) +{} + + +// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodySolvers::Newmark::~Newmark() +{} + + +// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // + +void Foam::RBD::rigidBodySolvers::Newmark::solve +( + scalar deltaT, + scalar deltaT0, + const scalarField& tau, + const Field<spatialVector>& fx +) +{ + // Accumulate the restraint forces + Field<spatialVector> rfx(fx); + model_.applyRestraints(rfx); + + // Calculate the accelerations for the given state and forces + model_.forwardDynamics(state(), tau, rfx); + + // Correct velocity + qDot() = qDot0() + aDamp()*deltaT*(gamma_*qDdot() + (1 - gamma_)*qDdot0()); + + // Correct position + q() = q0() + + deltaT*qDot0() + + sqr(deltaT)*beta_*qDdot() + sqr(deltaT)*(0.5 - beta_)*qDdot0(); + + // Update the body-state + model_.forwardDynamicsCorrection(state()); +} + + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/Newmark/Newmark.H b/src/rigidBodyDynamics/rigidBodySolvers/Newmark/Newmark.H new file mode 100644 index 0000000000000000000000000000000000000000..7faeebdf7d0e6cc32d5e2a616259a4711eca49fb --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/Newmark/Newmark.H @@ -0,0 +1,126 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2015 OpenFOAM Foundation + \\/ 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::rigidBodySolvers::Newmark + +Description + Newmark 2nd-order time-integrator for 6DoF solid-body motion. + + Reference: + \verbatim + Newmark, N. M. (1959). + A method of computation for structural dynamics. + Journal of the Engineering Mechanics Division, 85(3), 67-94. + \endverbatim + + Example specification in dynamicMeshDict: + \verbatim + solver + { + type Newmark; + gamma 0.5; // Velocity integration coefficient + beta 0.25; // Position integration coefficient + } + \endverbatim + +SourceFiles + Newmark.C + +\*---------------------------------------------------------------------------*/ + +#ifndef Newmark_H +#define Newmark_H + +#include "rigidBodySolver.H" + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +namespace Foam +{ +namespace RBD +{ +namespace rigidBodySolvers +{ + +/*---------------------------------------------------------------------------*\ + Class Newmark Declaration +\*---------------------------------------------------------------------------*/ + +class Newmark +: + public rigidBodySolver +{ + // Private data + + //- Coefficient for velocity integration (default: 0.5) + const scalar gamma_; + + //- Coefficient for position and orientation integration (default: 0.25) + const scalar beta_; + + +public: + + //- Runtime type information + TypeName("Newmark"); + + + // Constructors + + //- Construct for the given body from dictionary + Newmark + ( + rigidBodyMotion& body, + const dictionary& dict + ); + + + //- Destructor + virtual ~Newmark(); + + + // Member Functions + + //- Integrate the rigid-body joint-state one time-step + virtual void solve + ( + scalar deltaT, + scalar deltaT0, + const scalarField& tau, + const Field<spatialVector>& fx + ); +}; + + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +} // End namespace rigidBodySolvers +} // End namespace RBD +} // End namespace Foam + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +#endif + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/newRigidBodySolver.C b/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/newRigidBodySolver.C new file mode 100644 index 0000000000000000000000000000000000000000..8db7777f7758d5dbf7f6d857515dbdbcc05d39bf --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/newRigidBodySolver.C @@ -0,0 +1,57 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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 "rigidBodySolver.H" + +// * * * * * * * * * * * * * * * * Selector * * * * * * * * * * * * * * * * // + +Foam::autoPtr<Foam::RBD::rigidBodySolver> Foam::RBD::rigidBodySolver::New +( + rigidBodyMotion& body, + const dictionary& dict +) +{ + word rigidBodySolverType(dict.lookup("type")); + + Info<< "Selecting rigidBodySolver " << rigidBodySolverType << endl; + + dictionaryConstructorTable::iterator cstrIter = + dictionaryConstructorTablePtr_->find(rigidBodySolverType); + + if (cstrIter == dictionaryConstructorTablePtr_->end()) + { + FatalErrorInFunction + << "Unknown rigidBodySolverType type " + << rigidBodySolverType << endl << endl + << "Valid rigidBodySolver types are : " << endl + << dictionaryConstructorTablePtr_->sortedToc() + << exit(FatalError); + } + + return cstrIter()(body, dict); +} + + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/rigidBodySolver.C b/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/rigidBodySolver.C new file mode 100644 index 0000000000000000000000000000000000000000..669d8c9cc355267dd340d5b7d6fbaa05e6a45292 --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/rigidBodySolver.C @@ -0,0 +1,55 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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 "rigidBodySolver.H" + +// * * * * * * * * * * * * * * Static Data Members * * * * * * * * * * * * * // + +namespace Foam +{ +namespace RBD +{ + + defineTypeNameAndDebug(rigidBodySolver, 0); + defineRunTimeSelectionTable(rigidBodySolver, dictionary); +} +} + + +// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodySolver::rigidBodySolver(rigidBodyMotion& body) +: + model_(body) +{} + + +// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodySolver::~rigidBodySolver() +{} + + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/rigidBodySolver.H b/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/rigidBodySolver.H new file mode 100644 index 0000000000000000000000000000000000000000..c4137d4b9a3aa4683ccbc864419aca4cccea7be3 --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/rigidBodySolver.H @@ -0,0 +1,165 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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::rigidBodySolver + +Description + +SourceFiles + rigidBodySolver.C + newSixDoFSolver.C + +\*---------------------------------------------------------------------------*/ + +#ifndef RBD_rigidBodySolver_H +#define RBD_rigidBodySolver_H + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +#include "rigidBodyMotion.H" +#include "runTimeSelectionTables.H" + +namespace Foam +{ +namespace RBD +{ + +/*---------------------------------------------------------------------------*\ + Class rigidBodySolver Declaration +\*---------------------------------------------------------------------------*/ + +class rigidBodySolver +{ +protected: + + // Protected data + + //- The rigid-body model + rigidBodyMotion& model_; + + + //- Return the motion state + inline rigidBodyModelState& state(); + + //- Return the motion state + inline const rigidBodyModelState& state0() const; + + + //- Return the current joint position and orientation + inline scalarField& q(); + + //- Return the current joint quaternion + inline scalarField& w(); + + //- Return the current joint velocity + inline scalarField& qDot(); + + //- Return the current joint acceleration + inline scalarField& qDdot(); + + + //- Return the current joint position and orientation + inline const scalarField& q0() const; + + //- Return the current joint quaternion + inline const scalarField& w0() const; + + //- Return the current joint velocity + inline const scalarField& qDot0() const; + + //- Return the current joint acceleration + inline const scalarField& qDdot0() const; + + + //- Acceleration damping coefficient (for steady-state simulations) + inline scalar aDamp() const; + + +public: + + //- Runtime type information + TypeName("rigidBodySolver"); + + + // Declare runtime construction + + declareRunTimeSelectionTable + ( + autoPtr, + rigidBodySolver, + dictionary, + ( + rigidBodyMotion& body, + const dictionary& dict + ), + (body, dict) + ); + + + // Constructors + + // Construct for given body + rigidBodySolver(rigidBodyMotion& body); + + + //- Destructor + virtual ~rigidBodySolver(); + + + // Selectors + + static autoPtr<rigidBodySolver> New + ( + rigidBodyMotion& body, + const dictionary& dict + ); + + + // Member Functions + + //- Integrate the rigid-body joint-state one time-step + virtual void solve + ( + scalar deltaT, + scalar deltaT0, + const scalarField& tau, + const Field<spatialVector>& fx + ) = 0; +}; + + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +} // End namespace RBD +} // End namespace Foam + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +#include "rigidBodySolverI.H" + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +#endif + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/rigidBodySolverI.H b/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/rigidBodySolverI.H new file mode 100644 index 0000000000000000000000000000000000000000..b3d8043fa29da45b178112d69c27a54967baa815 --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/rigidBodySolver/rigidBodySolverI.H @@ -0,0 +1,95 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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/>. + +\*---------------------------------------------------------------------------*/ + +// * * * * * * * * * * * * * Protected Member Functions * * * * * * * * * * // + +inline Foam::RBD::rigidBodyModelState& Foam::RBD::rigidBodySolver::state() +{ + return model_.motionState_; +} + + +inline const Foam::RBD::rigidBodyModelState& +Foam::RBD::rigidBodySolver::state0() const +{ + return model_.motionState0_; +} + + +inline Foam::scalarField& Foam::RBD::rigidBodySolver::q() +{ + return state().q(); +} + + +inline Foam::scalarField& Foam::RBD::rigidBodySolver::w() +{ + return state().w(); +} + + +inline Foam::scalarField& Foam::RBD::rigidBodySolver::qDot() +{ + return state().qDot(); +} + + +inline Foam::scalarField& Foam::RBD::rigidBodySolver::qDdot() +{ + return state().qDdot(); +} + + +inline const Foam::scalarField& Foam::RBD::rigidBodySolver::q0() const +{ + return state0().q(); +} + + +inline const Foam::scalarField& Foam::RBD::rigidBodySolver::w0() const +{ + return state0().w(); +} + + +inline const Foam::scalarField& Foam::RBD::rigidBodySolver::qDot0() const +{ + return state0().qDot(); +} + + +inline const Foam::scalarField& Foam::RBD::rigidBodySolver::qDdot0() const +{ + return state0().qDdot(); +} + + +inline Foam::scalar Foam::RBD::rigidBodySolver::aDamp() const +{ + return model_.aDamp_; +} + + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/symplectic/symplectic.C b/src/rigidBodyDynamics/rigidBodySolvers/symplectic/symplectic.C new file mode 100644 index 0000000000000000000000000000000000000000..b05c5a567b5c90ff22574d52fa90c9a14279529b --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/symplectic/symplectic.C @@ -0,0 +1,95 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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 "symplectic.H" +#include "addToRunTimeSelectionTable.H" + +// * * * * * * * * * * * * * * Static Data Members * * * * * * * * * * * * * // + +namespace Foam +{ +namespace RBD +{ +namespace rigidBodySolvers +{ + defineTypeNameAndDebug(symplectic, 0); + addToRunTimeSelectionTable(rigidBodySolver, symplectic, dictionary); +} +} +} + + +// * * * * * * * * * * * * * * * * Constructors * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodySolvers::symplectic::symplectic +( + rigidBodyMotion& body, + const dictionary& dict +) +: + rigidBodySolver(body) +{} + + +// * * * * * * * * * * * * * * * * Destructor * * * * * * * * * * * * * * * // + +Foam::RBD::rigidBodySolvers::symplectic::~symplectic() +{} + + +// * * * * * * * * * * * * * * * Member Functions * * * * * * * * * * * * * // + +void Foam::RBD::rigidBodySolvers::symplectic::solve +( + scalar deltaT, + scalar deltaT0, + const scalarField& tau, + const Field<spatialVector>& fx +) +{ + // First simplectic step: + // Half-step for linear and angular velocities + // Update position and orientation + qDot() = qDot0() + aDamp()*0.5*deltaT0*qDdot(); + q() = q0() + deltaT*qDot(); + + // Update the body-state prior to the evaluation of the restraints + model_.forwardDynamicsCorrection(state()); + + // Accumulate the restraint forces + Field<spatialVector> rfx(fx); + model_.applyRestraints(rfx); + + // Calculate the body acceleration for the given state + // and restraint forces + model_.forwardDynamics(state(), tau, rfx); + + // Second simplectic step: + // Complete update of linear and angular velocities + qDot() += aDamp()*0.5*deltaT*qDdot(); +} + + +// ************************************************************************* // diff --git a/src/rigidBodyDynamics/rigidBodySolvers/symplectic/symplectic.H b/src/rigidBodyDynamics/rigidBodySolvers/symplectic/symplectic.H new file mode 100644 index 0000000000000000000000000000000000000000..e15a73b59a09e533e0916a7d1a6420319edad7c5 --- /dev/null +++ b/src/rigidBodyDynamics/rigidBodySolvers/symplectic/symplectic.H @@ -0,0 +1,125 @@ +/*---------------------------------------------------------------------------*\ + ========= | + \\ / F ield | OpenFOAM: The Open Source CFD Toolbox + \\ / O peration | + \\ / A nd | Copyright (C) 2016 OpenFOAM Foundation + \\/ 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::rigidBodySolvers::symplectic + +Description + Symplectic 2nd-order explicit time-integrator for rigid-body motion. + + Reference: + \verbatim + Dullweber, A., Leimkuhler, B., & McLachlan, R. (1997). + Symplectic splitting methods for rigid body molecular dynamics. + The Journal of chemical physics, 107(15), 5840-5851. + \endverbatim + + Can only be used for explicit integration of the motion of the body, + i.e. may only be called once per time-step, no outer-correctors may be + applied. For implicit integration with outer-correctors choose either + CrankNicolson or Newmark schemes. + + Example specification in dynamicMeshDict: + \verbatim + solver + { + type symplectic; + } + \endverbatim + +SeeAlso + Foam::RBD::rigidBodySolvers::CrankNicolson + Foam::RBD::rigidBodySolvers::Newmark + +SourceFiles + symplectic.C + +\*---------------------------------------------------------------------------*/ + +#ifndef symplectic_H +#define symplectic_H + +#include "rigidBodySolver.H" + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +namespace Foam +{ +namespace RBD +{ +namespace rigidBodySolvers +{ + +/*---------------------------------------------------------------------------*\ + Class symplectic Declaration +\*---------------------------------------------------------------------------*/ + +class symplectic +: + public rigidBodySolver +{ + +public: + + //- Runtime type information + TypeName("symplectic"); + + + // Constructors + + //- Construct for the given body from dictionary + symplectic + ( + rigidBodyMotion& body, + const dictionary& dict + ); + + + //- Destructor + virtual ~symplectic(); + + + // Member Functions + + //- Integrate the rigid-body joint-state one time-step + virtual void solve + ( + scalar deltaT, + scalar deltaT0, + const scalarField& tau, + const Field<spatialVector>& fx + ); +}; + + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +} // End namespace rigidBodySolvers +} // End namespace RBD +} // End namespace Foam + +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * // + +#endif + +// ************************************************************************* //