-
Notifications
You must be signed in to change notification settings - Fork 37
Lesson 9: Robot Velocity Kinematics Using Screw Theory ‐ Jacobian Matrix
Up to now, we have understood how to find the tool orientation and position (pose) of the open chain robots from joint positions that we call forward kinematics. In this lesson, we are going to learn how to compute the twist (angular and linear velocities) of the end-effector of an open chain, given joint velocities. But before diving into mathematical details, why do we need the Jacobian matrix to relate the end-effector velocities to the joint velocities? What are the possible applications of understanding the end-effector twist given the joint velocities?
There are numerous applications in robotics where we want to control the velocity of the end-effector. Common applications are in industrial robotic arms used for manufacturing processes. For example, in the automotive industry, precise velocity control of robotic arms is crucial in tasks such as painting. Controlling the end-effector's velocity is essential to ensure a smooth and even application of paint, thereby guaranteeing a high-quality finish on vehicles. This means that in order to get a smooth finish, the robot arms cannot move too fast.
Note: The above figures are created by DALL·E 3.
What other applications can you think of?
Let's first start with a quick example to provide an intuitive insight into the given problem.
Consider a two-do planar open-chain robot arm modeled using STEM building blocks.
Let's first find the forward kinematics of this simple planar robot using screw theory. It should be a piece of cake for you now, if not, review the forward kinematics lesson. The vector of joint angles can be written as:
The screw axes of the joints can be written as (note that screw axes are written in the robot's zero pose):
And the pose of the end-effector w.r.t the base frame in the robot's zero position is:
Therefore, the forward kinematics of this robot relating the joint positions to the end-effector pose can be found as the following matrix:
Therefore, the position of the end-effector frame w.r.t the base frame can be written as:
Taking the time derivative of these equations yields:
In robotics, we prefer to represent all our equations in matrix form; therefore, re-writing this in matrix form, we get:
The term
jacobian.matrix.maps.the.joint.velocities.to.the.end-effector.velocities.mp4
In the simulation above, you see how changing joint velocities that are bound to a unit circle are mapped to the end-effector velocity vector that is bound to an ellipsoid. This ellipsoid is called the manipulability ellipsoid, and it shows what instantaneous velocity the end-effector can achieve if you keep the joint velocities inside that unit circle.
Important note: Here, we found the Jacobian that relates the linear velocity of the end-effector frame in the space frame to the joint velocities.
Let's now study the columns of the Jacobian matrix. Let's re-write the above equation in terms of the linear velocity of the tool and joint velocities as follows:
This velocity vector is shown in the following figure:
Note that
and
If we draw
Now, suppose we want to determine which joint velocities are required to generate desired tip velocities. For example, for the configuration shown in the video below, you see that by changing the tip velocity, the required joint velocities to generate that desired tip velocity are changing (note the joint velocity arrows that are changing). You also see that in this configuration, the end-effector can only generate velocities in the directions bound by the manipulability ellipsoid:
joint.vels.for.desired.tip.velocity.mp4
If the configuration changes, so does the Jacobian matrix and the manipulability ellipsoid. Also, note in the video below that in certain configurations that we call them singularities, the manipulator's manipulability ellipsoid becomes tall and thin until, at the singular configuration, it becomes a straight line. In these singular configurations, the manipulator loses its degree of freedom and can only move on a straight line:
jacobian.changes.with.config.and.singularities.mp4
Mathematically, and according to the laws of linear algebra, it is possible to determine which joint velocities
In case the Jacobian matrix columns are linearly dependent, the associated configuration is called singular or represents a singularity. This means that in certain configurations, it is difficult or impossible to control the end-effector in a certain direction. The achievable velocity space dimension in a singularity is less than full rank.
As we saw from the above equations and from the simulations
If the matrix J is singular, it means that its determinant is zero (this way it cannot be inverted):
Therefore, for
As the figure above shows, you can only generate end-effector velocity along this line. In the simulation below, you see that at the singular configurations
singular.configs.2.dof.planar.robot.mp4
After this intuitive example of the concept of velocity kinematics, Jacobian matrix, manipulability ellipsoid, and singularities, let's see how we can calculate space and body Jacobians using screw theory.
Jacobian matrix can have different forms and interpretations, but there are two standard types of Jacobians: the space Jacobian
Space Jacobian
Considering the forward kinematics of an n-link open chain, which can be represented as a product of exponential terms, as follows:
As we have seen before in previous lessons, the spatial twist can be represented by the following product:
Also, the transformation inverse can be computed as follows:
Substituting (2) and (3) in (1), yields:
We can simplify the expression using the adjoint representation, remember that:
This is a sum of n spatial twists, which can be represented in the following form:
The matrix
In summary, in order to find the space Jacobian, we should follow these steps:
- Find the screw axes of the joints when the robot is in zero position
- Find the adjoint map of those screw axes for when the robot is no longer in zero position
- Find the columns of the Jacobian
$J_{s1}$ ,$J_{s2}$ , ... using this formulae:
- Construct the Jacobian matrix using its columns. The Jacobian will be a
$6 \times n$ matrix, where n is the number of joints.
Note: Each column of the space Jacobian represents the spatial twist resulting from the movement of an individual joint, with all other joint speeds set to zero except for the joint in consideration, which has a speed of one. For example,
Note: Note that the movement of joint i is only affected by the movement of joints i-1,i-2,...,1 and not the joints i and after the i, and that's why for the Jacobian matrix column associated with that joint, we only take into consideration the adjoint map of the screw motions of the joints until joint i. For example, the movement of joint three is only affected by the movement of joints 1 and 2 (See the illustration below).
In summary:
The space Jacobian
We can define the Jacobian by its columns as:
Where
The initial column of the space Jacobian corresponds to the screw axis
In summary, for the space Jacobian, we take the joint screw axes
Class Activity
Write a MATLAB code and calculate the twist of the end-effector for the 2-dof planar robot arm at the start of this lesson using both the step-by-step method for the space Jacobian (outlined above) and using the equation:
Show that they are the same.
Question 1: Why is this Jacobian different than the Coordinate Jacobian that we calculated at the start of this lecture? Using the concepts that we learned in this lesson and the velocities in the robotics lesson, write a Matlab code that can convert the linear part of the spatial twist to the velocity of the end-effector frame in the space frame.
Question 2: Does the 2R robot arm have singularities when considering the “output” to be the full 6-dof twist (as opposed to just the 2-dof linear velocity (
Body Jacobian
For body Jacobian, the screw axes are defined in the body frame. Body Jacobian can be expressed as the following equations:
The body Jacobian transforms joint velocities into the body twist. Since we did not go into details about how to find the screw axes in the body frame back in the forward kinematics lesson (which in my mind was not necessary), to find the body Jacobian, we only learn the mapping that can take the space Jacobian to the body Jacobian. The adjoint transformation can be used to map the space Jacobian to the body Jacobian:
Therefore,
We saw that the Jacobian matrix can relate the joint velocities to the end-effector twist (spatial twist or body twist):
The Jacobian is a
-
We know from linear algebra that the Jacobian matrix is called full rank at a configuration q if the rank is equal to the minimum of 6 and n:
$\text{J is full rank if rank }J(q) = min(6,n)$ . -
The Jacobian is singular at a configuration
$q^{*}$ if the rank of the Jacobian at$q^{*}$ is less than the maximum rank the Jacobian can achieve at some configuration:$\text{singular at } q^{*} \text{ if rank }J(q^{*}) < \text{max rank }J(q) \text{(at some q)}$
As we saw before, in a singular configuration, the robot loses the ability to move in one or more directions.
-
Kinematically Dificient Arms: If the number of joints of the arms n is less than 6, then the
$6 \times n$ Jacobian matrix will have more rows than columns, and it is "tall." In this case, the set of reachable configurations for the end-effector is less than 6-dimensional, so we call such robots kinematically deficient. Our Pincherx 100 robot arm has 4 joints so it is in this category. Being kinematically deficient is not a bad thing; it just means that the robot is not capable of general motion at the end-effector. -
General-purpose manipulators: If the number of robot joints is 6, then the Jacobian matrix is
$6 \times 6$ , and these robots are capable of general 6-dimensional rigid-body motion at their end-effectors, and that's why they are called general-purpose manipulators. The Kinova's 6R robot arm that you saw in the last homework is a general-purpose manipulator. -
Redundant manipulators: If the robot has more joints than 6, then the Jacobian matrix has more columns than rows, and it is "fat." These types of robots are called redundant since they can achieve the same end-effector twist with different joint velocities. Can you show redundancy in your own arm?
- Kevin, M.L. and Frank, C.P., 2017. Modern robotics: mechanics, planning, and control
- Murray, R.M., Li, Z. and Sastry, S.S., 2017. A mathematical introduction to robotic manipulation. CRC press.
- Corke, P., 2023. Robotics, Vision and Control: Fundamental Algorithms in Python (Vol. 146). Springer Nature
- https://www.wolfram.com/mathematica/