Odom Tutorial
Odom Tutorial
Edwin Olson
[email protected]
December 4, 2004
1 Introduction
Most robotics problems ultimately reduce to the question: where am I? How can you go
somewhere else without some notion of where you are now? You could proceed naively,
stumbling around, hoping that your goal will appear in range of your robot’s sensors, but
a better plan is to navigate. A basic method of navigation, used by virtually all robots, is
odometry, using knowledge of your wheel’s motion to estimate your vehicle’s motion.
The goal of this primer is to show you how to use odometry data. A real dataset will be
used extensively to show how well (and how badly) these ideas can work.
Suppose your robot starts at the origin, pointed down the x-axis. Its state is (x, y, θ) =
(0, 0, 0). If the robot travels (roughly) straight for three seconds at 1 m/s, a good guess of
your state will be (3, 0, 0). That’s the essence of odometry.
We’ll assume that the vehicle is differentially driven: it has a motor on the left side of
the robot, and another motor on the right side. If both motors rotate forward, the robot
goes (roughly) straight. If the right motor turns faster than the left motor, the robot will
move left.
Our goal is to measure how fast our left and right motors are turning. From this, we
can measure our velocity and rate of turn, and then integrate these quantities to obtain our
position.
2 Derivation
The speeds of our motors give us two quantities: the rate at which the vehicle is turning,
and the rate at which the vehicle is moving forward. All we have to do is integrate these
two quantities, and we’ll have our robot’s state (x, y, θ).
That sounds a bit scary, but the mathematics end up being very simple. If we had
analytic expressions for the angular rate and forward rate functions, their integral probably
would be scary. But in a real system, our data comes from real sensors that are sampled
periodically. Every few milliseconds, we get a new measurement of our motor velocities. We
will numerically integrate our solution, which is of course, just a fancy way of saying that
we’ll divide time up into little chunks and just add up all the little pieces.
Suppose our robot is at (x, y, θ). Depending on what kind of sensors we have, we might
get measurements of how much the motors have rotated (in radians), or an estimate of how
fast they’re rotating (angular rate, radians/sec.) We’ll consider the first case, but of course
the second case can be handled by just multiplying the angular rate by the amount of time
that has elapsed since our last iteration. Given the amount of rotation of the motor and
the diameter of the wheel, we can compute the actual distance that the wheel has covered.
1
Suppose the left wheel has moved by a distance of dlef t and the right wheel has moved
dright . For some small period of time (such that dlef t and dright are short), we can reasonably
assume that the vehicle trajectory was an arc (see Fig. 1).
θ'
d r ig
ht
(x',y')
d lef
θ
t
(x,y)
ϕ
dbaseline
P
Figure 1: Odometry geometry. Over a small time period, the robot’s motion can be ap-
proximated by an arc. The odometry problem is to solve for (x0 , y 0 , θ0 ) given (x, y, θ) and
dbaseline . In the figure, the robot is moving counter-clockwise.
The initial state (x, y, θ) defines our starting point, with θ representing the vehicle’s
heading. After our vehicle has moved by dlef t and dright , we want to compute the new
position, (x0 , y 0 , θ0 ).
The center of the robot (the spot immediately between the two wheels that define’s the
robot’s location), travels along an arc as well. Remembering that arc length is equal to the
radius times the inner angle, the length of this arc is:
dlef t + dright
dcenter = (1)
2
Given basic geometry, we know that:
If dbaseline is the distance between the left and right wheels, we can write:
2
θ'
d r ig
ht
(x',y')
d ce
nt
er
d lef
θ
t
(x,y)
ϕ
P θ−π/2
rleft
rcenter
rright
Figure 2: Detailed odometry geometry. We compute the center of the circle P by forcing
dlef t and dright to be two arcs with the same inner angle φ. From this, we can compute the
new robot position (x0 , y 0 , θ0 ).
and
3
y0 = Py + rcenter sin(φ + θ − π/2)
= y + rcenter cos(θ) − rcenter cos(φ + θ)
= y + rcenter [cos(θ) − cos(φ)cos(θ) + sin(θ)sin(φ)] (7)
If φ is small (as is usually the case for small time steps), we can approximate sin(φ) = φ
and cos(φ) = 1. This now gives us:
and
dlef t + dright
dcenter = (10)
2
dright − dlef t
φ = (11)
dbaseline
θ0 = θ+φ (12)
0
x = x + dcenter cos(θ) (13)
y0 = y + dcenter sin(θ) (14)
4
+
VEMF
+ -
VApplied
-
Motor
Figure 3: Simple motor model. The simplest motor model is a resistor (corresponding to the
resistance of the motor’s wire coil), and a voltage source corresponding to the Back EMF.
is known as the Electro-Motive Force (EMF). It’s often called the “Back EMF”, since it’s
the voltage coming back out of the motor.
When we interface with a motor, we typically control the voltage applied to the motor.
This applied voltage can cause current to flow into the motor. At any given moment, Ohm’s
law can be applied. However, the voltage that we have to consider isn’t the applied voltage,
but the net voltage: Vapplied − Vemf . In other words, the current can be written:
5
Suppose you’re trying to build a dimmable light switch; can you build one from just
an on-off switch? Suppose you start flipping the light on and off repeatedly, at first fairly
slowly. The room is bright, then dark, then bright again. Not a very good dimmer! But you
can probably imagine that if you could flip the switch fast enough, that you could achieve
intermediate brightness levels. This is what we’re going to do with motors.
If the switch is “on” 50% of the time, you might expect the motor to run about the same
as it does at 50% the voltage. This does, in fact, work... provided that the switching is fast
enough. The criteria for the switching rate is that the voltage has to change faster than the
motor can react; the motor has an “electrical time constant”, which reflects how rapidly it
can react to changing electrical conditions.
period
20%
50%
80%
This technique is called Pulse Width Modulation (PWM) (see Fig. 4), since the width
of each pulse is modulated in order to approximate different values of Vapplied .
In general, motor electrical time constants are on the order of a few milliseconds, but
PWM frequencies in the ¡20kHz range can cause audible vibrations. So often, PWM fre-
quencies are increased well above the human range of hearing.
3.4 Summary
We’ll continue to use our simple model for the rest of this article. Here’s what you need to
remember:
• The Back EMF of a motor (Vemf ) is proportional to the speed of the motor.
6
• Motor current is proportional to torque.
• We drive motors with PWM, which allows us to approximately control Vapplied .
4 Dead-reckoning Sensors
In order to build an odometry system, you must have a way of measuring the angular
velocity of the motor. This can be accomplished in a number of ways:
• Mono Phase Encoders. A sensor is placed on the motor shaft or wheel such that
when the shaft rotates, the circuitry generates alternating 1’s and 0’s. One way of
implementing a simple encoder is by attaching a disc with holes to the shaft, and using
a breakbeam sensor to detect when a hole passes by. A mono phase encoder can not
determine the direction of motion. A serious failure mode occurs when the motor is
essentially stationary with a hole half-way in front of the sensor: environmental noise
can cause the encoder to trigger and untrigger, making it appear as though the shaft
is rotating.
Break-beam sensor
Clockwise rotation:
Counter-Clockwise rotation:
7
Break-beam sensors
a
(90 degrees offset)
b
Clockwise rotation:
a
b
Counter-Clockwise rotation:
a
b
Figure 6: Quadrature Phase Encoder. Two simple encoders, arranged so that they pick up
the same perforated holes, but 90 degrees out of phase with each other, allow the direction
of rotation to be determined.
• Indirect Back EMF estimation via current sense. We can measure the amount of
current flowing through the motor by putting a small-valued resistor in the path
between the motor and ground. Ohm’s law tells us that the voltage across that
resistor will be proportional to the current.
If we know the motor current, the applied voltage (which we’re controlling), and the
resistance of the motor winding, we can estimate the back EMF. Solving Eqn 15 for
Vemf
• Gyro heading adjustment. Some vehicles have a gyroscope, which can provide an
estimate of the vehicle’s angular rate dθ/dt. Gyros drift over time, but can be quite
accurate over small periods of time. They can be used to improve dead reckoning
accuracy, particularly when a poor motor feedback sensor is used (e.g., back EMF.)
5 Odometry in Practice
Odometry can provide good dead-reckoning over short distances, but error accumulates very
rapidly. At every step, we inject error (noise) into not just x and y, but also θ. The error
in θ is the killer, since every error in θ will be amplified by future iterations.
There are a number of basic noise sources.
• Sensor error. If we’re using anything other than quadrature phase encoders for our
feedback, then our estimates of the dlef t and dright will be noisy.
• Slippage. When the robot turns a corner, one wheel will, in general, slip a little bit.
This means that even if the odometry data was perfect, the robot’s path would not
recoverable from it.
• Error in estimate of dbaseline or in wheel diameters. We must measure the baseline
of the robot and the scale factor relating angular rate and linear velocity (a function
of the wheel diameter.) Even small errors in these constants can cause problems–
typically, the odometry result will have a consistent veer in one direction or the other.
In fact, often the wheels on the robot are slightly different sizes. Even small differences
lead to large navigation errors with time.
8
Figure 7: Splinter. This is the robot that collected the dataset. The vehicle, known as
“Splinter”, has high quality quadrature phase encoders on each drive motor. A laptop on
the back of the vehicle logged the data. The large blue device in the front of the vehicle is
a laser range finder, not used in this article.
You should be itching to try out odometry now, and fortunately, there’s a dataset waiting
for you! In this section, we’ll walk through a few examples in Matlab.
The dataset consists of 200 meters of odometry and gyro data from an experiment that
lasted about 10 minutes. The vehicle that collected the data is shown in Fig. 7. The vehicle
left the lab, travelled around a large open space in a clockwise (as viewed from the top)
direction three times, then reversed direction and travelled around the same loop once in
the opposite direction. Finally, it returned to lab.
A good odometry result is shown in Fig. 8. While the robot started and stopped in
(approximately) the same space, notice how the odometry estimate is quite different at the
beginning and end. A small error in θ causes all subsequent navigation to be rotated out of
alignment.
The dataset is available from /mit/6.186/2005/doc/odomtutorial. Copy it into a direc-
tory and start matlab. The data is contained in a single array called “data”. Each row
in the dataset is a set of observations made at a single point in time. A helper script,
“setup.m” is provided which loads the dataset and sets up a few constants. These constants
are TIME, LEFTTICKS, RIGHTTICKS, LEFTCURRENT, RIGHTCURRENT, LEFT-
PWM, RIGHTPWM, and GYRO, and correspond to the column numbers in which data of
different types is stored. To get started, type:
>> setup
Note that the odometry data is provided in units of ticks: the amount of forward (or
backward) motion that occured since the last sample. Ticks are related to distance (and
angular rate) by constant scale factors, which are characteristics of the robot’s geometry.
We mentioned before that the baseline, the distance between the left and right wheels, is
also a characteristic of the robot.
These measurements are made using a ruler, and are inexact. One of our tasks will be
to find better values of the parameters.
Parameter Value
baseline 0.45 meters
metersPerTick 0.000045 meters
9
Corrected Odometry
16
14
12
10
Y (meters)
−15 −10 −5 0
X (meters)
Figure 8: Good odometry result. This result was obtained by manually optimizing the rigid
parameters of the vehicle until the path best resembled the actual trajectory. Note that
the trajectory, in fact, started and ended at approximately the same position; even good
odometry results can contain significant errors.
>> clf;
>> hold on;
>> plot(data(:,LEFTTICKS),’r’);
>> plot(data(:,RIGHTTICKS),’b’);
The command “clf” clears the figure, “hold on” allows multiple plots to be displayed on
top of each other, and the two plot commands plot the vector of data in either red (’r’) or
blue(’b’).
Compare the instantaneous velocity of the left and right wheels to the odometry results
in Fig. 8. Identify in the velocity plot where the robot was turning.
10
4
−2
−4
−6
−8
−10
−12
−14
−16
0 1 2 3 4 5 6
4
x 10
Figure 9: Adjusted gyro data. The robot traveled in straight line segments, punctuated by
(roughly) 90 degree turns. This is readily evident from the gyro data.
Make sure you understand how this code works. Try it with and without the “unwrap”
command. Obviously, you’ll need to experiment with different values of driftrate. Dealing
with 2π wrap-around is tricky, and many bugs can be introduced by neglecting it!
A fancy way of doing the calibration is to find some metric that “measures” the goodness
of the drift rate. Suppose you assume that the starting orientation and end orientation were
different by π/2; could you compute the correct drift rate from this?
11
Uncorrected Odometry
10
5
Y (meters)
−5
−10
−25 −20 −15 −10 −5 0
X (meters)
Figure 10: Uncorrected Odometry. Your first attempt at odometry should match this figure.
regardless of what the data actually tells us. Our goal is to get the best general purpose
values of our parameters– ones that will be useful on future navigation missions, not get the
absolute best result on a single, controlled (and perhaps contrived!) experiment. Remember
that on any actual experimental run, it is much more likely that there was some error, than
that there was no error.
Even with only three parameters (leftMetersPerTick, rightMetersPerTick, and baseline)
it is quite possible to overfit, particularly when the dataset is relatively short. A general
strategy for dealing with overfitting is to use cross-validation: fit parameters to a subset of
the data, and test it on a disjoint subset of the data. We can’t readily do that here, since
we only have one relatively short dataset.
12
Gyro−Corrected Odometry
18
16
14
12
Y (meters) 10
−10 −5 0 5 10 15
X (meters)
Figure 11: Gyro-derived heading odometry. The (drift-corrected) gyro was used exclusively
for heading. You should replicate these results, and try to improve them further by fusing
the odometry-derived heading and the gyro-derived heading.
Using Eqn. 17, estimate Vemf of the motor from these parameters. We know that Vemf
is proportional to angular velocity, but what is the scale factor? We could look it up on the
motor’s datasheet, but it’s probably not terribly accurate anyway.
Let’s consider a single wheel. We have it’s Vemf and its actual velocity as measured by
the quadrature phase encoders. To estimate velocity, you’ll need to consider the amount of
time that elapsed during every time step. You can compute this using:
One of the irritating things about working with real systems is that data doesn’t always
cooperate. It’s entirely possible (in fact, likely) that you may encounter intervals in which
zero time elapsed. When you compute the velocity during this interval, you must be careful
to avoid a divide-by-zero! A good way of dealing with this is to estimate the velocity by
looking at a window spanning several time samples. This can also serve to filter out some
of the noise!
We know that Vemf and velocity should be proportional to each other. Time for an
upsetting fact: there’s probably some nonlinear offset as well. In other words, let’s model
the system as:
Ax = B (19)
This of course is the most basic of all Linear Algebra problems. Remember that this
system is hugely overdetermined: we have thousands of simultaneous equations, and only
two unknown variables. This is a good opportunity to compute a least-squares fit. (For a
reminder of the mathematics, see Strang’s 18.06 textbook, “Introduction to Linear Alge-
bra”.)
13
x = (AT A)−1 AT B (20)
We can now estimate the velocity of the motor using our coefficients x1 and x2 , and
compare it to our measured values using odometry. For the left wheel, you should get a
graph like that in Fig. 17.
4
x 10
2
Back−EMF estimated velocity
Quadphase velocity
1.5
0.5
−0.5
−1
−1.5
0 1 2 3 4 5 6
4
x 10
Figure 12: Estimating velocity from Current Sense. Using Eqn. 17, we can estimate back-
emf (and thus velocity) using the motor’s current and applied voltage.
Now let’s put it all together. Estimate the velocity for the left and right wheels, and
compute a trajectory without using the quadrature phase data (except for calibrating your
models.)
How does it look? When does it perform well/poorly? How does it look if you use the
gyro data for your θ estimate? You should be able to achieve something like Fig. 13. Keep
in mind that this approach doesn’t require any optical encoders at all!
18
16
14
12
10
Y (meters)
−2
−10 −5 0 5 10 15
X (meters)
14
6 Conclusion
You now have a pretty good idea about what odometry is, what it can do, and what it can’t.
In Maslab, you won’t have optical encoders as good as those used in this problem. But you
will have a gyro, current sense, and the ability to build your own quadrature phase optical
encoders.
What approaches do you think will work? Is there some other way of navigating? Maslab
robots have cameras. If you pick out a feature and follow it around, can you use that to
compute changes in robot orientation? If you find a feature of known size, can you estimate
how far away you are?
You can purchase other sensors too– perhaps an electronic compass. Inexpensive elec-
tronic compasses might be low resolution, but they won’t drift like a gyro. Can an electronic
compass plus a gyro be a powerful navigation aid?
If you have any comments or corrections on this tutorial, please send me an email at
[email protected].
15