5.2. Motion Model for the Differential Drive Robot#
By rotating the two wheels independently, we can control both the linear and angular velocity of the DDR.

The motion model for the logistics robot of the previous chapter was fairly simple;
we assumed that the robot moved with constant linear velocity

When describing the motion of our DDR, the orientation of the robot enters in two ways.
First, because the robot wheels roll without slipping,
the linear velocity of the robot is always instantaneously in the steering direction.
Second, because the robot can rotate, we must take account of its angular velocity, in addition to the linear velocity.
This is illustrated in Figure 1.
Suppose the robot is following a path
Note that the velocity is tangent to the curve
Because our robot moves in the plane, the z-axis of the body-attached frame is always parallel to the z-axis of the world frame.
This greatly simplifies the description of angular velocity, which in this case we may define as
It is common to combine the angular and linear velocity into a single vector, either in the body frame,
or in the world frame:
5.2.1. The Relationship Between Wheel Rotation and Robot Velocity#
Because the wheels of the DDR are independently actuated, it is possible to achieve a large range of robot velocities. We can derive the relationship between wheel rotation and robot velocity by considering first the motion of a single wheel, and then considering the effect of coupling the two wheels along a single axis of rotation.

Figure 2 shows a side-view of the right wheel.
We denote by
The same reasoning can be applied to the left wheel to obtain

Suppose now that both wheels spin at the same speed,

If instead, as in Figure 4, the two wheels spin in opposite directions, i.e., we have
Applying the equation of circular motion yields
which leads to
We have now considered the two special cases of pure translation and pure rotation. Because instantaneous velocities lie in a vector space, we can add these in the same way that we would add any vectors. Therefore, by spinning the wheels at different rates, we can obtain various linear combinations of the above pure translations and rotations. Adding the equations for linear and angular velocities of the two wheels, we obtain
These two equations define the inverse velocity kinematics for our DDR:
Given a desired output specified by
The forward velocity kinematics are easily obtained from the above equations via simple algebra:
This leads immediately to the system equations with respect to the body-attached frame and with respect to the world frame
5.2.2. Kinematics in Code#
The equations above can be easily implemented in code. We do so below:
def ddr_ik(v_x, omega, L=0.5, r=0.1):
"""DDR inverse kinematics: calculate wheels speeds from desired velocity."""
return (v_x - (L/2)*omega)/r, (v_x + (L/2)*omega)/r
def ddr_fk(phidot_L, phidot_R, L=0.5, r=0.1):
"""DDR inverse kinematics: calculate wheels speeds from desired velocity."""
return gtsam.Point3((phidot_R+phidot_L)*r/2, 0, (phidot_R-phidot_L)*r/L)
As an example, let us try to move forward with a velocity of 20 cm/s, while turning counterclockwise at 0.3 rad/s:
phidot_L, phidot_R = ddr_ik(v_x=0.2, omega=0.3)
print(phidot_L, phidot_R)
1.25 2.75
As expected, the left wheel rotates less quickly, making us turn counter-clockwise. To sanity-check, let us put these same wheel speeds through the forward kinematics:
print(ddr_fk(phidot_L, phidot_R))
[0.2 0. 0.3]
The velocities are as desired, validating both the equations and their implementation. Feel free to experiment with other values using the code above!