From a9a92d5eff648e42109e5b1991b1340db4250ec0 Mon Sep 17 00:00:00 2001
From: Van Dung Nguyen <vdg.nguyen@gmail.com>
Date: Tue, 7 Nov 2017 15:19:51 +0100
Subject: [PATCH] add step as input

---
 .../nlsolver/nonLinearMechSolver.cpp          | 72 +++++++++----------
 .../nlsolver/nonLinearMechSolver.h            | 20 +++---
 2 files changed, 46 insertions(+), 46 deletions(-)

diff --git a/NonLinearSolver/nlsolver/nonLinearMechSolver.cpp b/NonLinearSolver/nlsolver/nonLinearMechSolver.cpp
index 80cabc8e2..0939ee302 100644
--- a/NonLinearSolver/nlsolver/nonLinearMechSolver.cpp
+++ b/NonLinearSolver/nlsolver/nonLinearMechSolver.cpp
@@ -1052,10 +1052,10 @@ void nonLinearMechSolver::endOfScheme(unknownField *ufield,energeticField *efiel
  #endif // HAVE_MPI
 }
 
-void nonLinearMechSolver::oneStepPreSolve(const double curtime, const double timestep)
+void nonLinearMechSolver::oneStepPreSolve(const double curtime, const double timestep, const int numstep)
 {
   this->setTimeForBC(curtime);
-  this->setTimeForLaw(curtime,timestep);
+  this->setTimeForLaw(curtime,timestep,numstep);
   //for periodic BC
 
   if (_testFlag){
@@ -1066,7 +1066,7 @@ void nonLinearMechSolver::oneStepPreSolve(const double curtime, const double tim
 
 }
 
-void nonLinearMechSolver::oneStepPreSolvePathFollowing(const double curtime, const double timestep){
+void nonLinearMechSolver::oneStepPreSolvePathFollowing(const double curtime, const double timestep, const int numstep){
 	static std::string name = "A";
 	linearSystem<double>* lsys =pAssembler->getLinearSystem(name);
 	pathFollowingSystem<double>* pathsys = dynamic_cast<pathFollowingSystem<double>*>(lsys);
@@ -1112,7 +1112,7 @@ void nonLinearMechSolver::oneStepPreSolvePathFollowing(const double curtime, con
 
 	double loadParam = pathsys->getControlParameter();
 	double dloadParam = fabs(pathsys->getControlParameterStep());
-	this->oneStepPreSolve(loadParam,dloadParam);
+	this->oneStepPreSolve(loadParam,dloadParam, numstep);
 }
 
 
@@ -2008,7 +2008,7 @@ void nonLinearMechSolver::setTimeForBC(double time){
 
 }
 
-void nonLinearMechSolver::setTimeForLaw(const double t,const double dt)
+void nonLinearMechSolver::setTimeForLaw(const double t,const double dt, const int numstep)
 {
   for(std::map<int,materialLaw*>::iterator it=maplaw.begin(); it!=maplaw.end();++it)
   {
@@ -2825,7 +2825,7 @@ double nonLinearMechSolver::solveStaticLinear()
   int step = 1;
 
   /* solving */
-  this->setTimeForLaw(curtime,timestep);
+  this->setTimeForLaw(curtime,timestep,step);
   std::cout <<  "Neumann BC"<< std::endl;
   double tsystresol = Cpu();
   this->computeExternalForces(_ufield);
@@ -2859,7 +2859,7 @@ double nonLinearMechSolver::solveEigen()
    int step = 1;
 
    /* solving */
-   this->setTimeForLaw(curtime,timestep);
+   this->setTimeForLaw(curtime,timestep,step);
    printf("--begin assembling \n");
    double tsystresol = Cpu();
    if (_eigenSolverType == DYNAMIC)
@@ -5536,7 +5536,7 @@ double nonLinearMechSolver::oneExplicitStep(const double curtime)
 
   if(mytime>endtime) mytime = endtime;
 
-  this->oneStepPreSolve(mytime,timeStep);
+  this->oneStepPreSolve(mytime,timeStep,_currentStep+1);
 
   // solve via assembler to perform mpi operation (communication before and after systemSolve
   pAssembler->systemSolve();
@@ -5660,27 +5660,27 @@ double nonLinearMechSolver::computeLocalPathFollowingStep() const{
 
 };
 
-int nonLinearMechSolver::oneStaticStep(const double curtime,const double dt)
+int nonLinearMechSolver::oneStaticStep(const double curtime,const double dt, const int numstep)
 {
     int niteNR = 0;
     if (_pathFollowing){
-			this->oneStepPreSolvePathFollowing(curtime,dt);
-      niteNR = NewtonRaphsonPathFollowing(pAssembler,_ufield);
+			this->oneStepPreSolvePathFollowing(curtime,dt,numstep);
+      niteNR = NewtonRaphsonPathFollowing(pAssembler,_ufield,numstep);
     }
     else{
-      this->oneStepPreSolve(curtime,dt);
+      this->oneStepPreSolve(curtime,dt,numstep);
       // Solve one step by NR scheme
       double tsystresol = Cpu();
-      niteNR = NewtonRaphson(pAssembler,_ufield);
+      niteNR = NewtonRaphson(pAssembler,_ufield,numstep);
       tsystresol = Cpu() - tsystresol;
       Msg::Info("Time of Newton-Raphson resolution %f",tsystresol);
     }
     return niteNR;
 }
 
-double nonLinearMechSolver::finalizeStaticScheme(const double curtime, const int ii)
+double nonLinearMechSolver::finalizeStaticScheme(const double curtime, const int numstep)
 {
-  this->endOfScheme(_ufield,_energField,curtime,ii);
+  this->endOfScheme(_ufield,_energField,curtime,numstep);
   Msg::Info("NonLinearStatic OK");
   return curtime;
 }
@@ -6161,7 +6161,7 @@ void nonLinearMechSolver::computeStiffMatrix(dofManager<double> *pmanager){
 }
 
 // Newton Raphson scheme to solve one step
-int nonLinearMechSolver::NewtonRaphson(dofManager<double> *pmanager,unknownField *ufield){
+int nonLinearMechSolver::NewtonRaphson(dofManager<double> *pmanager,unknownField *ufield, const int numstep){
   staticDofManager<double>* staticAssembler = static_cast<staticDofManager<double>*>(pmanager);
   if (whatScheme == Implicit){
     staticAssembler->systemSolveIntReturn();
@@ -6587,7 +6587,7 @@ void nonLinearMechSolver::createSystem()
 	}
 }
 
-int nonLinearMechSolver::NewtonRaphsonPathFollowing(dofManager<double> *pmanager, unknownField *ufield){
+int nonLinearMechSolver::NewtonRaphsonPathFollowing(dofManager<double> *pmanager, unknownField *ufield, const int numstep){
    std::string name = "A";
   linearSystem<double>* lsys =pmanager->getLinearSystem(name);
   nonLinearSystem<double>* nonsys = dynamic_cast<nonLinearSystem<double>*>(lsys);
@@ -6631,7 +6631,7 @@ int nonLinearMechSolver::NewtonRaphsonPathFollowing(dofManager<double> *pmanager
 		// update load
 		double loadParam = pathsys->getControlParameter();
 		double dloadParam = fabs(pathsys->getControlParameterStep());
-		this->oneStepPreSolve(loadParam,dloadParam);
+		this->oneStepPreSolve(loadParam,dloadParam,numstep);
 
     if (!_iterativeNR) break;
     // new forces
@@ -6708,7 +6708,7 @@ double nonLinearMechSolver::solveSNL()
     }
     Msg::Info("t= %e on %e",curtime,dendtime);
 
-    int niteNR  = this->oneStaticStep(curtime,dt);
+    int niteNR  = this->oneStaticStep(curtime,dt,ii+1);
 
     if(niteNR == _maxNRite) // time step reduction
     {
@@ -6864,7 +6864,7 @@ double nonLinearMechSolver::solveMulti()
     curtime+=dt;
     if(curtime > dendtime){curtime = dendtime;}
 
-    this->oneStepPreSolve(curtime,dt);
+    this->oneStepPreSolve(curtime,dt,step+1);
     // Solve one step by NR scheme
     int niteNR=0;
     if(step%_numstepImpl==0 or !oneExplicitScheme)
@@ -6872,7 +6872,7 @@ double nonLinearMechSolver::solveMulti()
       Msg::Info("Solve implicit system(s)");
       double tsystresol = Cpu();
       tsystresol = Cpu() - tsystresol;
-      niteNR = NewtonRaphson(pAssembler,_ufield);
+      niteNR = NewtonRaphson(pAssembler,_ufield,step+1);
       Msg::Info("Time of Newton-Raphson resolution n %f: ",tsystresol);
 
       if(niteNR == _maxNRite) // time step reduction
@@ -9022,7 +9022,7 @@ void nonLinearMechSolver::extractAveragePropertiesPerturbation(homogenizedData*
 				_microBC->setFirstOrderKinematicalVariable(Fplus);
 
 				/** solve perturbated system**/
-				this->OneStep();
+				this->OneStep(0);
 
 				/** get homogenized stress in perturbed system **/
 				this->extractAverageStress(&homoDataPlus);
@@ -9105,7 +9105,7 @@ void nonLinearMechSolver::extractAveragePropertiesPerturbation(homogenizedData*
 
 						_microBC->setSecondOrderKinematicalVariable(Gplus);
 						/** solve perturbed system**/
-						this->OneStep();
+						this->OneStep(0);
 
 						/** get homogenized stress in perturbed system **/
 						this->extractAverageStress(&homoDataPlus);
@@ -9192,7 +9192,7 @@ void nonLinearMechSolver::extractAveragePropertiesPerturbation(homogenizedData*
 				gradTplus(i) += gradTpert;
 				_microBC->setConstitutiveExtraDofDiffusionKinematicalVariable(index,gradTplus);
 				/** solve perturbed system**/
-				this->OneStep();
+				this->OneStep(0);
 
 				/** get homogenized stress in perturbed system **/
 				this->extractAverageStress(&homoDataPlus);
@@ -9261,7 +9261,7 @@ void nonLinearMechSolver::extractAveragePropertiesPerturbation(homogenizedData*
 
 			_microBC->setConstitutiveExtraDofDiffusionConstantVariable(index,Tplus);
 			/** solve perturbed system**/
-			this->OneStep();
+			this->OneStep(0);
 
 			/** get homogenized stress in perturbed system **/
 			this->extractAverageStress(&homoDataPlus);
@@ -9332,7 +9332,7 @@ void nonLinearMechSolver::extractAveragePropertiesPerturbation(homogenizedData*
 				gradVplus(i) += gradVpert;
 				_microBC->setNonConstitutiveExtraDofDiffusionKinematicalVariable(index,gradVplus);
 				/** solve perturbed system**/
-				this->OneStep();
+				this->OneStep(0);
 
 				/** get homogenized stress in perturbed system **/
 				this->extractAverageStress(&homoDataPlus);
@@ -10717,21 +10717,21 @@ double nonLinearMechSolver::microSolve(){
   return time;
 };
 
-void nonLinearMechSolver::OneStep(){
+void nonLinearMechSolver::OneStep(const int numstep){
   int niteNR = 0;
   if (_pathFollowing){
     niteNR = pathFollowingPerturbation(pAssembler,_ufield);
   }
   else{
     if (_systemType == MULT_ELIM)
-      niteNR = microNewtonRaphson(pAssembler,_ufield);
+      niteNR = microNewtonRaphson(pAssembler,_ufield,numstep);
     else {
       if (_systemType == DISP_ELIM)
         _pAl->applyPBCByConstraintElimination();
        else if (_systemType == DISP_ELIM_UNIFIED){
          _pAl->updateSystemUnknown();
        }
-      niteNR = NewtonRaphson(pAssembler,_ufield);
+      niteNR = NewtonRaphson(pAssembler,_ufield,numstep);
     }
     if(niteNR == _maxNRite) // time step reduction
     {
@@ -10790,7 +10790,7 @@ double nonLinearMechSolver::solveMicroSolverSNL(){
     if (_pathFollowing){
       pathSys->setPseudoTimeIncrement(dt);
       _pAl->updateConstraint(_ipf);
-      niteNR = microNewtonRaphsonPathFollowing(pAssembler,_ufield);
+      niteNR = microNewtonRaphsonPathFollowing(pAssembler,_ufield,ii+1);
 
       double control = pathSys->getControlParameter();
       if (_outputFile)
@@ -10815,10 +10815,10 @@ double nonLinearMechSolver::solveMicroSolverSNL(){
       }
     }
     else{
-			this->oneStepPreSolve(curtime,dt);
+			this->oneStepPreSolve(curtime,dt,ii+1);
       _pAl->updateConstraint(_ipf);
       if (_systemType == MULT_ELIM)
-        niteNR = microNewtonRaphson(pAssembler,_ufield);
+        niteNR = microNewtonRaphson(pAssembler,_ufield,ii+1);
       else {
         if (_systemType == DISP_ELIM){
           _pAl->applyPBCByConstraintElimination();
@@ -10827,7 +10827,7 @@ double nonLinearMechSolver::solveMicroSolverSNL(){
           _pAl->updateSystemUnknown();
         }
 
-        niteNR = NewtonRaphson(pAssembler,_ufield);
+        niteNR = NewtonRaphson(pAssembler,_ufield,ii+1);
       }
     }
 
@@ -11009,7 +11009,7 @@ double nonLinearMechSolver::solveMicroSolverStaticLinear(){
   int step = 1;
   /* solving */
   this->setTimeForBC(curtime);
-  this->setTimeForLaw(curtime,timestep);
+  this->setTimeForLaw(curtime,timestep,step);
 
   if (_systemType == DISP_ELIM)
     _pAl->applyPBCByConstraintElimination();
@@ -11176,7 +11176,7 @@ int nonLinearMechSolver::pathFollowingPerturbation(dofManager<double> *pmanager,
   return iter;
 };
 
-int nonLinearMechSolver::microNewtonRaphson(dofManager<double> *pmanager,unknownField *ufield){
+int nonLinearMechSolver::microNewtonRaphson(dofManager<double> *pmanager,unknownField *ufield, const int numstep){
   std::string name = "A";
   linearSystem<double>* lsys = pmanager->getLinearSystem(name);
   pbcSystem<double> * pbcSys = dynamic_cast<pbcSystem<double>*>(lsys);
@@ -11236,7 +11236,7 @@ int nonLinearMechSolver::microNewtonRaphson(dofManager<double> *pmanager,unknown
   return iter;
 }
 
-int nonLinearMechSolver::microNewtonRaphsonPathFollowing(dofManager<double> *pmanager,unknownField *ufield){
+int nonLinearMechSolver::microNewtonRaphsonPathFollowing(dofManager<double> *pmanager,unknownField *ufield, const int numstep){
   std::string name = "A";
   linearSystem<double>* lsys =pmanager->getLinearSystem(name);
   nonLinearSystem<double>* nonsys = dynamic_cast<nonLinearSystem<double>*>(lsys);
diff --git a/NonLinearSolver/nlsolver/nonLinearMechSolver.h b/NonLinearSolver/nlsolver/nonLinearMechSolver.h
index 5ff81fb39..88b62820e 100644
--- a/NonLinearSolver/nlsolver/nonLinearMechSolver.h
+++ b/NonLinearSolver/nlsolver/nonLinearMechSolver.h
@@ -362,8 +362,8 @@ class nonLinearMechSolver
 	void initAllBCsOnDofs();
   void initTerms(unknownField *ufield, IPField *ipf);
   void endOfScheme(unknownField *ufield,energeticField *efield,const double endtime, const int endstep); // common operation at the end of a scheme
-  void oneStepPreSolve(const double curtime, const double timestep);
-	void oneStepPreSolvePathFollowing(const double curtime, const double timestep);
+  void oneStepPreSolve(const double curtime, const double timestep, const int numstep);
+	void oneStepPreSolvePathFollowing(const double curtime, const double timestep, const int numstep);
   void computeIPCompOnDomain(const double time);
   void computeIPCompDamageZoneAveraging(const double time);
   void fillMapOfInterfaceElementsInOneDomain(MElement *e, std::vector<MElement*> &eleFound,
@@ -375,12 +375,12 @@ class nonLinearMechSolver
   void setPairSpaceElementForBoundaryConditions(); // new implementation
 
   // Function used by non linear solver (return the number of iteration to converge)
-  int NewtonRaphson(dofManager<double> *pmanager, unknownField *ufield);
+  int NewtonRaphson(dofManager<double> *pmanager, unknownField *ufield, const int numstep);
 
   /*
   NewtonRaphson function for arc-length path following
   */
-  int NewtonRaphsonPathFollowing(dofManager<double> *pmanager, unknownField *ufield);
+  int NewtonRaphsonPathFollowing(dofManager<double> *pmanager, unknownField *ufield, const int numstep);
 
 	bool localPathFollowingSwitching() const;
 	double computeLocalPathFollowingStep() const;
@@ -407,7 +407,7 @@ class nonLinearMechSolver
   double criticalExplicitTimeStep(unknownField *ufield);
   void setInitialCondition();
   void setTimeForBC(double time);
-  void setTimeForLaw(const double t,const double dt);
+  void setTimeForLaw(const double t,const double dt, const int numstep);
   void initArchiveForce();
   void endArchiveForce();
   void forceArchiving(const double curtime,const int numstep,const dofManager<double>* pAssembler);
@@ -665,8 +665,8 @@ class nonLinearMechSolver
   virtual double finalizeExplicitScheme(const double curtime);
   // Implicit scheme control
   virtual void initializeStaticScheme();
-  virtual int oneStaticStep(const double curtime, const double dt);
-  virtual double finalizeStaticScheme(const double curtime,const int curstep);
+  virtual int oneStaticStep(const double curtime, const double dt, const int numstep);
+  virtual double finalizeStaticScheme(const double curtime,const int numstep);
 
   // Display control
   virtual void createOnelabDisplacementView(const std::string &fname,const double time) const;
@@ -843,8 +843,8 @@ class nonLinearMechSolver
   double critialPointTestFunction(double time, double* &mode);
   void modeViewToFile(std::vector<int>& num, double time, int step);
   // newton raphson
-  int microNewtonRaphson(dofManager<double> *pAssembler,unknownField *ufield);
-  int microNewtonRaphsonPathFollowing(dofManager<double> *pAssembler,unknownField *ufield);
+  int microNewtonRaphson(dofManager<double> *pAssembler,unknownField *ufield,const int numstep);
+  int microNewtonRaphsonPathFollowing(dofManager<double> *pAssembler,unknownField *ufield, const int numstep);
 
   int pathFollowingPerturbation(dofManager<double> *pAssembler,unknownField *ufield);
 
@@ -856,7 +856,7 @@ class nonLinearMechSolver
   double solveMicroSolverStaticLinear();
   double solveMicroSolverForwardEuler();
 
-  void OneStep();
+  void OneStep(const int numstep);
 
   void writeDisturbedMeshByEigenVector(int step);
   void writeDeformedMesh(int step);
-- 
GitLab