Introduction
In FIRST Tech Challenge (FTC), kinematics are used all of the
time—they’re essential to robot operation. However, few teams understand
where the relationships come from or even acknowledge them explicitly,
especially for holonomic drives. This paper intends to demystify the
role and derivation of drive kinematics with a unified approach.
Drive Kinematics
This section systematically derives the forward and inverse
kinematics for a variety of drives found in FTC (i.e., differential,
mecanum, and swerve). The forward kinematics describe how the robot
moves with specific wheel velocities. The inverse kinematics describe
the opposite—how the wheels move during a given robot motion.
Robots as Rigid Bodies
Most FTC robots have a robust structure that holds all of the
components together into one coherent system. When acted upon by a
force, the robot does not materially deform, and its constituent parts
remain essentially fixed relative to each other. Objects with this
property are called rigid bodies, and their kinematics can be summarized
with a single translational and angular velocity vector pair. The
translational velocity describes the motion of the axis or tation, while
the angular velocity magnitude points along the axis of rotation and has
magnitude equal to the angular speed.
Consider a point in the body with position . This position can be written as
the sum where points from the origin to the
axis of rotation and extends perpendicular
to . Differentiation gives the velocity relationship
As FTC robots are generally confined to a plane,
we have In this special case, the velocity is
Now for a given configuration it is possible to compute the two-dimensional velocity
of any point on the robot.
Differential Drives
Perhaps the simplest practical mobile robot drive configuration is a
differential drive with two normal wheels. These wheels have radius
and are spaced units apart. Let the center of
rotation (i.e., the midpoint of the wheel positions) be the origin with
the wheel axles laying parallel to the y-axis. With this setup, the
wheel center positions are .
Using the results of the previous subsection, the desired velocities are
Furthermore, the orientation of the wheels gives
us the tangential velocities in terms of the wheel angular velocities
For traction wheels, the corresponding velocities
must exactly match. This yields the equations From this we can solve to obtain the forward and
inverse kinematics In matrix form, these relations are These same kinematics can be applied to
differential drives with multiple wheels per side. However, you’ll
quickly realize that it is no longer possible to satisfy all the
constraints. To rotate properly, the wheels must overcome static
friction and slide parallel to the wheel axis. This slippage can be
mathematically accounted for by treating this scrub direction as a
passive degree of freedom (like an omni wheel) as we’ll see in the next
section. With this assumption, the kinematics are the same as above with
all motors on each side sharing the same velocity.
Mecanum Drives
Mecanum drives consist of four mecanum wheels with rollers at angles with respect to the axle
positioned in a rectangle. Looking from above, the main diagonal wheels
have counterclockwise-rotated rollers, while the alternate diagonal
wheels have clockwise-rotated rollers. The careful combination of these
two different directions enables omnidirectional movement. The track
width (distance between opposing wheels) is and the wheelbase (distance between
adjacent wheels) is . Place the
center of rotation at the origin as before with wheel center positions
.
Using the same procedure as before, we obtain Computing the tangential velocities from the
angular velocities is bit trickier for mecanum wheels. The tangential
force acts from the
roller, resulting in a speed reduction of . The direction of the velocity
points perpendicular to the roller axis (viewed from above). Thus, the
velocities are The vectors can’t be directly equated for
non-square configurations due to the passive motion of the rollers.
Instead we equate the portion of each vector in the tangential velocity
direction. For example, the front left constraint is The
final system is which yields the matrix kinematics
Swerve Drives
Unlike the previous drives, swerve drives have actuated wheel
directions. Nevertheless, swerve kinematics can still be derived within
the same framework. Let each wheel have coordinates , orientation , tangential velocity , and angular velocity .
For simplicity, we will assume the swerve wheels do not slip and
directly equate the tangential velocities: and . This
gives the following inverse kinematics:
Forward kinematics for a collection of multiple wheels can be
computed by solving the corresponding overdetermined system.
Odometry
The previous section focused on finding the relationship between
configuration and wheel velocities. This by itself is sufficient to
employ the inverse kinematics for sending the appropriate control
signals. However, the forward kinematics cannot be directly used for
odometry. To localize the robot, the local velocities must be integrated
into positions and transformed into the global frame.
Constant Velocity Odometry
For simplicity, this method assumes constant translational and
rotational velocity over each measurement period. In practice, this is a
good assumption so long as measurements are frequent enough
(additionally, estimating acceleration or other higher order derivatives
robustly from wheel position data is nontrivial).
Without loss of generality, we take the robot heading to be initially. A measurement is then taken
time later. During this
period the robot’s global velocity is Integrating this over time gives This can then be rotated and added to the
previous estimate to complete the update
Tracking Wheels
Tracking wheels are passive omni wheels intended solely for odometry.
Each wheel has an arbitrary position and orientation in the robot frame. Similar to
swerve, the tangential velocities of each wheel are and . If placed properly, three
tracking wheels are sufficient to determine the configuration: For example, take the common configuration of two
tracking wheels placed parallel to the robot’s -axis at and a third placed parallel
to the robot’s -axis at . For simplicity, all wheels point
in the positive direction of their corresponding axis. This gives the
following matrices: Two tracking wheels and a heading sensor is
also sufficient for localization.