Calculating Jacobian matrixes for a 6 axis Robot Arm

What are Jacobian matrixes (good for)?

I want to know how fast the Sixi robot has to move each joint (how much work in each muscle) to move the end effector (finger tip) at my desired velocity (direction * speed). For any given pose, the Jacobian matrix describes the relationship between the joint velocities and the end effector velocity. The inverse jacobian matrix does the reverse, and that’s what I want.

The Jacobian matrix could be a matrix of equations, solved for any pose of the robot. That is a phenomenal amount of math and, frankly, I’m not that smart. I’m going to use a method to calculate the instantaneous approximate Jacobian at any given robot pose, and then recalculate it as often as I need. It may be off in the 5th or 6th decimal place, but it’s still good enough for my needs.

Special thanks to Queensland University of Technology. Their online explanation taught me this method. I strongly recommend you watch their series, which will help this post (a kind of cheat sheet) make more sense.

What tools do I have to find the Jacobian matrix?

  • I have the D-H parameters for my robot;
  • I have my Forward Kinematics (FK) calculations; and
  • I have my Inverse Kinematics (IK) calculations.

I have a convenience method that takes 6 joint angles and the robot description and returns the matrix of the end effector.

/**
 * @param jointAngles 6 joint angles
 * @param robot the D-H description and the FK/IK solver
 * @return the matrix of the end effector
 */
private Matrix4d computeMatrix(double [] jointAngles,Sixi2 robot) {
     robot.setRobotPose(jointAngles);  // recursively calculates all the matrixes down to the finger tip.
     return new Matrix4d(robot.getLiveMatrix());
}

The method for approximating the Jacobian

Essentially I’m writing a method that returns the 6×6 Jacobian matrix for a given robot pose.

/**
 * Use Forward Kinematics to approximate the Jacobian matrix for Sixi.
 * See also https://robotacademy.net.au/masterclass/velocity-kinematics-in-3d/?lesson=346
 */ 
public double [][] approximateJacobian(Sixi robot,double [] jointAnglesA) { 
     double [][] jacobian = new double[6][6]; 
     //....
     return jacobian;
}

The keyframe is a description of the current joint angles, and the robot contains the D-H parameters and the FK/IK calculators.

Each column of the Jacobian has 6 parameters: 0-2 describe the translation of the hand and 3-5 describe the rotation of the hand. Each column describes the change for a single joint: the first column is the change in the end effector isolated to only a movement in J0.

So I have my current robot pose T and one at a time I will change each joint a very small change (0.5 degrees) and calculate the new pose Tnew. (Tnew-T)/change gives me a matrix dT showing the amount of change. The translation component of the Jacobian can be directly extracted from here.

     double ANGLE_STEP_SIZE_DEGREES=0.5;  // degrees
     double [] jointAnglesB = new double[6]; 

     // use anglesA to get the hand matrix 
     Matrix4d T = computeMatrix(jointAnglesA,robot);

     int i,j;
     for(i=0;i<6;++i) {  // for each axis
         for(j=0;j<6;++j) {
             jointAnglesB[j]=jointAnglesA[j];
         }
         // use anglesB to get the hand matrix after a tiiiiny adjustment on one axis. 
         jointAnglesB[i] += ANGLE_STEP_SIZE_DEGREES; 
         Matrix4d Tnew = computeMatrix(jointAnglesB,robot);

         // use the finite difference in the two matrixes
         // aka the approximate the rate of change (aka the integral, aka the velocity) 
         // in one column of the jacobian matrix at this position.
         Matrix4d dT = new Matrix4d();
         dT.sub(Tnew,T);
         dT.mul(1.0/Math.toRadians(ANGLE_STEP_SIZE_DEGREES));
         jacobian[i][0]=dT.m03;
         jacobian[i][1]=dT.m13;
         jacobian[i][2]=dT.m23;

We’re halfway there! Now the rotation part is more complex. We need to look at just the rotation part of each matrix.

        Matrix3d T3 = new Matrix3d(
                 T.m00,T.m01,T.m02,
                 T.m10,T.m11,T.m12,
                 T.m20,T.m21,T.m22);
        Matrix3d dT3 = new Matrix3d(
                 dT.m00,dT.m01,dT.m02,
                 dT.m10,dT.m11,dT.m12,
                 dT.m20,dT.m21,dT.m22);
        T3.transpose();  // inverse of a rotation matrix is its transpose
        Matrix3d skewSymmetric = new Matrix3d();
        skewSymmetric.mul(dT3,T3);
        //[  0 -Wz  Wy]
         //[ Wz   0 -Wx]
         //[-Wy  Wx   0]
         jacobian[i][3]=skewSymmetric.m12;  // Wx
         jacobian[i][4]=skewSymmetric.m20;  // Wy
         jacobian[i][5]=skewSymmetric.m01;  // Wz
    }
    return jacobian;
}

Testing the Jacobian (finding Joint Velocity over Time)

So remember the whole point is to be able to say “I want to move the end effector with Force F, how fast do the joints move?” I could apply this iteratively over some period of time and watch how the end effector moves.

public void angularVelocityOverTime() {
    System.out.println("angularVelocityOverTime()");
    Sixi2 robot = new Sixi2();

    BufferedWriter out=null;
    try {
        out = new BufferedWriter(new FileWriter(new File("c:/Users/Admin/Desktop/avot.csv")));
        out.write("Px\tPy\tPz\tJ0\tJ1\tJ2\tJ3\tJ4\tJ5\n");
        
        DHKeyframe keyframe = (DHKeyframe)robot.createKeyframe();
        DHIKSolver solver = robot.getSolverIK();
        double [] force = {0,3,0,0,0,0};  // force along +Y direction

        // move the hand to some position...
        Matrix4d m = robot.getLiveMatrix();
        m.m13=-20;
        m.m23-=5;
        // get the hand position
        solver.solve(robot, m, keyframe);
        robot.setRobotPose(keyframe);
        
        float TIME_STEP=0.030f;
        float t;
        int j, safety=0;
        // until hand moves far enough along Y or something has gone wrong
        while(m.m13<20 && safety<10000) {
            safety++;
            m = robot.getLiveMatrix();
            solver.solve(robot, m, keyframe);  // get angles
            // if this pose is in range and does not pass exactly through a singularity
            if(solver.solutionFlag == DHIKSolver.ONE_SOLUTION) {
                double [][] jacobian = approximateJacobian(robot,keyframe);
                // Java does not come by default with a 6x6 matrix class.
                double [][] inverseJacobian = MatrixHelper.invert(jacobian);
                
                out.write(m.m03+"\t"+m.m13+"\t"+m.m23+"\t");  // position now
                double [] jvot = new double[6];
                for(j=0;j<6;++j) {
                    for(int k=0;k<6;++k) {
                        jvot[j]+=inverseJacobian[k][j]*force[k];
                    }
                    // each jvot is now a force in radians/s
                    out.write(Math.toDegrees(jvot[j])+"\t");
                    // rotate each joint aka P+= V*T
                    keyframe.fkValues[j] += Math.toDegrees(jvot[j])*TIME_STEP;
                }
                out.write("\n");
                robot.setRobotPose(keyframe);
            } else {
                // Maybe we're exactly in a singularity.  Cheat a little.
                m.m03+=force[0]*TIME_STEP;
                m.m13+=force[1]*TIME_STEP;
                m.m23+=force[2]*TIME_STEP;
            }
        }
        
    }
    catch(Exception e) {
        e.printStackTrace();
    }
    finally {
        try {
            if(out!=null) out.flush();
            if(out!=null) out.close();
        } catch (IOException e1) {
            e1.printStackTrace();
        }
    }
}

Viewing the results

The output of this method is conveniently formatted to work with common spreadsheet programs, and then graphed.

Position and Joint velocity over Time

I assume the small drift in Z is due to numerical error over many iterations.

Now what?

Since velocity is a function of acceleration (v=a*t) and acceleration is a force I should be able to teach the arm all about forces:

  • Please push this way (squeeze my lemon)
  • Please stop if you meet a big opposite force. (aka compliant robotics aka safe working around humans)
  • You are being pushed. Please move that way. (push to teach)
  • Are any of the joints turning too fast? Warn me, please.

Final thoughts

All the code in this post is in the open source Robot Overlord app on Github. The graph above is saved to the Sixi 2 Github repository.

Please let me know this tutorial helps. I really appreciate the motivation! If you want to support my work, there’s always my Patreon or the many fine robots on this site. If you have follow up questions or want me to explain more parts, contact me.