5.4. Manipulability

This video describes the visualization of a robot’s ease of moving in different directions in terms of a manipulability ellipsoid, as well as scalar measures of the manipulability. Analogous ideas are presented describing the robot’s ability to apply wrenches as its end-effector.

A robot configuration is either singular or it’s not. But even if a configuration is nonsingular, it still may be close to being singular. The manipulability ellipsoid we saw in the first video of this chapter is one way to visualize how close a robot is to being singular.

For this 2_R robot, a circle of velocities in the joint space maps through the Jacobian to an ellipse of velocities at the tip of the robot depending on the robot's configuration. As the second joint angle approaches zero, the ellipse squashes in the direction it is difficult to move and stretches in the orthogonal direction, until, at the singularity, the ellipse collapses to a line segment. As we will see shortly, we can assign a measure of just how close the robot is to being singular according to how close the ellipse is to collapsing.

To derive a general expression for the end-effector velocity ellipsoid, let's begin by assuming the end-effector's velocity is represented as the m-dimensional vector v_tip. The robot has n joints, so the Jacobian is an m by n matrix. A sphere of joint velocities, like the circle shown here, is defined by the equation theta-dot transpose times theta-dot equals 1. If we assume the Jacobian is invertible, which is not strictly necessary, then we can rewrite the equation as shown here. Rearranging, we get this, and rearranging once more, we get this. We summarize this equation as v_tip-transpose times A-inverse times v_tip equals 1, where A is the m-by-m matrix J times J-transpose. The A matrix is both symmetric and positive definite, and so is its inverse.

Now assume we take this same equation but replace v_tip by a generic vector x. The eigenvalues of the matrix A are called lambda_1 to lambda_m, and the corresponding eigenvectors are v_1 to v_m. It is well known that the quadratic equation x-transpose times A-inverse times x equals 1 defines an ellipsoid of x values that satisfy the equation. In general, this ellipsoid is an m-minus-1-dimensional surface in the m-dimensional space of x, but this figure shows the case where x is a 3-vector. The principal axes of the ellipsoid are aligned with the eigenvectors of A and the half-lengths of the ellipsoid along the principal axes are the square roots of the eigenvalues. This geometric interpretation holds for any symmetric positive definite matrix A, but if we choose A equal to J times J-transpose, then the x-vector can be interpreted as v_tip, and the ellipsoid is called the manipulability ellipsoid resulting from the unit sphere of joint velocities. If instead we set A equal to the inverse of J times J-transpose, then the x-vector can be interpreted as the end-effector forces f_tip, and the ellipsoid is called the force ellipsoid resulting from a unit sphere of joint forces and torques.

This figure shows the manipulability ellipsoid and the force ellipsoid for a 2R robot at a particular configuration. Since the matrix defining the manipulability ellipsoid is just the inverse of the matrix defining the force ellipsoid, the two ellipsoids have the same principal axes, and the lengths of the principal semi-axes are just the reciprocals of each other. In other words, only small forces can be applied in directions where large velocities can be attained, and only small velocities are possible in directions where large forces can be applied.

Now that we can visualize the end-effector motion capabilities as a manipulability ellipsoid, we can assign a single number representing how close the robot is to being singular. These numbers are called manipulability measures. The first manipulability measure is the ratio of the longest axis to the shortest axis of the ellipsoid. This measure is lower-bounded by 1, and if it is equal to 1, we say that the manipulability ellipsoid is isotropic; it is equally easy to move in any direction. On the other hand, as the robot approaches a singularity, this number grows large.

The second measure is just the square of the first measure, often called the condition number of the matrix A.

A final measure is the square root of the product of the eigenvalues of A, which is proportional to the volume of the manipulability ellipsoid. If the manipulability ellipsoid volume becomes large, then the force ellipsoid volume becomes small, and vice-versa.

Finally, consider the case that the Jacobian corresponds to the body Jacobian derived in this chapter. The 6-by-n body Jacobian can be split into the 3-by-n angular velocity Jacobian J-b-omega and the 3-by-n linear velocity Jacobian J-b-v. This separation into linear and angular components is useful, because the units of the angular velocity and linear velocity are different. Then for any configuration of the robot, J_b-omega can be used to create angular velocity manipulability ellipsoids and angular moment ellipsoids and J_bv can be used to create linear velocity manipulability ellipsoids and linear force ellipsoids.

So, this concludes Chapter 5. You should now have a solid understanding of how to derive and interpret the Jacobian, a fundamental object in robotics that is heavily used in many robot motion planners and controllers. In Chapter 6, we study another key issue in robot motion planning and control: inverse kinematics, or, how to find joint positions that achieve a desired end-effector configuration.