In this lecture we will look at the relationship between velocities at joints and velocities of points attached to the robot.
Trajectories
Assume the configuration space is parameterized by some vector q. For example, for a planar rigid body, we might have
, and for a 3R planar arm we might have
.
At each instant in time,
, the system has some configuration
. For the planar rigid body, we have
. The configuration is thus a vector-valued function of time. The trajectory describes a curve in the configuration space, and we say that the curve is parameterized by time. We can start the clock whenever we like, so often we will consider a trajectory with time in some interval,
, such that the start time of the trajectory is zero and the end time is T.
We typically expect the trajectory to be a continuous function of time, except for "rollovers" of angles from
to
or vice versa. (In fact, the trajectories are continuous even at these points, if we view them correctly in the configuration space. Remember, for example, that the topology of the configuration space for a 2R arm is a torus.)
The tangent space
A formal mathematical framework allows us to leverage existing techniques and theorems from the mathematics community to solve robotics problems. We will use some terminology from differential geometry.
First, there is the idea of a tangent to a parameterized curve at at point t:
(1)
where x is the vector of coordinates describing a configuration. The tangent has a physical interpretation: it describes the velocity of the elements of the system.
There are problems with how you define the tangent to the trajectory at the boundary between
and
angles, but these problems disappear if we remember that the system is defined as a collection of particles, and the configuration gives the location of every particle. Each particle, if following a smooth trajectory, has a well-defined tangent vector, even if our parameterization of the configuration space has some inconvenient sharp edges.
Since every trajectory is embedded in the configuration space surface, the constraints on the motion of the system constrain the possible tangents to a trajectory at a point. We define the
tangent space: The tangent space at a point on a surface is set of all possible tangents through that point. We denote the tangent space at a point x with the notation
.
It is important to remember that the tangent space is defined at points in the configuration space; i.e., for a single configuration space, there are many tangent spaces — one tangent space corresponding to each point in the configuration space. There is a term for the collection of tangent spaces for a surface; this is called the tangent bundle. Wikipedia has some nice pictures of tangent bundles for one-dimensional surfaces.
The Jacobian
Let's look at an example, a 2R planar arm. We have
(2)
What is the relationship between how fast the joints are moving (
s), and how fast the point
is moving? We'll start by taking a time derivative of each side. We have to use the chain rule, since the angles are functions of time. Remember that

The chain rule has a simple physical explanation: we want to know how fast f changes with time; we know how fast f changes with
, and we know how fast
changes with time.

and
are the joint velocities, while the other terms describe the geometry of the robot at a particular configuration. Let's collect the velocity terms:

We could write this in vector form:
(6)![\left( \begin{matrix} {\dot x(t) \\ \dot y(t)} \end{matrix} \right) = \left[ \begin{array}{cc} { (-l_1 s_1 - l_2 s_{12} ) & - \dot \theta_2(t)) l_2 s_{12} \ ( l_1 c_1 + l_2c_{12}) & l_2 c_{12} } \end{array} \right] \left( \begin{matrix} {\dot \theta_1(t) \\ \dot \theta_2(t)} \end{matrix} \right)](/local--math/eqs/ac0612048c27397cd90b9b93b357792b.png)
The matrix is called the Jacobian matrix, and it transforms between velocities in joint space and velocities in the workspace. Notice that it is only a function of the configuration: so, given a configuration, the workspace velocity is related linearly to the joint space velocity.
Also notice that for our example, upper left element of the Jacobian happens to be the partial derivative of
, the expression for x as a function of q, with respect to
. In fact, observation tells us that the Jacobian for this system has the form
![J(q) = \left[ \begin{array}{cc} \partial x / \partial \theta_1 & \partial x / \partial \theta_2 \ \partial y / \partial \theta_1 & \partial y / \partial \theta_2 \end{array} \right]](/local--math/eqs/f535195961c6bd5ca6f8f67311f81b0f.png)
The multivariable chain rule
If we could compute the elements of the Jacobian by just computing partial derivatives of the forwards kinematics, that would be much easier than using the chain rule and factoring out
s! In fact we can, and this is a consequence of the multivariable chain rule from vector calculus:
Let
be a function of n variables
, each of which is a function of some other variable
. Then

The multivariable chain rule is easy to remember if we think about some examples. For example, let f be a function of x, y, z. Maybe f is the air temperature at different points in a room. Then let x(t), y(t), z(t) be a trajectory through that room. How fast does the temperature change (df/dt) at some point on that trajectory? The first thing we do is compute a vector tangent to the trajectory: (dx/dt, dy/dt, dz/dt). Then we compute a vector that describes how much the temperature changes in each of the coordinate directions x, y, z:
— this vector is known as the gradient of the temperature. So how fast does the temperature change? It's the dot product (or projection) of the tangent vector with the gradient.
For our system, the x coordinate of the arm is a function of several variables,
, each of which is a function of time. So
can be computed by taking the partial derivative of the forward kinematics for x with respect to
, and taking a dot product with the joint velocities. This is the effect of multiplying first row of the Jacobian times the joint velocity vector! The second row of the Jacobian corresponds to the y coordinate.
So, the Jacobian is a generalization of the multivariable chain rule to vector-valued functions. That may sound intimidating, but in practice it's easy to remember: you have one vector (the position of the end effector) whose elements are functions of another vector (the configuration of the robot), and the configuration of the robot is changing with time. To compute the relationship between the time derivative of each vector, just multiply by a matrix of partials.
Geometric interpretation of the Jacobian
Matrix multiplication is linear:
. If we fix the robot arm at a particular configuration, the Jacobian can be computed explicitly, and is just a constant matrix. We have

where x is the vector describing the location of the end effector. It follows that the effect of moving joint one with
and moving (at the same time) joint two with
is the sum of the effects of the independent motions.
This means that you can (approximately) measure the Jacobian experimentally, at least at a fixed configuration! Lock joint 2, and move joint 1 slightly. Measure the motion of the end effector. This is the first column of the Jacobian. Lock joint 1, and move joint 2 slightly. This is the second column of the Jacobian.
The cross-product method of computing the Jacobian for serial revolute arms
The idea of moving joints independently to determine columns of the Jacobian gives an idea about how to compute the Jacobian for serial revolute arms without computing any partial derivatives! The first column of the Jacobian tells how the velocity of the end effector depends on the motion of the first joint. Lock all of the joints except the first. Draw the line from the first joint to the end effector. Rotating the joint will move the effector in a direction that is 1) perpendicular to the joint axis, 2) perpendicular to the line you just drew, and 3) has magnitude proportional to the length of that line. If you take the cross product of the joint axis and the vector from joint 1 to the effector, you'll get a vector with exactly that property, and this will be the first column of the Jacobian!
How about the second column? Fix all joints except the second, draw the line from the second joint to the effector, and take the cross product with the second joint.
Singularities of the Jacobian
Sometimes columns of the Jacobian are linearly independent, and sometimes they are not. The rank of the Jacobian is the number of linearly independent columns. Each column describes a direction in the workspace that the robot can move by changing one configuration variable.





