Implementing Efficient Simulation of Inextensible Cloth

Please don't post Bullet support questions here, use the above forums instead.
Post Reply
mobeen
Posts: 122
Joined: Thu May 05, 2011 11:47 am

Implementing Efficient Simulation of Inextensible Cloth

Post by mobeen »

Dear all,
I am trying to implement the paper by Goldenthal et. al. (ESIC). I have already seen this existing thread where the author of this paper and Erin, Dirk and others shed some light on the implementation of this method as well as its similarities to Non-linear Gauss Seidel style methods. I have read the paper but still I believe I do not understand it completely. I hope those with experience with this paper's implementation can shed some light or direct me to relevant resources (like demo source codes etc.) that might help.

So far based on my understanding (from the SIG98 Baraff and Witkin's physics based modeling course notes, this tutorial series and this University of Minnesota course material). I have also setup a github repository for these experiments here for others to try this.

The following is how the constrained based Lagrangian dynamics is implemented. I will be solving all constraints at once as in the original paper using Eigen instead of Pardiso.

Code: Select all

void constrainedForwardEulerStep(ConstrainedSystem *system, double dt) {
    forwardEulerStep(system, dt);
    projectPositions(system);
    projectVelocities(system);
}
ProjectPositions is defined as follows

Code: Select all

void projectPositions(ConstrainedSystem *system) {
    int n = system->getDOFs(),	
        m = system->getConstraints();
    static VectorXd c(m);	system->getConstraintValues(c);	 
    static MatrixXd J(m,n);	system->getConstraintJacobian(J);
    static MatrixXd Mi(n, n);	system->getInverseInertia(Mi);
	
    MatrixXd A = J*Mi*J.transpose();
    VectorXd lambda = solve(A, -c); 
    static VectorXd dx(n);		
    dx = Mi*J.transpose()*lambda;
    
    static VectorXd x(n), v(n);		
    system->getState(x, v);

    system->setState(x + dx, v);
}
And ProjectVelocities is defined as follows

Code: Select all

void projectVelocities(ConstrainedSystem *system) {
    int n = system->getDOFs(), 
        m = system->getConstraints();
    static VectorXd x(n), v(n);
    system->getState(x, v);
    v = v * 0.995; //global dampening
    
    static MatrixXd J(m,n);
    system->getConstraintJacobian(J);
    
    static MatrixXd Mi(n,n);
    system->getInverseInertia(Mi);
    
    MatrixXd A = J*Mi*J.transpose();
    
    VectorXd b = -J*v;
    VectorXd lambda = solve(A, b);
    
    static VectorXd dv(n);
    dv = Mi*J.transpose()*lambda;
    
    system->setState(x, v + dv);
}
This is how its all defined in the course notes and it works fine. You can try the demos in the github repository.

Now I looked at the ESIC paper in particular their algorithm 1 on page 4. It seems that there will be three loops in it. The outer loop for the number of solver iterations, the middle inner loop for iterating over all constraints and the inner most for strain limiting as shown below. Kindly correct me if I am wrong anywhere? Note that this is not implemented yet put this is how it will be implemented if I have understood it clearly?

Code: Select all

 
void FastProjection(ParticleSystem* system, float dt) {
   //allocate memory for X0,Xt,Vt, dx, C, J, Mi;
  
   //get initial values
    system->getInverseInertia(Mi);
    system->getState(Xt,Vt);

   //outer solver iteration loop
   for(int j=0; j<MAX_ITERATIONS;++j ) {
      
      X0 = Xt+dt*Vt; //take initial unconstrained step
      system->setState(X0,Vt);

      for (int i=0; i<constraints.size(); ++i ) {
         const Constraint& c = constraints[i];


         float strain(0);
         do {
            //calculate strain
            Vector2d delta = X0[c.p1]-X0[c.p0];
 	    strain = delta.mag() / c.rest_length; 
                 
            //obtain lambda by solving linear system 
            system->getConstraintJacobian(J);
            system->getConstraintValues(C);
            Jt=J.transpose();
            
             MatrixXd A = J*Mi*Jt; //from eq. 7
             VectorXd b = C;
             VectorXd lambda = solve(A, b);

             static VectorXd dx(n); //from eq. 5
             dx = Mi*Jt*lambda;       
     
             X0 = X0 + dx;
 
             system->setState(X0,Vt);
        } while(strain > STRAIN_THRESHOLD);
   
      } //end for all constraints
   
  }//end for all solver iterations
   
   V = (X0-Xt)/dt;
   system->setState(X0,V);
} 
So this way, we are solving for each constraint one by one but not all constraints at the same time. We then find the amount to move (dx) and correcting its position, and then checking the value of strain to remain within the desired threshold. is this correct? Unless I am missing anything, I cant possibly think of a way to obtain strain at a point without iterating through the constraints?
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: Implementing Efficient Simulation of Inextensible Cloth

Post by Dirk Gregorius »

I am totally out of this, but I remember there is a bunch of additional information in the PhD. I cannot find a link right now, but I have a local copy if you PM me.
mobeen
Posts: 122
Joined: Thu May 05, 2011 11:47 am

Re: Implementing Efficient Simulation of Inextensible Cloth

Post by mobeen »

Hi Dirk,
Thanks for a prompt responses. IZIRC when I started opencloth you referred me to this very paper and his PhD thesis. Thanks to archives, is this the thesis you are referring to?
https://web.archive.org/web/20121027055 ... Thesis.pdf
Dirk Gregorius
Posts: 861
Joined: Sun Jul 03, 2005 4:06 pm
Location: Kirkland, WA

Re: Implementing Efficient Simulation of Inextensible Cloth

Post by Dirk Gregorius »

Yup, looks like it!
Post Reply