35 #include "../sm/EngineeringModels/nlinearstatic.h" 36 #include "../sm/Elements/structuralelement.h" 57 #ifdef __PARALLEL_MODE 67 totalDisplacement(), incrementOfDisplacement(), internalForces(), initialLoadVector(), incrementalLoadVector(),
68 initialLoadVectorOfPrescribed(), incrementalLoadVectorOfPrescribed()
98 if ( mStep == NULL ) {
109 if ( dynamic_cast< CylindricalALM * >(
nMethod) ) {
119 if ( dynamic_cast< NRSolver * >(
nMethod) ) {
208 #ifdef __PARALLEL_MODE 269 OOFEM_ERROR(
"Unknown is of undefined ValueModeType for this problem");
277 if (
master && (!force)) {
295 double totalTime = 0.0;
297 double deltaTtmp =
deltaT;
305 totalTime =
currentStep->giveTargetTime() + deltaTtmp;
307 counter =
currentStep->giveSolutionStateCounter() + 1;
310 if ( !this->
giveMetaStep(mStepNum)->isStepValid(istep) ) {
334 #ifdef __VERBOSE_PARALLEL 373 if ( isLastMetaStep ) {
445 OOFEM_ERROR(
"stiffnessMatrix does not support asymmetric storage");
453 if ( ( mstep->giveFirstStepNumber() == tStep->
giveNumber() ) ) {
598 if ( !this->
giveDomain(1)->giveOutputManager()->testTimeStepOutput(tStep) ) {
602 fprintf(file,
"\n\nOutput for time %.3e, solution step number %d\n", tStep->
giveTargetTime(), tStep->
giveNumber() );
603 fprintf(file,
"Reached load level : %20.6f in %d iterations\n\n",
632 if ( !stream.
write(_cm) ) {
676 if ( !stream.
read(_cm) ) {
709 #ifdef __PARALLEL_MODE 732 static_cast< StructuralElement *
>( elem.get() )->addNonlocalStiffnessContributions(answer, s, tStep);
758 ctype = TangentStiffnessMatrix;
760 ctype = SecantStiffnessMatrix;
762 ctype = SecantStiffnessMatrix;
766 elem->showSparseMtrxStructure(ctype, gc, tStep);
770 elem->showExtendedSparseMtrxStructure(ctype, gc, tStep);
783 OOFEM_ERROR(
"unable to respond due to invalid solution step or domain");
790 FloatArray &_incrementalLoadVectorOfPrescribed,
795 _incrementalLoadVector.
zero();
797 _incrementalLoadVectorOfPrescribed.
zero();
821 int count = 0, pcount = 0;
824 if ( packUnpackType == 0 ) {
825 for (
int map: commMap ) {
827 for (
Dof *dof: *dman ) {
828 if ( dof->isPrimaryDof() && ( dof->__giveEquationNumber() ) ) {
838 }
else if ( packUnpackType == 1 ) {
839 for (
int map: commMap ) {
850 #ifdef __PARALLEL_MODE 892 for (
int idofman = 1; idofman <= ndofman; idofman++ ) {
894 for (
Dof *_dof: *_dm ) {
895 if ( _dof->isPrimaryDof() ) {
897 if ( ( _eq = _dof->__giveEquationNumber() ) ) {
900 if ( initialLoadVectorEmpty ) {
901 _dof->updateUnknownsDictionary(tStep, VM_RhsInitial, 0.0);
907 }
else if ( ( _eq = _dof->__givePrescribedEquationNumber() ) ) {
909 if ( initialLoadVectorOfPrescribedEmpty ) {
910 _dof->updateUnknownsDictionary(tStep, VM_RhsInitial, 0.0);
939 for (
int idofman = 1; idofman <= ndofman; idofman++ ) {
941 for (
Dof *_dof: *_dm ) {
942 if ( _dof->isPrimaryDof() ) {
944 if ( ( _eq = _dof->__giveEquationNumber() ) ) {
953 fprintf(stderr,
"[%d] Shared: %d(%d) -> %d\n", myrank, idofman, idof, _eq);
955 fprintf(stderr,
"[%d] Local : %d(%d) -> %d\n", myrank, idofman, idof, _eq);
959 }
else if ( ( _eq = _dof->__givePrescribedEquationNumber() ) ) {
966 fprintf(stderr,
"[%d] %d(%d) -> %d\n", myrank, idofman, idof, -_eq);
EngngModelTimer timer
E-model timer.
virtual void updateAttributes(MetaStep *mStep)
Update receiver attributes according to step metaStep attributes.
virtual SparseLinearSystemNM * giveLinearSolver()
Constructs (if necessary) and returns a linear solver.
The representation of EngngModel default unknown numbering.
Solves an approximated tangent problem from the last iteration. Useful for changing Dirichlet boundar...
virtual NM_Status solve(SparseMtrx &A, FloatArray &b, FloatArray &x)=0
Solves the given sparse linear system of equations .
virtual IRResultType initializeFrom(InputRecord *ir)
Initializes receiver according to object description in input reader.
LoadBalancer * createLoadBalancer(const char *name, Domain *d)
std::unique_ptr< TimeStep > currentStep
Current time step.
virtual LoadBalancer * giveLoadBalancer()
Returns reference to receiver's load balancer.
virtual TimeStep * giveNextStep()
Returns next time step (next to current step) of receiver.
The reference load vector is obtained as incremental load vector at given time.
virtual int giveNumberOfDomainEquations(int di, const UnknownNumberingScheme &num)
Returns number of equations for given domain in active (current time step) time step.
LoadBalancerMonitor * lbm
int giveNumberOfDofManagers() const
Returns number of dof managers in domain.
Base class for all matrices stored in sparse format.
This class implements Newton-Raphson Method, derived from abstract NumericalMethod class for solving ...
virtual void solveYourself()
Starts solution process.
SparseMtrx * createSparseMtrx(SparseMtrxType type)
Creates new instance of sparse matrix corresponding to given keyword.
The purpose of DataStream abstract class is to allow to store/restore context to different streams...
contextIOResultType storeYourself(DataStream &stream) const
virtual void doStepOutput(TimeStep *tStep)
Prints the ouput of the solution step (using virtual this->printOutputAtservice) to the stream detemi...
std::unique_ptr< TimeStep > previousStep
Previous time step.
double & at(int i)
Coefficient access function.
The secant stiffness is used and updated only at the beginning of new load step.
int max(int i, int j)
Returns bigger value form two given decimals.
int nonlocalStiffnessFlag
MetaStep * giveMetaStep(int i)
Returns the i-th meta step.
ValueModeType
Type representing the mode of UnknownType or CharType, or similar types.
int nonlocalExt
Flag indicating if nonlocal extension active, which will cause data to be sent between shared element...
The tangent stiffness is used and updated whenever requested.
long StateCounterType
StateCounterType type used to indicate solution state.
virtual void showSparseMtrxStructure(int type, oofegGraphicContext &gc, TimeStep *tStep)
Shows the sparse structure of required matrix, type == 1 stiffness.
NonLinearStatic_controlType controlMode
Characterizes the type of control used.
This base class is an abstraction for all numerical methods solving sparse linear system of equations...
FloatArray internalForces
This base class is an abstraction for numerical algorithm.
oofem::oofegGraphicContext gc[OOFEG_LAST_LAYER]
std::unique_ptr< TimeStep > stepWhenIcApply
Solution step when IC (initial conditions) apply.
NonLinearStatic_stiffnessMode stiffMode
EngngModel * giveEngngModel()
Returns engineering model to which receiver is associated.
Implementation for assembling tangent matrices in standard monolithic FE-problems.
virtual int estimateMaxPackSize(IntArray &commMap, DataStream &buff, int packUnpackType)
Determines the space necessary for send/receive buffer.
double giveTargetTime()
Returns target time.
bool isParallel() const
Returns true if receiver in parallel mode.
virtual NumericalMethod * giveNumericalMethod(MetaStep *mStep)
Returns reference to receiver's numerical method.
#define _IFT_NonLinearStatic_updateElasticStiffnessFlag
Base class for dof managers.
int giveNumberOfProcesses() const
Returns the number of collaborating processes.
virtual void solveYourself()
Starts solution process.
#define _IFT_NonLinearStatic_deltat
StateCounterType internalVarUpdateStamp
Contains last time stamp of internal variable update.
int giveNumber()
Returns domain number.
virtual int __giveEquationNumber() const =0
Returns equation number of receiver, usually assigned by emodel.
virtual double giveUnknownComponent(ValueModeType type, TimeStep *tStep, Domain *d, Dof *dof)
Returns requested unknown.
REGISTER_EngngModel(ProblemSequence)
virtual void terminate(TimeStep *tStep)
Terminates the solution of time step.
#define OOFEM_LOG_DEBUG(...)
Class implementing an array of integers.
virtual int read(int *data, int count)=0
Reads count integer values into array pointed by data.
bool updateElasticStiffnessFlag
virtual void giveInternalForces(FloatArray &answer, bool normFlag, int di, TimeStep *tStep)
Evaluates the nodal representation of internal forces by assembling contributions from individual ele...
FloatArray incrementalLoadVector
Incremental load vector which is applied in loading step (as a whole for direct control or proportion...
void printReactionForces(TimeStep *tStep, int id, FILE *out)
Computes and prints reaction forces, computed from nodal internal forces.
double cumulatedLoadLevel
NonLinearStatic_controlType
Type determining type of loading control. This type determines the solver to be used.
NonLinearStatic_stiffnessMode
Type determining the stiffness mode.
virtual void solveYourselfAt(TimeStep *tStep)
Solves problem for given time step.
#define OOFEM_LOG_RELEVANT(...)
void saveStepContext(TimeStep *tStep, ContextMode mode)
Saves context of given solution step, if required (determined using this->giveContextOutputMode() met...
FloatArray initialLoadVectorOfPrescribed
A load vector which does not scale for prescribed DOFs.
FloatArray incrementalLoadVectorOfPrescribed
Incremental Load Vector for prescribed DOFs.
virtual void printStatistics() const
Prints the receiver statistics (one-line) to stdout.
virtual IRResultType initializeFrom(InputRecord *ir)
Initializes receiver according to object description in input reader.
SparseNonLinearSystemNM::referenceLoadInputModeType refLoadInputMode
The following parameter allows to specify how the reference load vector is obtained from given totalL...
double giveTimeIncrement()
Returns solution step associated time increment.
#define _IFT_NonLinearStatic_stiffmode
void assembleIncrementalReferenceLoadVectors(FloatArray &_incrementalLoadVector, FloatArray &_incrementalLoadVectorOfPrescribed, SparseNonLinearSystemNM::referenceLoadInputModeType _refMode, Domain *sourceDomain, TimeStep *tStep)
virtual int write(const int *data, int count)=0
Writes count integer values from array pointed by data.
virtual void assemble(SparseMtrx &answer, TimeStep *tStep, const MatrixAssembler &ma, const UnknownNumberingScheme &s, Domain *domain)
Assembles characteristic matrix of required type into given sparse matrix.
Abstract base class for all "structural" finite elements.
bool loadBalancingFlag
If set to true, load balancing is active.
MetaStep * giveCurrentMetaStep()
Returns current meta step.
ProblemCommunicator * nonlocCommunicator
NonLocal Communicator. Necessary when nonlocal constitutive models are used.
int giveNumber()
Returns receiver's number.
#define OOFEM_LOG_INFO(...)
Element * giveElement(int n)
Service for accessing particular domain fe element.
void proceedStep(int di, TimeStep *tStep)
NumericalCmpn
Type representing numerical component.
SparseNonLinearSystemNM * nMethod
Numerical method used to solve the problem.
void doElementOutput(FILE *, TimeStep *)
Does the element output.
Callback class for assembling specific types of matrices.
virtual void packMigratingData(TimeStep *tStep)
Packs receiver data when rebalancing load.
int updateSharedDofManagers(FloatArray &answer, const UnknownNumberingScheme &s, int ExchangeTag)
Exchanges necessary remote DofManagers data.
The reference incremental load vector is defined as totalLoadVector assembled at given time...
Implementation of sparse nonlinear solver with indirect control.
Implementation for assembling external forces vectors in standard monolithic FE-problems.
bool mstepCumulateLoadLevelFlag
virtual contextIOResultType saveContext(DataStream &stream, ContextMode mode)
Stores the state of model to output stream.
Abstract base class allowing to control the way, how equations are assigned to individual DOFs...
#define _IFT_EngngModel_initialGuess
contextIOResultType restoreYourself(DataStream &stream)
#define _IFT_NonLinearStatic_nonlocalext
ProblemCommunicator * communicator
Communicator.
virtual void printState(FILE *outputStream)
Prints status message of receiver to output stream.
InitialGuess
Means to choose methods for finding a good initial guess.
FloatArray totalDisplacement
EngngModel * master
Master e-model; if defined receiver is in maintained (slave) mode.
CommunicatorBuff * commBuff
Common Communicator buffer.
int nMetaSteps
Number of meta steps.
virtual int giveNumberOfFirstStep(bool force=false)
Returns number of first time step used by receiver.
virtual void printOutputAt(FILE *file, TimeStep *tStep)
Prints output of receiver to output domain stream, for given time step.
referenceLoadInputModeType
The following parameter allows to specify how the reference load vector is obtained from given totalL...
SparseMtrxType sparseMtrxType
bool isEmpty() const
Returns true if receiver is empty.
The initial elastic stiffness is used in the whole solution.
double giveIntrinsicTime()
Returns intrinsic time, e.g. time in which constitutive model is evaluated.
virtual void updateDomainLinks()
Updates domain links after the domains of receiver have changed.
#define _IFT_NonLinearStatic_keepll
double deltaT
Intrinsic time increment.
Abstract base class representing general load balancer.
Describes the direct control where load or displacement (or both) are controlled. ...
virtual contextIOResultType saveContext(DataStream &stream, ContextMode mode)
Stores the state of model to output stream.
Initializes the variable VERBOSE, in order to get a few intermediate messages on screen: beginning an...
virtual void updateComponent(TimeStep *tStep, NumericalCmpn, Domain *d)
Updates components mapped to numerical method if necessary during solution process.
Class representing vector of real numbers.
int estimatePackSize(DataStream &buff)
Estimates the necessary pack size to hold all packed data of receiver.
#define _IFT_NonLinearStatic_refloadmode
virtual void updateDomainLinks()
Updates domain links after the domains of receiver have changed.
virtual void reinitialize()
virtual void computeExternalLoadReactionContribution(FloatArray &reactions, TimeStep *tStep, int di)
Computes the contribution external loading to reaction forces in given domain.
FloatArray incrementOfDisplacement
IRResultType
Type defining the return values of InputRecord reading operations.
virtual int givePackSizeOfDouble(int count)=0
std::unique_ptr< SparseMtrx > stiffnessMatrix
No special treatment for new iterations. Probably means ending up using for all free dofs...
int giveMetaStepNumber()
Returns receiver's meta step number.
#define _IFT_NonLinearStatic_controlmode
int giveNumberOfTimeStepWhenIcApply()
Returns the time step number, when initial conditions should apply.
InitialGuess initialGuessType
The initial guess type to use before starting the nonlinear solver.
NonLinearStatic(int i, EngngModel *_master=NULL)
virtual void reinitialize()
Reinitializes the receiver.
The representation of EngngModel default prescribed unknown numbering.
#define _IFT_NonLinearStatic_nonlocstiff
virtual contextIOResultType restoreContext(DataStream &stream, ContextMode mode)
Restores the state of model from output stream.
void zero()
Zeroes all coefficients of receiver.
This class implements linear static engineering problem.
Class implementing single timer, providing wall clock and user time capabilities. ...
void assemblePrescribedExtrapolatedForces(FloatArray &answer, TimeStep *tStep, CharType type, Domain *domain)
int giveRank() const
Returns domain rank in a group of collaborating processes (0..groupSize-1)
void initializeCommMaps(bool forceInit=false)
ClassFactory & classFactory
long ContextMode
Context mode (mask), defining the type of information written/read to/from context.
LoadBalancerMonitor * createLoadBalancerMonitor(const char *name, EngngModel *e)
LoadBalancer * lb
Load Balancer.
virtual ~NonLinearStatic()
virtual ErrorEstimator * giveDomainErrorEstimator(int n)
Service for accessing ErrorEstimator corresponding to particular domain.
OutputManager * giveOutputManager()
Returns domain output manager.
int giveVersion()
Returns receiver's version.
virtual TimeStep * giveSolutionStepWhenIcApply(bool force=false)
Returns the solution step when Initial Conditions (IC) apply.
virtual void assemble(SparseMtrx &answer, TimeStep *tStep, const MatrixAssembler &ma, const UnknownNumberingScheme &, Domain *domain)
Assembles characteristic matrix of required type into given sparse matrix.
virtual LoadBalancerMonitor * giveLoadBalancerMonitor()
Returns reference to receiver's load balancer monitor.
FloatArray internalForcesEBENorm
Norm of nodal internal forces evaluated on element by element basis (squared)
A generalized norm of displacement and loading vectors is controlled. In current implementation, the CALM solver is used, the reference load vector is FIXED.
The Communicator and corresponding buffers (represented by this class) are separated in order to allo...
std::vector< std::unique_ptr< Element > > & giveElements()
virtual void setDomain(Domain *d)
sets associated Domain
Abstract base class representing the "problem" under consideration.
virtual void setDomain(Domain *d)
virtual TimeStep * giveCurrentStep(bool force=false)
Returns current time step.
The secant stiffness is used and updated whenever requested.
virtual contextIOResultType restoreContext(DataStream &stream, ContextMode mode)
Restores the state of model from output stream.
virtual void updateAttributes(MetaStep *mStep)
Update receiver attributes according to step metaStep attributes.
the oofem namespace is to define a context or scope in which all oofem names are defined.
bool isNotEmpty() const
Returns true if receiver is not empty.
virtual void updateLoadVectors(TimeStep *tStep)
Domain * giveDomain(int n)
Service for accessing particular problem domain.
problemScale pScale
Multiscale mode.
FloatArray initialLoadVector
A load vector already applied, which does not scales.
Abstract class Dof represents Degree Of Freedom in finite element mesh.
DofManager * giveDofManager(int n)
Service for accessing particular domain dof manager.
void negated()
Switches the sign of every coefficient of receiver.
void doDofManOutput(FILE *, TimeStep *)
Does the dofmanager output.
double getUtime()
Returns total user time elapsed in seconds.
virtual TimeStep * giveSolutionStepWhenIcApply(bool force=false)
Returns the solution step when Initial Conditions (IC) apply.
void assembleVector(FloatArray &answer, TimeStep *tStep, const VectorAssembler &va, ValueModeType mode, const UnknownNumberingScheme &s, Domain *domain, FloatArray *eNorms=NULL)
Assembles characteristic vector of required type from dofManagers, element, and active boundary condi...
Class representing solution step.
DofManager is shared by neighboring partitions, it is necessary to sum contributions from all contrib...
void add(const FloatArray &src)
Adds array src to receiver.
Abstract base class representing general load balancer monitor.
virtual NM_Status solve(SparseMtrx &K, FloatArray &R, FloatArray *R0, FloatArray &X, FloatArray &dX, FloatArray &F, const FloatArray &internalForcesEBENorm, double &s, referenceLoadInputModeType rlm, int &nite, TimeStep *tStep)=0
Solves the given sparse linear system of equations .
virtual void unpackMigratingData(TimeStep *tStep)
Unpacks receiver data when rebalancing load.
#define _IFT_NonLinearStatic_donotfixload
void resize(int s)
Resizes receiver towards requested size.