Controls Engineering in FRC
Controls Engineering in FRC
Tyler Veness
Controls Engineering in the
FIRST Robotics Competition
Graduate-level control theory for high schoolers
Tyler Veness
Copyright © 2017-2023 Tyler Veness
HTTPS://GITHUB.COM/CALCMOGUL/CONTROLS-ENGINEERING-IN-FRC
Licensed under the Creative Commons Attribution-ShareAlike 4.0 International License (the “Li-
cense”). You may not use this file except in compliance with the License. You may obtain a copy
of the License at https://creativecommons.org/licenses/by-sa/4.0/. Unless required by applicable
law or agreed to in writing, software distributed under the License is distributed on an “AS IS” BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the
specific language governing permissions and limitations under the License.
Generated from commit 8bfdb63 made on April 8, 2023. The latest version can be downloaded from
https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
Tree next to Oakes Circle at UCSC
Contents
Preface . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . xiii
2 PID controllers . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 11
2.1 Proportional term 11
2.2 Derivative term 12
2.3 Integral term 14
iv Contents
3 Application advice . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 19
3.1 Mechanical solutions vs software solutions 19
3.2 Actuator saturation 20
4 Calculus . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 21
4.1 Derivatives 21
4.1.1 Power rule . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 22
4.1.2 Product rule . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 22
4.1.3 Chain rule . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 22
4.1.4 Partial derivatives . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 22
4.2 Integrals 22
4.3 Change of variables 23
4.4 Tables 24
4.4.1 Common derivatives and integrals . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 24
5 Linear algebra . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 27
5.1 Vectors 27
5.2 Linear combinations, span, and basis vectors 27
5.3 Linear transformations and matrices 27
5.4 Matrix multiplication as composition 27
5.5 The determinant 28
5.6 Inverse matrices, column space, and null space 28
5.7 Nonsquare matrices as transformations between dimensions 28
5.8 Eigenvectors and eigenvalues 28
5.9 Miscellaneous notation 28
5.10 Matrix definiteness 28
5.11 Common control theory matrix equations 29
5.11.1 Continuous algebraic Riccati equation (CARE) . . . . . . . . . . . . . . . . . . . . . . . . . . . . 29
5.11.2 Discrete algebraic Riccati equation (DARE) . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 29
5.11.3 Continuous Lyapunov equation . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 29
5.11.4 Discrete Lyapunov equation . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 29
5.12 Matrix calculus 29
5.12.1 Jacobian . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 30
5.12.2 Hessian . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 30
5.12.3 Useful identities . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 30
Contents v
8 Nonlinear control . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 79
8.1 Introduction 79
8.2 Linearization 79
8.3 Lyapunov stability 80
8.3.1 Lyapunov stability for linear systems . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 81
8.4 Affine systems 81
8.4.1 Feedback linearization for reference tracking . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 82
8.5 Pendulum 82
8.5.1 State-space model . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 82
8.6 Holonomic drivetrains 84
8.6.1 Model . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 84
8.6.2 Control . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 84
8.6.3 Holonomic vs nonholonomic control . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 84
8.7 Differential drive 85
8.7.1 Velocity subspace state-space model . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 85
8.7.2 Heading state-space model . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 86
Contents vii
IV System modeling
11 Dynamics . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 141
11.1 Linear motion 141
11.2 Angular motion 141
11.3 Vectors 142
11.3.1 Basic vector operations . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 142
11.3.2 Cross product . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 142
11.4 Curvilinear motion 143
11.5 Differential drive kinematics 143
11.5.1 Inverse kinematics . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 144
11.5.2 Forward kinematics . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 145
11.6 Mecanum drive kinematics 145
11.6.1 Inverse kinematics . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 145
11.6.2 Forward kinematics . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 148
11.7 Swerve drive kinematics 148
11.7.1 Inverse kinematics . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 148
11.7.2 Forward kinematics . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 150
V Motion planning
VI Appendices
C Feedforwards . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 213
C.1 QR-weighted linear plant inversion 213
C.1.1 Setup . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 213
C.1.2 Minimization . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 214
C.2 Steady-state feedforward 215
C.2.1 Continuous case . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 215
C.2.2 Discrete case . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 215
C.2.3 Deriving steady-state input . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 216
D Derivations . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 219
D.1 Linear system zero-order hold 219
Contents xi
Glossary . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 249
Bibliography . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 251
Online 251
Index . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 255
This page intentionally left blank
Flower bush near Spencer’s Market in Santa Maria, CA
Preface
When I was a high school student on FIRST Robotics Competition (FRC) team 3512, I had to learn
control theory from scattered internet sources that either weren’t rigorous enough or assumed too
much prior knowledge. After I took graduate-level control theory courses from University of Cal-
ifornia, Santa Cruz for my bachelor’s degree, I realized that the concepts weren’t difficult when
presented well, but the information wasn’t broadly accessible outside academia.
I wanted to fix the information disparity so more people could appreciate the beauty and elegance I
saw in control theory. This book streamlines the learning process to make that possible.
I wrote the initial draft of this book as a final project for an undergraduate technical writing class I
took at UCSC in Spring 2017 (CMPE 185). It was a 13-page IEEE-formatted paper intended as a
reference manual and guide to state-space control that summarized the three graduate controls classes
I had taken that year. I kept working on it the following year to flesh it out, and it eventually became
long enough to make into a proper book. I’ve been adding to it ever since as I learn new things.
I contextualized the material within FRC because it’s always been a significant part of my life, and
it’s a useful application sandbox. I’ve since contributed implementations of many of this book’s tools
to the FRC standard library (WPILib) and maintain them.
Acknowledgements
Thanks to my controls engineering instructors Dejan Milutinović and Gabriel Elkaim for introducing
me to the field of control theory. They taught me what it means to be a controls engineer, and I
appreciated their classes’s pragmatic perspective focused on intuition and application.
This page intentionally left blank
Trees by Baskin Engineering building at UCSC
0.1 Prerequisites
Knowledge of basic algebra and complex numbers is assumed. Some introductory physics and cal-
culus will be taught as necessary.
theoretically incorrect solution like linear approximations of the nonlinear system works well enough
to be used industry-wide. There are more sophisticated controllers than PID, but we use PID anyway
for its versatility and simplicity. Sometimes the inferior solutions are more effective or have a more
desirable cost-benefit ratio than what the control system designer considers ideal or clean. Choose
the tool that is most effective.
Solutions need to be good enough, but do not need to be perfect. We want to avoid integrators
as they introduce instability, but we use them anyway because they work well for meeting tracking
specifications. One should not blindly defend a design or follow an ideology, because there is always a
case where its antithesis is a better option. The engineer should be able to determine when this is the
case, set aside their ego, and do what will meet the specifications of their client (e.g., system response
characteristics, maintainability, usability). Preferring one solution over another for pragmatic or
technical reasons is fine, but the engineer should not care on a personal level which sufficient solution
is chosen.
2 PID controllers . . . . . . . . . . . . . . . . . . . . . . 11
2.1 Proportional term
2.2 Derivative term
2.3 Integral term
2.4 PID controller definition
2.5 Response types
2.6 Manual tuning
2.7 Limitations
3 Application advice . . . . . . . . . . . . . . . . . . 19
3.1 Mechanical solutions vs software solutions
3.2 Actuator saturation
4 Calculus . . . . . . . . . . . . . . . . . . . . . . . . . . . . 21
4.1 Derivatives
4.2 Integrals
4.3 Change of variables
4.4 Tables
This page intentionally left blank
Road near walking trail off of Rice Ranch Road in Santa Maria, CA
Control systems are all around us and we interact with them daily. A small list of ones you may have
seen includes heaters and air conditioners with thermostats, cruise control and the anti-lock braking
system (ABS) on automobiles, and fan speed modulation on modern laptops. Control systems monitor
or control the behavior of systems like these and may consist of humans controlling them directly
(manual control), or of only machines (automatic control).
How can we prove closed-loop controllers on an autonomous car, for example, will behave safely
and meet the desired performance specifications in the presence of uncertainty? Control theory is an
application of algebra and geometry used to analyze and predict the behavior of systems, make them
respond how we want them to, and make them robust to disturbances and uncertainty.
Controls engineering is, put simply, the engineering process applied to control theory. As such,
it’s more than just applied math. While control theory has some beautiful math behind it, controls
engineering is an engineering discipline like any other that is filled with trade-offs. The solutions
control theory gives should always be sanity checked and informed by our performance specifications.
We don’t need to be perfect; we just need to be good enough to meet our specifications.[1]
R Most resources for advanced engineering topics assume a level of knowledge well above that
which is necessary. Part of the problem is the use of jargon. While it efficiently communicates
ideas to those within the field, new people who aren’t familiar with it are lost. Therefore, it’s
important to define terms before using them. See the glossary for a list of words and phrases
commonly used in control theory, their origins, and their meaning. Links to the glossary are
provided for certain words throughout the book and will use this color.
t K t
+
input open-loop output
∓
feedback
The open-loop gain is the total gain from the sum node at the input (the circle) to the output branch.
This would be the system’s gain if the feedback loop was disconnected. The feedback gain is the
total gain from the output back to the input sum node. A sum node’s output is the sum of its inputs.
Figure 1.3 is a block diagram with more formal notation in a feedback configuration.
+
X P1 Y
∓
P2
Feedforward u(t)
r(t) y(t)
controller
Controllers which incorporate information fed back from the plant’s output are called closed-loop or
feedback controllers. Figure 1.5 shows a plant with a feedback controller.
Note that the input and output of a system are defined from the plant’s point of view. The negative
feedback controller shown is driving the difference between the reference and output, also known as
the error, to zero.
Figure 1.6 shows a plant with feedforward and feedback controllers.
Feedforward
controller
1.4 Feedforward
Feedback control can be effective for reference tracking (making a system’s output follow a desired
reference signal), but it’s a reactionary measure; the system won’t start applying control effort until
the system is already behind. If we could tell the controller about the desired movement and required
input beforehand, the system could react quicker and the feedback controller could do less work. A
controller that feeds information forward into the plant like this is called a feedforward controller.
A feedforward controller injects information about the system’s dynamics (like a model does) or the
desired movement. The feedforward handles parts of the control actions we already know must be
applied to make a system track a reference, then feedback compensates for what we do not or cannot
know about the system’s behavior at runtime.
10 Chapter 1. Control system basics
There are two types of feedforwards: model-based feedforward and feedforward for unmodeled
dynamics. The first solves a mathematical model of the system for the inputs required to meet desired
velocities and accelerations. The second compensates for unmodeled forces or behaviors directly so
the feedback controller doesn’t have to. Both types can facilitate simpler feedback controllers; we’ll
cover examples of each in later chapters.
2. PID controllers
The PID controller is a commonly used feedback controller consisting of proportional, integral, and
derivative terms, hence the name. This chapter will build up the definition of a PID controller term
by term while trying to provide intuition for how each of them behaves.
First, we’ll get some nomenclature for PID controllers out of the way. The reference is called the
setpoint (the desired position) and the output is called the process variable (the measured position).
Below are some common variable naming conventions for relevant quantities.
where Kp is the proportional gain and e(t) is the error at the current time t.
Proportional gains act like “software-defined springs” that pull the system toward the desired posi-
tion. Recall from physics that we model springs as F = −kx where F is the force applied, k is
a proportional constant, and x is the displacement from the equilibrium point. This can be written
another way as F = k(0 − x) where 0 is the equilibrium point. If we let the equilibrium point be
our feedback controller’s setpoint, the equations have a one-to-one correspondence.
F = k(r − x)
u(t) = Kp e(t) = Kp (r(t) − y(t))
so the “force” with which the proportional controller pulls the system’s output toward the setpoint is
proportional to the error, just like a spring.
where Kp is the proportional gain, Kd is the derivative gain, and e(t) is the error at the current
time t.
Kp e(t)
+ e(t) + u(t) y(t)
r(t) Plant
− +
Kd de(t)
dt
A PD controller has a proportional controller for position (Kp ) and a proportional controller for
velocity (Kd ). The velocity setpoint is implicitly provided by how the position setpoint changes over
time. Figure 2.3 shows an example for an elevator.
To prove a PD controller is just two proportional controllers, we will rearrange the equation for a PD
controller.
ek − ek−1
u k = Kp e k + Kd
dt
where uk is the control input at timestep k and ek is the error at timestep k. ek is defined as ek =
rk − yk where rk is the setpoint and yk is the current output at timestep k.
r −r y −y
Notice how k dtk−1 is the velocity of the setpoint. By the same reasoning, k dtk−1 is the system’s
velocity at a given timestep. That means the Kd term of the PD controller is driving the estimated
velocity to the setpoint velocity.
If the setpoint is constant, the implicit velocity setpoint is zero, so the Kd term slows the system
down if it’s moving. This acts like a “software-defined damper”. These are commonly seen on door
closers, and their damping force increases linearly with velocity.
14 Chapter 2. PID controllers
where Kp is the proportional gain, Ki is the integral gain, e(t) is the error at the current time t,
and τ is the integration variable.
The integral integrates from time 0 to the current time t. We use τ for the integration because we
need a variable to take on multiple values throughout the integral, but we can’t use t because we
already defined that as the current time.
Kp e(t)
+ e(t) + u(t) y(t)
r(t) Plant
− +
∫t
Ki 0
e(τ ) dτ
When the system is close to the setpoint in steady-state, the proportional term may be too small to pull
the output all the way to the setpoint, and the derivative term is zero. This can result in steady-state
error, as shown in figure 2.5.
A common way of eliminating steady-state error is to integrate the error and add it to the control
input. This increases the control effort until the system converges. Figure 2.5 shows an example
of steady-state error for a flywheel, and figure 2.6 shows how an integrator added to the flywheel
controller eliminates it. However, too high of an integral gain can lead to overshoot, as shown in
figure 2.7.
R There are better approaches to fix steady-state error like using feedforwards or constraining
when the integral control acts using other knowledge of the system. We will discuss these in
more detail when we get to modern control theory.
2.3 Integral term 15
Figure 2.6: PI controller on a flywheel without Figure 2.7: PI controller on a flywheel with over-
steady-state error shoot from large Ki gain
16 Chapter 2. PID controllers
where Kp is the proportional gain, Ki is the integral gain, Kd is the derivative gain, e(t) is the
error at the current time t, and τ is the integration variable.
Figure 2.8 shows a block diagram for a system controlled by a PID controller.
Kp e(t)
Kd de(t)
dt
R Note: Adding an integral gain to the controller is an incorrect way to eliminate steady-state
error. A better approach would be to tune it with an integrator added to the plant, but this
requires a model. Since we are doing output-based rather than model-based control, our only
option is to add an integrator to the controller.
Beware that if Ki is too large, integral windup can occur. Following a large change in setpoint, the
integral term can accumulate an error larger than the maximal control input. As a result, the system
overshoots and continues to increase until this accumulated error is unwound.
2.7 Limitations
PID’s heuristic method of tuning is a reasonable choice when there is no a priori knowledge of the
system dynamics. However, controllers with much better response can be developed if a dynamical
model of the system is known. Furthermore, PID only applies to single-input, single-output (SISO)
18 Chapter 2. PID controllers
systems; we’ll cover methods for multiple-input, multiple-output (MIMO) control in part II of this
book.
Treeline by Crown/Merril bus stop at UCSC
3. Application advice
Design robot mechanisms for controllability. FRC team 971’s seminar[1] goes into more detail. Two
of the important takeaways from it are:
• Reduce gearbox backlash
• Choose motors and gear reductions that provide adequate control authority
Remember, “fix it in software” isn’t always the answer. The remaining chapters of this book assume
you’ve done the engineering analysis and concluded that your chosen design would benefit from more
sophisticated controls, and you have the time or expertise to make it work.
umax < u
kmax (r − x) < k(r − x)
kmax < k
For the inequality to hold, kmax must be less than the original value for k. This reduced gain is
evident in a system response when there is a linear change in state instead of an exponential one as it
approaches the reference. This is due to the control effort no longer following a decaying exponential
plot. Once the system is closer to the reference, the controller will stop saturating and produce realistic
controller values again.
[1]
https://www.youtube.com/watch?v=VNfFn-gcfFI
Hills by northbound freeway between Santa Maria and Ventura
4. Calculus
This book uses derivatives and integrals occasionally to represent small changes in values over small
changes in time and the infinitesimal sum of values over time respectively. The formulas and tables
presented here are all you’ll need to carry through with the math in later chapters.
If you are interested in more information after reading this chapter, 3Blue1Brown does a fantastic
job of introducing them in his Essence of calculus series [5]. We recommend reading or watching
chapters 1 through 3 and 7 through 11 for a solid foundation. The Taylor series (presented in chapter
11) will be used in chapter 7.
4.1 Derivatives
Derivatives are expressions for the slope of a curve at arbitrary points. Common notations for this
operation on a function like f (x) include
f (x) = xn
f ′ (x) = nxn−1
h(x) = f (x)g(x)
h′ (x) = f ′ (x)g(x) + f (x)g ′ (x)
h(x) = f (g(x))
h′ (x) = f ′ (g(x)) · g ′ (x)
For example,
4.2 Integrals
The integral is the inverse operation of the derivative and calculates the area under a curve. Here is
an example of one based on table 4.2.
Z
eat dt
1 at
e +C
a
The arbitrary constant C is needed because when you take a derivative, constants are discarded be-
cause vertical offsets don’t affect the slope. When performing the inverse operation, we don’t have
enough information to determine the constant.
4.3 Change of variables 23
Let u = ωt.
du = ω dt
1
dt = du
ω
Another example, which will be relevant when we actually cover state-space notation (ẋ = Ax+Bu),
is a closed-loop state-space system.
ẋ = (A − BK)x + BKr
ẋ = Acl x + Bcl ucl
where Acl = A − BK, Bcl = BK, and ucl = r. Since it matches the form of the open-loop
system, all the same analysis tools will work with it.
24 Chapter 4. Calculus
4.4 Tables
4.4.1 Common derivatives and integrals
R
f (x) dx f (x) f ′ (x)
ax a 0
1 2
2 ax ax a
1 a+1
a+1 x xa axa−1
1 ax
ae eax aeax
− cos(x) sin(x) cos(x)
sin(x) cos(x) − sin(x)
cos(x) − sin(x) − cos(x)
− sin(x) − cos(x) sin(x)
5 Linear algebra . . . . . . . . . . . . . . . . . . . . . . 27
5.1 Vectors
5.2 Linear combinations, span, and basis vectors
5.3 Linear transformations and matrices
5.4 Matrix multiplication as composition
5.5 The determinant
5.6 Inverse matrices, column space, and null space
5.7 Nonsquare matrices as transformations between dimen-
sions
5.8 Eigenvectors and eigenvalues
5.9 Miscellaneous notation
5.10 Matrix definiteness
5.11 Common control theory matrix equations
5.12 Matrix calculus
8 Nonlinear control . . . . . . . . . . . . . . . . . . . 79
8.1 Introduction
8.2 Linearization
8.3 Lyapunov stability
8.4 Affine systems
8.5 Pendulum
8.6 Holonomic drivetrains
8.7 Differential drive
8.8 Ramsete unicycle controller
8.9 Linear time-varying unicycle controller
8.10 Further reading
This page intentionally left blank
Grass clearing by Interdisciplinary Sciences building and Thimann Labs at UCSC
5. Linear algebra
Modern control theory borrows concepts from linear algebra. At first, linear algebra may appear very
abstract, but there are simple geometric intuitions underlying it. First, watch 3Blue1Brown’s preview
video for the Essence of linear algebra video series (5 minutes) [6]. The goal here is to provide an
intuitive, geometric understanding of linear algebra as a method of linear transformations.
We would normally include written material here for learning linear algebra, but 3Blue1Brown’s
animated videos are better at conveying the geometric intuition involved than anything we could
write here with static text. Instead of making an inferior copy of his work, we’ll provide bibliography
entries for a selection of his videos.
5.1 Vectors
Watch the “Vectors, what even are they?” video from 3Blue1Brown’s Essence of linear algebra series
(5 minutes) or read the associated lesson on 3blue1brown.com [15].
The matrix denoted by 0m×n is a matrix filled with zeroes with m rows and n columns.
Matrix transpose
The T in AT denotes transpose, which flips the matrix across its diagonal such that the rows become
columns and vice versa.
A symmetric matrix is equal to its transpose.
Matrix pseudoinverse
The + in B+ denotes the Moore-Penrose pseudoinverse given by B+ = (BT B)−1 BT . The pseu-
doinverse is used when the matrix is nonsquare and thus not invertible to produce a close approxima-
tion of an inverse in the least squares sense.
Matrix trace
tr(A) denotes the trace of the square matrix A, which is defined as the sum of the elements on the
main diagonal (top-left to bottom-right).
Table 5.1: Types of matrix definiteness. Let M be a matrix and let x and y be nonzero vectors.
5.12.1 Jacobian
The Jacobian is the first-order partial derivative of a vector-valued function with respect to one of
its vector arguments. The columns of the Jacobian of f are filled with partial derivatives of f ’s rows
with respect to each of the argument’s elements. For example, the Jacobian of f with respect to x is
∂f1 ∂f1
h i ∂x1 ... ∂xm
∂f (x, u) ..
= ∂f (x,u)
∂x1 ... ∂f (x,u)
∂xm
= ... ..
. .
∂x ∂fm ∂fm
∂x1 ... ∂xm
∂f1
∂x1 is the partial derivative of the first row of f with respect to the first row of x, and so on for all
rows of f and x. This has m2 permutations and thus produces a square matrix.
The Jacobian of f with respect to u is
∂f1 ∂f1
...
∂f (x, u) h ∂f (x,u) i ∂u1 ∂un
..
= ∂u1 ... ∂f (x,u)
∂un
= ... ..
. .
∂u ∂fm ∂fm
∂u1 ... ∂un
∂f1
∂u1 is the partial derivative of the first row of f with respect to the first row of u, and so on for all
rows of f and u. This has m × n permutations and can produce a nonsquare matrix if m ̸= n.
5.12.2 Hessian
The Hessian is the second-order partial derivative of a vector-valued function with respect to one of
its vector arguments. For example, the Hessian of f with respect to x is
∂ 2 f1 ∂ 2 f1
...
∂ 2 f (x, u) h ∂ 2 f (x,u) i ∂x21 ∂x2m
. ..
= ..
∂ 2 f (x,u)
= ... . .
∂x2 ∂x21 ∂x2m . .
∂ 2 fm ∂ 2 fm
∂x21
... ∂x2m
∂xT Ax
Theorem 5.12.1 ∂x = 2Ax where A is symmetric.
∂(Ax+b)T C(Dx+e)
Theorem 5.12.2 ∂x = AT C(Dx + e) + DT CT (Ax + b)
5.12 Matrix calculus 31
∂(Ax+b)T C(Ax+b)
Corollary 5.12.3 ∂x = 2AT C(Ax + b) where C is symmetric.
Proof:
∂(Ax + b)T C(Ax + b)
= AT C(Ax + b) + AT CT (Ax + b)
∂x
∂(Ax + b)T C(Ax + b)
= (AT C + AT CT )(Ax + b)
∂x
C is symmetric, so
When we want to command a system to a set of states, we design a controller with certain control laws
to do it. PID controllers use the system outputs with proportional, integral, and derivative control
laws. In state-space, we also have knowledge of the system states so we can do better.
Modern control theory uses state-space representation to model and control systems. State-space
representation models systems as a set of state, input, and output variables related by first-order
differential equations that describe how the system’s state changes over time given the current states
and inputs.
teams test basic functionality in simulation much earlier in the build season and tune their feedback
controllers automatically.
where ω is the angular velocity and ωmax is the maximum angular velocity. If DC brushed motors
are said to behave linearly, then why is this?
Linearity refers to a system’s equations of motion, not its time domain response. The equation defin-
ing the motor’s change in angular velocity over time looks like
ω̇ = −aω + bV
where ω̇ is the derivative of ω with respect to time, V is the input voltage, and a and b are constants
specific to the motor. This equation, unlike the one shown before, is actually linear because it only
consists of multiplications and additions relating the input V and current state ω.
Also of note is that the relation between the input voltage and the angular velocity of the output
shaft is a linear regression. You’ll see why if you model a DC brushed motor as a voltage source
and generator producing back-EMF (in the equation above, bV corresponds to the voltage source
and −aω corresponds to the back-EMF). As you increase the input voltage, the back-EMF increases
linearly with the motor’s angular velocity. If there was a friction term that varied with the angular
velocity squared (air resistance is one example), the relation from input to output would be a curve.
Friction that scales with just the angular velocity would result in a lower maximum angular velocity,
but because that term can be lumped into the back-EMF term, the response is still linear.
6.3.2 Definition
Below is the continuous version of state-space notation.
ẋ = Ax + Bu (6.1)
y = Cx + Du (6.2)
The change in state and the output are linear combinations of the state vector and the input vector.
The A and B matrices are used to map the state vector x and the input vector u to a change in the
state vector ẋ. The C and D matrices are used to map the state vector x and the input vector u to
an output vector y.
So the system tends toward the equilibrium point (i.e., it’s stable) if λj < 0 for all j.
[1]
Section 7.3 will explain why the matrix exponential eAt shows up here.
[2]
We’re handwaving why this is the case, but it’s a consequence of eAt being diagonalizable.
36 Chapter 6. Continuous state-space control
Now let’s consider when the eigenvalues are complex numbers. What does that mean for the system
response? Let λj = aj + bj i. Each of the exponential terms in the solution can be written as
Therefore,
eλj t = eaj t (cos(bj t) + i sin(bj t))
When the eigenvalue’s imaginary part bj ̸= 0, it contributes oscillation to the real part’s response.
The eigenvalues of A are called poles.[4] Figure 6.1 shows the impulse responses in the time domain
for systems with various pole locations in the complex plane (real numbers on the x-axis and imaginary
numbers on the y-axis). Each response has an initial condition of 1.
Im
Stable Unstable
t
t
t
LHP RHP
t
t t
Re
t t t
Poles in the left half-plane (LHP) are stable; the system’s output may oscillate but it converges to
steady-state. Poles on the imaginary axis are marginally stable; the system’s output oscillates at a
constant amplitude forever. Poles in the right half-plane (RHP) are unstable; the system’s output
grows without bound.
R Imaginary poles always come in complex conjugate pairs (e.g., −2 + 3i, −2 − 3i).
[3]
Euler’s formula may seem surprising at first, but it’s rooted in the fact that complex exponentials are rotations in the
complex plane around the origin. If you can imagine walking around the unit circle traced by that rotation, you’ll notice
the real part of your position oscillates between −1 and 1 over time. That is, complex exponentials manifest as oscillations
in real life. Watch the “What is Euler’s formula actually saying? | Ep. 4” video from 3Blue1Brown’s Lockdown live math
series [2] for a more in-depth explanation of Euler’s formula.
[4]
This name comes from classical control theory. See subsection E.2.2 for more.
6.5 Closed-loop controller 37
ẋ = Ax + BK(r − x)
ẋ = Ax + BKr − BKx
ẋ = (A − BK)x + BKr (6.3)
Now for the output equation. Substitute the control law into equation (6.2).
y = Cx + D(K(r − x))
y = Cx + DKr − DKx
y = (C − DK)x + DKr (6.4)
Instead of commanding the system to a state using the vector u directly, we can now specify a vector
of desired states through r and the controller will choose values of u for us over time that drive the
system toward the reference.
The eigenvalues of A − BK are the poles of the closed-loop system. Therefore, the rate of conver-
gence and stability of the closed-loop system can be changed by moving the poles via the eigenvalues
of A − BK. A and B are inherent to the system, but K can be chosen arbitrarily by the controller
designer. For equation (6.3) to reach steady-state, the eigenvalues of A−BK must be in the left-half
plane. There will be steady-state error if Ar ̸= 0.
Matrix augmentation is the process of appending rows or columns to a matrix. In state-space, there
are several common types of augmentation used: plant augmentation, controller augmentation, and
observer augmentation.
6.6.5 Examples
Snippet 6.1 shows how one packs together the following augmented matrix in Python using np.block().
A B
C D
[5]
Observers use a matrix K to steer the state estimate toward the true state in the same way controllers use a matrix
K to steer the current state toward a desired state. We’ll cover this in more detail in part III.
6.7 Integral control 39
import numpy as np
Snippet 6.2 shows how one packs together the same augmented matrix in Python using array slices.
import numpy as np
Section 6.7 demonstrates model augmentation for different types of integral control.
Second, unconstrained integral control is a poor choice for modeled dynamics compensation. Feed-
forwards provide more precise compensation since we already know beforehand how to counteract
the undesirable dynamics.
Third, unconstrained integral control is a poor choice for unmodeled dynamics compensation. To
choose proper gains, the integrator must be tuned online when the unmodeled dynamics are present,
which may be inconvenient or unsafe in some circumstances. Furthermore, accumulation even when
the system is following the model means it still compensates for modeled dynamics despite our intent
otherwise. Prefer the approach in subsection 6.7.2.
Implementation
We want to augment the system with an integral term that integrates the error e = r − y = r − Cx.
Z
xI = e dt
ẋI = e = r − Cx
u = K(r − x) − KI xI
r x
u = K KI −
0 xI
ẋ = Ax + B (u + uerror )
ẋ = Ax + Bu + Buerror
ẋ = Ax + Bu + Berror uerror
6.8 Double integrator 41
where Berror is a column vector that maps uerror to changes in the rest of the state the same way B
does for u. Berror is only a column of B if uerror corresponds to an existing input within u.
Given the above equation, we’ll augment the plant as
x˙ A Berror x B
= + u
uerror 0 0 uerror 0
x
y= C 0 + Du
uerror
Notice how the state is augmented with uerror . With this model, the observer will estimate both the
state and the uerror term. The controller is augmented similarly. r is augmented with a zero for the
goal uerror term.
u = K (r − x) − kerror uerror
r x
u = K kerror −
0 uerror
where kerror is a column vector with a 1 in a given row if uerror should be applied to that input or a
0 otherwise.
This process can be repeated for an arbitrary error which can be corrected via some linear combina-
tion of the inputs.
ẋ = v
v̇ = a
T T
We want to put these into the form ẋ = Ax + Bu. Let x = x v and u = a . First, add
missing terms so that all equations have the same states and inputs. Then, sort them by states followed
by inputs.
ẋ = 0x + 1v + 0a
v̇ = 0x + 0v + 1a
6.9 Elevator
This elevator consists of a DC brushed motor attached to a pulley that drives a mass up or down.
42 Chapter 6. Continuous state-space control
R ωp
I ωm
Vemf
m v
V G
r
circuit mechanics
ẋ = v (6.5)
G2 Kt GKt
v̇ = − v+ V (6.6)
Rr2 mK v Rrm
Augment the matrix equation with the position state x, which has the model equation ẋ = v. The
matrix elements corresponding to v will be 1, and the others will be 0 since they don’t appear, so
ẋ = 0x + 1v + 0V . The existing rows will have zeroes inserted where x is multiplied in.
˙ " #
x 0 1 x 0
= 2K + GKt V
v 0 − RrG2 mK t
v
v Rrm
ẋ = Ax + Bu
y = Cx + Du
x
x= y=x u=V
v
" #
0 1 0
A= G2 Kt B= C= 1 0 D=0 (6.7)
0 − Rr2 mKv GKt
Rrm
Therefore, the plant and observer augmentations assume a continuous model and the controller aug-
mentation assumes a discrete controller.
x
xaug = v y = x u = V
uerror
A B B
Aaug = Baug = Caug = C 0 Daug = D (6.8)
01×2 0 0
r
Kaug = K 1 raug = (6.9)
0
This will compensate for unmodeled dynamics such as gravity. However, using a constant voltage
feedforward to counteract gravity is preferred over uerror estimation in this case because it results in
a simpler controller with similar performance.
where B is the motor acceleration term from B and uf f is the voltage feedforward.
Buf f = −(−mg)
Buf f = mg
GKt
uf f = mg
Rrm
Rrm2 g
uf f =
GKt
6.9.4 Simulation
Python Control will be used to discretize the model and simulate it. One of the frccontrol examples[7]
creates and tests a controller for it. Figure 6.3 shows the closed-loop system response.
6.9.5 Implementation
C++ and Java implementations of this elevator controller are available online.[8] [9]
[7]
https://github.com/calcmogul/frccontrol/blob/main/examples/elevator.py
[8]
https://github.com/wpilibsuite/allwpilib/blob/main/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/
cpp/Robot.cpp
[9]
https://github.com/wpilibsuite/allwpilib/blob/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/
examples/statespaceelevator/Robot.java
44 Chapter 6. Continuous state-space control
6.10 Flywheel
This flywheel consists of a DC brushed motor attached to a spinning mass of non-negligible moment
of inertia.
R ωf
I ωm J
Vemf
V G
circuit mechanics
G2 Kt GKt
ω̇ = − ω+ V
Kv RJ RJ
Factor out ω and V into column vectors.
˙ h G2 K i GK
ω = − Kv RJt ω + RJt V
6.10 Flywheel 45
ẋ = Ax + Bu
y = Cx + Du
This will compensate for unmodeled dynamics such as projectiles slowing down the flywheel.
6.10.3 Simulation
Python Control will be used to discretize the model and simulate it. One of the frccontrol examples[10]
creates and tests a controller for it. Figure 6.5 shows the closed-loop system response.
Notice how the control effort when the reference is reached is nonzero. This is a plant inversion
feedforward compensating for the system dynamics attempting to slow the flywheel down when no
voltage is applied.
6.10.4 Implementation
C++ and Java implementations of this flywheel controller are available online.[11] [12]
G2 Kt GKt
ω̇ = − ω+ V
Kv RJ RJ
Next, we’ll derive the current I as an output.
ω
V = IR +
Kv
ω
IR = V −
Kv
1 1
I=− ω+ V
Kv R R
Therefore,
ẋ = Ax + Bu
y = Cx + Du
Notice that in this model, the output doesn’t provide any direct measurements of the state. To esti-
mate the full state (also known as full observability), we only need the outputs to collectively include
linear combinations of every state[13] . We’ll revisit this in chapter 9 with an example that uses range
measurements to estimate an object’s orientation.
[13]
While the flywheel model’s outputs are a linear combination of both the states and inputs, inputs don’t provide new
information about the states. Therefore, they don’t affect whether the system is observable.
6.10 Flywheel 47
The effectiveness of this model’s observer is heavily dependent on the quality of the current sensor
used. If the sensor’s noise isn’t zero-mean, the observer won’t converge to the true state.
where V is the controller’s new input voltage, Vcmd is the old input voltage, Vnominal is the rail voltage
when effects like voltage drop due to current draw are ignored, and Vrail is the real rail voltage.
To drive the model with a more accurate voltage that includes voltage drop, the reciprocal can be
used.
Vrail
V = Vcmd (6.15)
Vnominal
where V is the model’s new input voltage. Note that if both the controller compensation and model
compensation equations are applied, the original voltage is obtained. The model input only drops
from ideal if the compensated controller voltage saturates.
For an explanation of where these equations come from, read section 12.1.
dω
First, we’ll solve for dt in terms of V .
48 Chapter 6. Continuous state-space control
J dω
dt ω
V = R+
Kt Kv
ω J dω
V − = dt R
Kv Kt
dω Kt ω
= V −
dt JR Kv
dω Kt Kt
=− ω +
|{z} V (6.19)
dt
|{z} JRK JR |{z}
|{z}
| {z v} x u
ẋ A B
u = K(r − x)
V = Kp (ωgoal − ω)
Closed-loop models have the form ẋ = (A − BK)x + BKr. Therefore, the closed-loop poles are
the eigenvalues of A − BK.
ẋ = (A − BK)x + BKr
Kt Kt Kt
ω̇ = − − (Kp ) ω + (Kp )(ωgoal )
JRKv JR JR
Kt Kt K p Kt K p
ω̇ = − + ω+ ωgoal
JRKv JR JR
Kt Kp
This closed-loop flywheel model has one pole at − JRK Kt
v
+ JR . It therefore only needs one P
controller to place that pole anywhere on the real axis. A derivative term is unnecessary on an ideal
flywheel. It may compensate for unmodeled dynamics such as accelerating projectiles slowing the
flywheel down, but that effect may also increase recovery time; Kd drives the acceleration to zero
in the undesired case of negative acceleration as well as well as the actually desired case of positive
acceleration.
This analysis assumes that the motor is well coupled to the mass and that the time constant of the
inductor is small enough that it doesn’t factor into the motor equations. The latter is a pretty good
assumption for a CIM motor with the following constants: J = 3.2284×10−6 kg-m2 , b = 3.5077×
10−6 N -m-s, Ke = Kt = 0.0181 V /rad/s, R = 0.0902 Ω, and L = 230 μH. Notice the slight
6.10 Flywheel 49
Figure 6.6: Step response of second-order DC Figure 6.7: Step response of first-order DC
brushed motor plant augmented with position brushed motor plant augmented with position
(L = 230 μH) (L = 0 μH)
wiggle in figure 6.6 compared to figure 6.7. If more mass is added to the motor armature, the response
timescales increase and the inductance matters even less.
Subsection 6.7.2 covers a superior compensation method that avoids zeroes in the controller, doesn’t
act against the desired control action, and facilitates better tracking.
50 Chapter 6. Continuous state-space control
m
R ωarm
l
I ωm
Vemf
V G
circuit mechanics
Augment the matrix equation with the angle state θarm , which has the model equation θ̇arm = ωarm .
The matrix elements corresponding to ωarm will be 1, and the others will be 0 since they don’t appear,
so θ̇arm = 0θarm +1ωarm +0V . The existing rows will have zeroes inserted where θarm is multiplied
in.
˙ " #
θarm 0 1 θarm 0
= G2 Kt + GKt V
ωarm 0 −K v RJ
ωarm RJ
ẋ = Ax + Bu
y = Cx + Du
θarm
x= y = θarm u = V
ωarm
" #
0 1 0
A= G2 Kt B = GKt C= 1 0 D=0 (6.22)
0 − Kv RJ RJ
6.11 Single-jointed arm 51
This will compensate for unmodeled dynamics such as gravity or other external loading from lifted ob-
jects. However, if only gravity compensation is desired, a feedforward of the form uf f = Vgravity cos θ
is preferred where Vgravity is the voltage required to hold the arm level with the ground and θ is the
angle of the arm with the ground.
JBuf f = −(r × F)
JBuf f = −(rF cos θ)
Torque is usually written as rF sin θ where θ is the angle between the r and F vectors, but θ in this
case is being measured from the horizontal axis rather than the vertical one, so the force vector is π4
radians out of phase. Thus, an angle of 0 results in the maximum torque from gravity being applied
rather than the minimum.
The force of gravity mg is applied at the center of the arm’s mass. For a uniform beam, this is
halfway down its length, or L2 where L is the length of the arm.
L
JBuf f = − (−mg) cos θ
2
L
JBuf f = mg cos θ
2
GKt
B= RJ , so
GKt L
J uf f = mg cos θ
RJ 2
52 Chapter 6. Continuous state-space control
RJ L
uf f = mg cos θ
JGKt 2
L Rmg
uf f = cos θ
2 GKt
L
2 can be adjusted according to the location of the arm’s center of mass.
6.11.4 Simulation
Python Control will be used to discretize the model and simulate it. One of the frccontrol examples[14]
creates and tests a controller for it. Figure 6.9 shows the closed-loop system response.
6.11.5 Implementation
C++ and Java implementations of this single-jointed arm controller are available online.[15] [16]
[14]
https://github.com/calcmogul/frccontrol/blob/main/examples/single_jointed_arm.py
[15]
https://github.com/wpilibsuite/allwpilib/blob/main/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/
Robot.cpp
[16]
https://github.com/wpilibsuite/allwpilib/blob/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/
examples/statespacearm/Robot.java
6.12 Controllability and observability 53
where rank is the number of linearly independent rows in a matrix and n is the number of states.
The controllability matrix in equation (6.25) being rank-deficient means the inputs cannot apply trans-
forms along all axes in the state-space; the transformation the matrix represents is collapsed into a
lower dimension.
The condition number of the controllability matrix C is defined as σσmax (C)
min (C)
where σmax is the maxi-
mum singular value[17] and σmin is the minimum singular value. As this number approaches infinity,
one or more of the states becomes uncontrollable. This number can also be used to tell us which actu-
ators are better than others for the given system; a lower condition number means that the actuators
have more control authority.
Alternatively, Z ∞
Tτ
Wc = eAτ BBT eA dτ (6.27)
0
If the solution is positive definite, the system is controllable. The eigenvalues of Wc represent how
controllable their respective states are (larger means more controllable).
6.12.4 Stabilizability
Stabilizability is a weaker form of controllability. A system is considered stabilizable if one of the
following conditions is true:
1. All uncontrollable states can be stabilized
2. All unstable states are controllable
[17]
Singular values are a generalization of eigenvalues for nonsquare matrices.
54 Chapter 6. Continuous state-space control
where rank is the number of linearly independent rows in a matrix and n is the number of states.
The observability matrix in equation (6.29) being rank-deficient means the outputs do not contain
contributions from every state. That is, not all states are mapped to a linear combination in the
output. Therefore, the outputs alone are insufficient to estimate all the states.
The condition number of the observability matrix O is defined as σσmax (O)
min (O)
where σmax is the maxi-
[17]
mum singular value and σmin is the minimum singular value. As this number approaches infinity,
one or more of the states becomes unobservable. This number can also be used to tell us which
sensors are better than others for the given system; a lower condition number means the outputs
produced by the sensors are better indicators of the system state.
Alternatively, Z ∞
T
Wo = eA τ CT CeAτ dτ (6.31)
0
If the solution is positive definite, the system is observable. The eigenvalues of Wo represent how
observable their respective states are (larger means more observable).
6.12.8 Detectability
Detectability is a weaker form of observability. A system is considered detectable if one of the
following conditions is true:
1. All unobservable states are stable
2. All unstable states are observable
This page intentionally left blank
Chaparral by Merril Apartments at UCSC
The complex plane discussed so far deals with continuous systems. In decades past, plants and con-
trollers were implemented using analog electronics, which are continuous in nature. Nowadays, mi-
croprocessors can be used to achieve cheaper, less complex controller designs. Discretization con-
verts the continuous model we’ve worked with so far from a differential equation like
ẋ = x − 3 (7.1)
where xk refers to the value of x at the k th timestep. The difference equation is run with some update
period denoted by T , by ∆T , or sometimes sloppily by dt.[1]
While higher order terms of a differential equation are derivatives of the state variable (e.g., ẍ in
relation to equation (7.1)), higher order terms of a difference equation are delayed copies of the state
variable (e.g., xk−1 with respect to xk in equation (7.2)).
[1]
The discretization of equation (7.1) to equation (7.2) uses the forward Euler discretization method.
58 Chapter 7. Discrete state-space control
Continuous Discrete
(0, 0) (1, 0)
imaginary axis edge of unit circle
(−∞, 0) (0, 0)
Figure 7.1: Mapping of complex plane from continuous (left) to discrete (right)
Figure 7.2: Single poles in various locations in Figure 7.3: Complex conjugate poles in various
discrete plane locations in discrete plane
given sample rate can capture is called the Nyquist frequency, which is half the sample frequency.
This is why recorded audio is sampled at 44.1 kHz. The maximum frequency a typical human can
hear is about 20 kHz, so the Nyquist frequency is 20 kHz and the minimum sampling frequency is
40 kHz. (44.1 kHz in particular was chosen for unrelated historical reasons.)
Frequencies above the Nyquist frequency are folded down across it. The higher frequency and the
folded down lower frequency are said to alias each other.[2] Figure 7.4 demonstrates aliasing.
The effect of these high-frequency aliases can be reduced with a low-pass filter (called an anti-aliasing
filter in this application).
[2] def
The aliases of a frequency f can be expressed as falias (N ) = |f − N fs |. For example, if a 200 Hz sine wave is
sampled at 150 Hz, the observer will see a 50 Hz signal instead of a 200 Hz one.
60 Chapter 7. Discrete state-space control
Figure 7.4: The original signal is a 1.5 Hz sine wave, which means its Nyquist frequency is 1.5 Hz.
The signal is being sampled at 2 Hz, so the aliased signal is a 0.5 Hz sine wave.
time of your system. Some systems like heaters have outputs that change on the order of minutes.
Running a control loop at 1 kHz doesn’t make sense for this because the plant input the controller
computes won’t change much, if at all, in 1 ms.
where w is the process noise, v is the measurement noise, and both are zero-mean white noise sources
with covariances of Qc and Rc respectively. w and v are defined as normally distributed random
variables.
w ∼ N (0, Qc )
v ∼ N (0, Rc )
Discretization is done using a zero-order hold. That is, the input is only updated at discrete intervals
and it’s held constant between samples.
R Watch the “Taylor series” video from 3Blue1Brown’s Essence of calculus series (22 minutes)
[13] for an explanation of how the Taylor series expansion works.
The definition for the matrix exponential and the approximations below all use the Taylor series
expansion. The Taylor series is a method of approximating a function like et via the summation
of weighted polynomial terms like tk . et has the following Taylor series around t = 0.
∞ n
X t
et =
n!
n=0
where a finite upper bound on the number of terms produces an approximation of et . As n increases,
the polynomial terms increase in power and the weights by which they are multiplied decrease. For
et and some other functions, the Taylor series expansion equals the original function for all values of
t as the number of terms approaches infinity.[3] Figure 7.5 shows the Taylor series expansion of et
around t = 0 for a varying number of terms.
We’ll expand the first few terms of the Taylor series expansion in equation (7.3) for X = AT so we
can compare it with other methods.
X
3
1 1 1
(AT )k = I + AT + A2 T 2 + A3 T 3
k! 2 6
k=0
Table 7.2 compares the Taylor series expansions of the discretization methods for the matrix case.
These use a more complex formula which we won’t present here.
Each of them has different stability properties. The bilinear transform preserves the (in)stability of
the continuous time system.
[3]
Functions for which their Taylor series expansion converges to and also equals it are called analytic functions.
62 Chapter 7. Discrete state-space control
Table 7.2: Taylor series expansions of discretization methods (matrix case). The zero-order hold
discretization method is exact.
R Watch the “How (and why) to raise e to the power of a matrix” video from 3Blue1Brown’s
Essence of linear algebra series (27 minutes) [7] for a visual introduction to the matrix expo-
nential.
To understand why the matrix exponential is used in the discretization process, consider the scalar
differential equation ẋ = ax. The solution to this type of differential equation uses an exponential.
ẋ = ax
7.3 Linear system discretization 63
dx
= ax(t)
dt
dx = ax(t) dt
1
dx = a dt
x(t)
Z t Z t
1
dx = a dt
0 x(t) 0
ln(x(t))|t0 = at|t0
ln(x(t)) − ln(x(0)) = at − a · 0
ln(x(t)) − ln(x0 ) = at
x(t)
ln = at
x0
x(t)
= eat
x0
x(t) = eat x0
This solution generalizes via the matrix exponential to the set of differential equations ẋ = Ax +Bu
we use to describe systems.[4]
where x0 contains the initial conditions and u is the constant input from time 0 to t. If the initial
state is the current system state, then we can describe the system’s state over time as
or more compactly,
xk+1 = Ad xk + Bd uk
where T is the time between samples xk and xk+1 . Theorem 7.3.1 has more efficient ways to compute
Ad and Bd .
7.3.3 Definition
The model can be discretized as follows
xk+1 = Ad xk + Bd uk + wk
y k = Cd x k + D d u k + v k
with covariances
wk ∼ N (0, Qd )
vk ∼ N (0, Rd )
[4]
See section D.1 for a complete derivation of the linear system zero-order hold.
64 Chapter 7. Discrete state-space control
A d = e Ac T (7.4)
Z T
Bd = eAc τ dτ Bc = A−1
c (Ad − I)Bc (7.5)
0
Cd = Cc (7.6)
Dd = Dc (7.7)
Z T
T
Qd = eAc τ Qc eAc τ dτ (7.8)
τ =0
1
Rd = Rc (7.9)
T
where subscripts c and d denote matrices for the continuous or discrete systems respectively, T is
the sample period of the discrete system, and eAc T is the matrix exponential of Ac T .
Ad and Bd can be computed in one step as
A Bc
c
T
0 0 A d Bd
e =
0 I
where Qd = ΦT
2,2 Φ1,2 [26].
Now for the output equation. Substitute the control law into equation (7.11).
yk = Cxk + D(K(rk − xk ))
yk = Cxk + DKrk − DKxk
yk = (C − DK)xk + DKrk (7.13)
Instead of commanding the system to a state using the vector uk directly, we can now specify a vector
of desired states through rk and the controller will choose values of uk for us over time that drive
the system toward the reference.
The eigenvalues of A − BK are the poles of the closed-loop system. Therefore, the rate of conver-
gence and stability of the closed-loop system can be changed by moving the poles via the eigenvalues
of A − BK. A and B are inherent to the system, but K can be chosen arbitrarily by the controller
designer. For equation (7.12) to reach steady-state, the eigenvalues of A − BK must be in the
left-half plane. There will be steady-state error if Ark ̸= rk .
66 Chapter 7. Discrete state-space control
Figure 7.6: Mapping of complex plane from continuous (left) to discrete (right)
Pole placement should only be used if you know what you’re doing. It’s much easier to let LQR place
the poles for you, which we’ll discuss next.
where a is a negative constant representing the back-EMF of the motor, x is the angular velocity, b is a
positive constant that maps the input voltage to some change in angular velocity (angular acceleration),
u is the voltage applied to the motor, and ẋ is the angular acceleration. Discretized, this equation
would look like
xk+1 = ad x + bd uk
If the angular velocity starts from zero and we apply a positive voltage, we’d see the motor spin
up to some constant speed following an exponential decay, then stay at that speed. If we throw in
the control law uk = kp (rk − xk ), we can make the system converge to a desired state rk through
proportional feedback. In what manner can we pick the constant kp that balances getting to the target
angular velocity quickly with getting there efficiently (minimal oscillations or excessive voltage)?
We can solve this problem with something called the linear-quadratic regulator. We’ll define the
following cost function that includes the states and inputs:
∞
X
J= (Q(rk − xk )2 + Ru2k )
k=0
We want to minimize this while obeying the constraint that the system follow our flywheel dynamics
xk+1 = ad xk + bd uk .
The cost is the sum of the squares of the error and the input for all time. If the controller gain kp we
pick in the control law uk = kp (rk − xk ) is stable, the error rk − xk and the input uk will both go
to zero and give us a finite cost. Q and R let us decide how much the error and input contribute to
the cost (we will require that Q ≥ 0 and R > 0 for reasons that will be clear shortly[5] ). Penalizing
error more will make the controller more aggressive, while penalizing the input more will make the
controller less aggressive. We want to pick a kp that minimizes the cost.
There’s a common trick for finding the value of a variable that minimizes a function of that variable.
We’ll take the derivative (the slope) of the cost function with respect to the input uk , set the derivative
to zero, then solve for uk . When the slope is zero, the function is at a minimum or maximum. Now,
the cost function we picked is quadratic. All the terms are strictly positive on account of the squared
variables and nonnegative weights, so our cost is strictly positive and the quadratic function is concave
up. The uk we found is therefore a minimum.
The actual process of solving for uk is mathematically intensive and outside the scope of this expla-
nation (appendix B references a derivation for those curious). The rest of this section will describe
the more general form of the linear-quadratic regulator and how to use it.
where J represents a trade-off between state excursion and control effort with the weighting factors
Q and R. LQR is a control law u that minimizes the cost functional. Figure 7.7 shows the optimal
cost-to-go for an elevator model. Pole placement, on the other hand, will have a cost-to-go above this
for an arbitrary state vector (in this case, an arbitrary position-velocity pair).
The cost-to-go looks effectively constant along the velocity axis because the velocity is contributing
much less to the cost-to-go than position.[6] In other words, it’s much more expensive to correct for
a position error than a velocity error. This difference in cost is reflected by LQR’s selected position
feedback gain of Kp = 234.041 and selected velocity feedback gain of Kd = 5.603.
The minimum of LQR’s cost functional is found by setting the derivative of the cost functional to
zero and solving for the control law uk . However, matrix calculus is used instead of normal calculus
to take the derivative.
The feedback control law that minimizes J is shown in theorem 7.7.1.
If the system is controllable, the optimal control policy u∗k that drives all the states to zero is −Kxk .
To converge to nonzero states, a reference vector rk can be added to the state xk .
uk = K(rk − xk ) (7.15)
[6]
While it may not look like it at this scale, the elevator’s cost-to-go along both state axes is strictly increasing away
from the origin (convex upward). This means there’s a global minimum at the origin, and the system is globally stable; no
matter what state you start from, you’re guaranteed to reach the origin with this controller.
7.7 Linear-quadratic regulator 69
This means that optimal control can be achieved with simply a set of proportional gains on all the
states. To use the control law, we need knowledge of the full state of the system. That means we
either have to measure all our states directly or estimate those we do not measure.
See appendix B for how K is calculated. If the result is finite, the controller is guaranteed to be stable
and robust with a phase margin of 60 degrees [38].
R LQR design’s Q and R matrices don’t need discretization, but the K calculated for contin-
uous time and discrete time systems will be different. The discrete time gains approach the
continuous time gains as the sample period tends to zero.
The index subscript denotes a row of the state or input vector. Small values of ρ penalize control
effort while large values of ρ penalize state excursions. Large values would be chosen in applications
like fighter jets where performance is necessary. Spacecrafts would use small values to conserve their
limited fuel supply.
Figure 7.8 shows the response using various discrete pole placements and using LQR with the fol-
lowing cost matrices.
1
0
Q= 20 2
R = 1212
0 0
With Bryson’s rule, this means an angular velocity tolerance of 20 rad/s, an infinite current tolerance
(in other words, we don’t care what the current does), and a voltage tolerance of 12 V.
Notice with pole placement that as the current pole moves toward the origin, the control effort be-
comes more aggressive.
70 Chapter 7. Discrete state-space control
Figure 7.8: Second-order CIM motor response with pole placement and LQR
7.8 Feedforward
There are two types of feedforwards: model-based feedforward and feedforward for unmodeled
dynamics. The first solves a mathematical model of the system for the inputs required to meet desired
velocities and accelerations. The second compensates for unmodeled forces or behaviors directly so
the feedback controller doesn’t have to. Both types can facilitate simpler feedback controllers; we’ll
cover examples of each.
u(t)
r(t) y(t)
where uk is the feedforward input. Note that this feedforward equation does not and should not take
into account any feedback terms. We want to find the optimal uk such that we minimize the tracking
error between rk+1 and rk .
rk+1 − Ark = Buk
To solve for uk , we need to take the inverse of the nonsquare matrix B. This isn’t possible, but we
can find the pseudoinverse given some constraints on the state tracking error and control effort. To
find the optimal solution for these sorts of trade-offs, one can define a cost function and attempt to
minimize it. To do this, we’ll first solve the expression for 0.
This expression will be the state tracking cost we use in the following cost function as an H2 norm.
Minimization
Given theorem 5.12.1, find the minimum of J by taking the partial derivative with respect to uk and
setting the result to 0.
∂J
= 2BT (Buk − (rk+1 − Ark ))
∂uk
0 = 2BT (Buk − (rk+1 − Ark ))
0 = 2BT Buk − 2BT (rk+1 − Ark )
2BT Buk = 2BT (rk+1 − Ark )
BT Buk = BT (rk+1 − Ark )
uk = (BT B)−1 BT (rk+1 − Ark )
Theorem 7.8.1 — Linear plant inversion. Given the discrete model xk+1 = Axk + Buk ,
the plant inversion feedforward is
where B+ is the Moore-Penrose pseudoinverse of B, rk+1 is the reference at the next timestep,
and rk is the reference at the current timestep.
Discussion
Linear plant inversion in theorem 7.8.1 compensates for reference dynamics that don’t follow how
the model inherently behaves. If they do follow the model, the feedforward has nothing to do as
the model already behaves in the desired manner. When this occurs, rk+1 − Ark will return a zero
vector.
For example, a constant reference requires a feedforward that opposes system dynamics that would
change the state over time. If the system has no dynamics, then A = I and thus
uk = B+ (rk+1 − Irk )
72 Chapter 7. Discrete state-space control
uk = B+ (rk+1 − rk )
uk = B+ (rk − rk )
uk = B+ (0)
uk = 0
uk = Vapp (7.17)
where Vapp is a constant. Another feedforward holds a single-jointed arm steady in the presence of
gravity. It has the following form.
where Vapp is the voltage required to keep the single-jointed arm level with the ground, and θ is
the angle of the arm relative to the ground. Therefore, the force applied is greatest when the arm is
parallel with the ground and zero when the arm is perpendicular to the ground (at that point, the joint
supports all the weight).
7.9 Numerical integration methods 73
Note that the elevator model could be augmented easily enough to include gravity and still be linear,
but this wouldn’t work for the single-jointed arm since a trigonometric function is required to model
the gravitational force in the arm’s rotating reference frame.[7]
The multiplicative term on xk is still A−BK, so the feedforward didn’t affect stability. It still affects
the system response and steady-state error though.
where s is the number of stages in the method, the matrix [aij ] is the Runge-Kutta matrix, b1 , . . . , bs
are the weights, and c1 , . . . , cs are the nodes. The top-left quadrant contains the sums of the rows in
the top-right quadrant. Each column in the right half corresponds to a k coefficient from k1 to ks .
[7]
While the applied torque of the motor is constant throughout the arm’s range of motion, the torque caused by gravity
in the opposite direction varies according to the arm’s angle.
74 Chapter 7. Discrete state-space control
k1 = f (tk , xk )
k2 = f (tk + c2 h, xk + h(a2,1 k1 ))
..
.
ks = f (tk + cs h, xk + h(as,1 k1 + . . . + as,s−1 ks−1 ))
Xs
xk+1 = xk + h bi k i
i=1
k1 = f (t+0h,xk ) 0
xk+1 = xk + h(1k1 ) 1
Remove zeroed out terms.
k1 = f (t, xk )
xk+1 = xk + hk1
Simplify.
xk+1 = xk + hf (t, xk )
In FRC, our differential equations are of the form ẋ = f (x, u) where u is held constant between
timesteps. Since it’s time-invariant, we can ignore the time argument of the integration method. This
gives theorem 7.9.1.
Theorem 7.9.1 — Forward Euler integration. Given the differential equation ẋ = f (xk , uk ),
this method solves for xk+1 at h seconds in the future. u is assumed to be held constant between
timesteps.
0
xk+1 = xk + hf (xk , uk )
1
k1 = f (t+0h, xk )
1 1 0
k2 = f (t+ h,xk + h( k1 )) 1 1
2 2 2 2
1 1 1
0 1
k3 = f (t+ h,xk + h(0k1 + k2 )) 2 2
2 2
1 0 0 1
k4 = f (t+1h, xk + h(0k1 + 0k2 + 1k3 ))
1 1 1 1
1 1 1 1 6 3 3 6
xk+1 = xk + h( k1 + k2 + k3 + k4 )
6 3 3 6
Remove zeroed out terms.
k1 = f (t, xk )
1 1
k2 = f (t + h, xk + h k1 )
2 2
1 1
k3 = f (t + h, xk + h k2 )
2 2
k4 = f (t + h, xk + hk3 )
1 1 1 1
xk+1 = xk + h k1 + k2 + k3 + k4
6 3 3 6
1
6 is usually factored out of the last equation to reduce the number of floating point operations.
1
xk+1 = xk + h (k1 + 2k2 + 2k3 + k4 )
6
In FRC, our differential equations are of the form ẋ = f (x, u) where u is held constant between
timesteps. Since it’s time-invariant, we can ignore the time argument of the integration method. This
gives theorem 7.9.2.
k1 = f (xk , uk )
1 0
k2 = f (xk + h k1 , uk ) 1 1
2 2 2
1 1
0 1
k3 = f (xk + h k2 , uk ) 2 2
2
1 0 0 1
k4 = f (xk + hk3 , uk )
1 1 1 1
1 6 3 3 6
xk+1 = xk + h (k1 + 2k2 + 2k3 + k4 )
6
/**
* Performs 4th order Runge-Kutta integration of dx/dt = f(x, u) for dt.
*
* @param f The function to integrate. It must take two arguments x and u.
76 Chapter 7. Discrete state-space control
T k1 = f(x, u);
T k2 = f(x + h * 0.5 * k1, u);
T k3 = f(x + h * 0.5 * k2, u);
T k4 = f(x + h * k3, u);
Other methods of Runge-Kutta integration exist with various properties [16], but the one presented
here is popular for its high accuracy relative to the amount of floating point operations (FLOPs) it
requires.
0
1 1
5 5
3 3 9
10 40 40
4
5
44
45 − 56
15
32
9
8
9
19372
6561 − 25360
2187
64448
6561 − 212
729
1 9017
3168 − 355
33
46732
5247
49
176 − 18656
5103
1 35
384 0 500
1113
125
192 − 2187
6784
11
84
35
384 0 500
1113
125
192 − 2187
6784
11
84 0
5179
57600 0 7571
16695
393
640 − 339200
92097 187
2100
1
40
The first row of coefficients below the table divider gives the fifth-order accurate solution. The
second row gives an alternative solution which, when subtracted from the first solution, gives the
error estimate.
#include <Eigen/Core>
#include <units/time.h>
7.9 Numerical integration methods 77
/**
* Performs adaptive Dormand-Prince integration of dx/dt = f(x, u) for dt.
*
* @param f The function to integrate. It must take two arguments x
and
* u.
* @param x The initial value of x.
* @param u The value u held constant over the integration period.
* @param dt The time over which to integrate.
* @param maxError The maximum acceptable truncation error. Usually a small
* number like 1e-6.
*/
template <typename F, typename T, typename U>
T RKDP(F&& f, T x, U u, units::second_t dt, double maxError = 1e-6) {
// See https://en.wikipedia.org/wiki/Dormand%E2%80%93Prince_method for the
// Butcher tableau the following arrays came from.
// clang-format off
constexpr double A[kDim - 1][kDim - 1]{
{ 1.0 / 5.0},
{ 3.0 / 40.0, 9.0 / 40.0},
{ 44.0 / 45.0, -56.0 / 15.0, 32.0 / 9.0},
{19372.0 / 6561.0, -25360.0 / 2187.0, 64448.0 / 6561.0, -212.0 /
729.0},
{ 9017.0 / 3168.0, -355.0 / 33.0, 46732.0 / 5247.0, 49.0 / 176.0,
-5103.0 / 18656.0},
{ 35.0 / 384.0, 0.0, 500.0 / 1113.0, 125.0 / 192.0,
-2187.0 / 6784.0, 11.0 / 84.0}};
// clang-format on
T newX;
double truncationError;
// clang-format off
T k1 = f(x, u);
T k2 = f(x + h * (A[0][0] * k1), u);
T k3 = f(x + h * (A[1][0] * k1 + A[1][1] * k2), u);
T k4 = f(x + h * (A[2][0] * k1 + A[2][1] * k2 + A[2][2] * k3), u);
T k5 = f(x + h * (A[3][0] * k1 + A[3][1] * k2 + A[3][2] * k3 + A[3][3]
* k4), u);
T k6 = f(x + h * (A[4][0] * k1 + A[4][1] * k2 + A[4][2] * k3 + A[4][3]
78 Chapter 7. Discrete state-space control
// Since the final row of A and the array b1 have the same coefficients
// and k7 has no effect on newX, we can reuse the calculation.
newX = x + h * (A[5][0] * k1 + A[5][1] * k2 + A[5][2] * k3 +
A[5][3] * k4 + A[5][4] * k5 + A[5][5] * k6);
T k7 = f(newX, u);
dtElapsed += h;
x = newX;
}
return x;
}
8. Nonlinear control
While many tools exist for designing controllers for linear systems, all systems in reality are inherently
nonlinear. We’ll briefly mention some considerations for nonlinear systems.
8.1 Introduction
Recall from linear system theory that we defined systems as having the following form:
ẋ = Ax + Bu + w
y = Cx + Du + v
In this equation, A and B are constant matrices, which means they are both time-invariant and linear
(all transformations on the system state are linear ones, and those transformations remain the same
for all time). In nonlinear and time-variant systems, the state evolution and output are defined by
arbitrary functions of the current states and inputs.
ẋ = f (x, u, w)
y = h(x, u, v)
Nonlinear functions come up regularly when attempting to control the pose of a vehicle in the global
coordinate frame instead of the vehicle’s rotating local coordinate frame. Converting from one to
the other requires applying a rotation matrix, which consists of sine and cosine operations. These
functions are nonlinear.
8.2 Linearization
One way to control nonlinear systems is to linearize the model around a reference point. Then, all
the powerful tools that exist for linear controls can be applied. This is done by taking the Jacobians
80 Chapter 8. Nonlinear control
of f and h with respect to the state and input vectors. See section 5.12 for more on Jacobians.
Linearization of a nonlinear equation is a Taylor series expansion to only the first-order terms (that
is, terms whose variables have exponents on the order of x1 ). This is where the small angle approxi-
mations for sin θ and cos θ (θ and 1 respectively) come from.
Higher order partial derivatives can be added to better approximate the nonlinear dynamics. We typi-
cally only linearize around equilibrium points[1] because we are interested in how the system behaves
when perturbed from equilibrium. An FAQ on this goes into more detail [21]. To be clear though,
linearizing the system around the current state as the system evolves does give a closer approximation
over time.
Note that linearization with static matrices (that is, with a time-invariant linear system) only works
if the original system in question is feedback linearizable.
V (x) > 0
V (0) = 0
dV ∂V dx
V̇ (x) = = ≤0
dt ∂x dt
More than one Lyapunov function can prove stability, and if one function doesn’t prove it, another
candidate should be tried. For this reason, we refer to these functions as Lyapunov candidate func-
tions.
[1]
Equilibrium points are points where ẋ = 0. At these points, the system is in steady-state.
8.4 Affine systems 81
For this function to be negative definite, AT P + PA must be negative definite. Since P is positive
definite, the only way to satisfy that condition is if A is negative definite (i.e., A is stable).
An affine system is a linear system with a constant offset in the dynamics. If (x0 , u0 ) is an equilibrium
point, f (x0 , u0 ) = 0, the resulting model is linear, and LQR works as usual. If (x0 , u0 ) is, say, the
current operating point rather than an equilibrium point, the easiest way to correctly apply LQR is
1. Find a control input u0 that makes (x0 , u0 ) an equilibrium point.
2. Obtain an LQR for the linearized system.
3. Add u0 to the LQR’s control input.
A control-affine system is of the form ẋ = f (x) + g(x)u. Since it has separable control inputs, u0
can be derived via plant inversion as follows.
ṙ = f (x) + Bu
Bu = ṙ − f (x)
u = B+ (ṙ − f (x)) (8.3)
rk+1 −rk
R To use equation (8.3) in a discrete controller, one can approximate ṙ with T where T is
the time period between the two references.
8.5 Pendulum
8.5.1 State-space model
Below is the model for a pendulum
g
θ̈ = − sin θ
l
where θ is the angle of the pendulum and l is the length of the pendulum.
Since state-space representation requires that only single derivatives be used, they should be broken up
as separate states. We’ll reassign θ̇ to be ω so the derivatives are easier to keep straight for state-space
representation.
g
ω̇ = − sin θ
l
Now separate the states.
θ̇ = ω
g
ω̇ = − sin θ
l
T
This makes our state vector θ ω and our nonlinear model the following.
ω
f (x, u) =
− gl sin θ
Linearization around θ = 0
To apply our tools for linear control theory, the model must be a linear combination of the states and
inputs (addition and multiplication by constants). Since this model is nonlinear on account of the sine
function, we should linearize it.
Linearization finds a tangent line to the nonlinear dynamics at a desired point in the state-space.
The Taylor series is a way to approximate arbitrary functions with polynomials, so we can use it for
linearization.
The taylor series expansion for sin θ around θ = 0 is θ − 16 θ3 + 1 5
120 θ − . . .. We’ll take just the
first-order term θ to obtain a linear function.
θ̇ = ω
8.5 Pendulum 83
g
ω̇ = − θ
l
Now write the model in state-space representation. We’ll write out the system of equations with the
zeroed variables included to assist with this.
θ̇ = 0θ + 1ω
g
ω̇ = − θ + 0ω
l
Factor out θ and ω into a column vector.
˙
θ 0 1 θ
= (8.4)
ω − gl 0 ω
If we want to linearize around an arbitrary point, we can take the Jacobian with respect to x.
∂f (x, u) 0 1
=
∂x − gl cos θ 0
For full state feedback, knowledge of all states is required. If not all states are measured directly, an
estimator can be used to supplement them.
We may only be measuring θ in the pendulum example, not θ̇, so we’ll need to estimate the latter.
The C matrix the observer would use in this case is
C= 1 0
y = Cx
θ
y= 1 0
ω
y = 1θ + 0ω
y=θ
ẋ = Ax
y = Cx
θ
x= y=θ
ω
0 1
A= C= 1 0 (8.5)
− gl cos θ 0
84 Chapter 8. Nonlinear control
where vx,chassis is the velocity ahead in the chassis frame, vy,chassis is the velocity to the left in
the chassis frame, and ωchassis is the angular velocity in the chassis frame. This can be written in
state-space notation as
˙
x 0 0 0 x cos θ − sin θ 0 vx,chassis
y = 0 0 0 y + sin θ cos θ 0 vy,chassis
θ 0 0 0 θ 0 0 1 ωchassis
8.6.2 Control
This control-affine model is fully actuated but nonlinear in the chassis frame. However, we can apply
linear control theory to the error dynamics in the global frame instead. Note how equation (8.6)’s state
vector contains the global pose and its input vector contains the global linear and angular velocities.
˙
x 0 0 0 x 1 0 0 vx,global
y = 0 0 0 y + 0 1 0 vy,global (8.6)
θ 0 0 0 θ 0 0 1 ωglobal
vx,global cos θ − sin θ 0 vx,chassis
where vy,global = sin θ cos θ 0 vy,chassis (8.7)
ωglobal 0 0 1 ωchassis
We can control the model in equation (8.6) with an LQR, which will have three independent propor-
tional controllers. Then, we can convert the global velocity commands to chassis velocity commands
with equation (8.7) and convert the chassis velocity commands to wheel speed commands with in-
verse kinematics. LQRs on each wheel can track the wheel speed commands.
Note that the full control law is nonlinear because the kinematics contain a rotation matrix for trans-
forming from the chassis frame to the global frame. However, the nonlinear part has been abstracted
away from the tunable linear control laws.
R Nonholonomic controllers should not be used for holonomic drivetrains. They make different
assumptions about the drivetrain dynamics that yield suboptimal results compared to holonomic
controllers.
8.7 Differential drive 85
vr
ωl ωr vl
J
r +x
rb θ
Factor out vl and vr into a column vector and Vl and Vr into a column vector.
˙ rb2 rb2 rb2 rb2
vl
1
+ C 1
1
− C 3 v
1
+ C 2
1
− J C 4 Vl
= m l + m m
m J J J
r 2 r 2 r 2 rb2
vr vr Vr
m − J C1 m − J C2
1 1 1 1
m + J C3 m + J C4
b b b
86 Chapter 8. Nonlinear control
ẋ = Ax + Bu
y = Cx + Du
vl vl V
x= y= u= l
vr vr Vr
rb2 rb2 rb2 rb2
1
+ J C1
1
− C 3
1
+ C 2
1
− J C4
A= m m J
B = m J
m
rb2 r 2 r 2 rb2
− 1
J C1
1
m + J C3
b
m − J C2
1 b 1
m + J C4 (8.8)
m
1 0
C= D = 02×2
0 1
G2 K 2
where C1 = − KvlRrt2 , C2 = G l Kt
Rr , C3 = − KGvrRr
Kt
2 , and C4 =
Gr Kt
Rr .
Simulation
Python Control will be used to discretize the model and simulate it. One of the frccontrol examples[2]
creates and tests a controller for it. Figure 8.3 shows the closed-loop system response.
Given the high inertia in drivetrains, it’s better to drive the reference with a motion profile instead of
a step input for reproducibility.
[2]
https://github.com/calcmogul/frccontrol/blob/main/examples/differential_drive.py
8.7 Differential drive 87
ẋ = Ax + Bu
y = Cx + Du
T T T
x = θ v l vr y = θ v l vr u = V l Vr
0 − 2r1b 1
0 0
2rb
1 r2 rb2
rb2 r2
A= 0 1
+ J C1
1
− Jb C3 B = m + Jb C2 1
− C4
m m m J
(8.9)
rb2 r2 rb2 rb2
0 m −
1
J C1
1
m + Jb C3 1
m − J C 2
1
m + J C4
C = I3×3 D = 03×2
G2 K 2
where C1 = − KvlRrt2 , C2 = GRr l Kt
, C3 = − KGvrRr
Kt
2 , and C4 =
Gr Kt
Rr . The constants C1 through
C4 are from the derivation in section 12.6.
T
This augmented model is a nonlinear vector function where x = x y θ vl vr and u =
T
Vl V r .
vr
2 cos θ + v2l cos θ
vr
sin θ + v2l sin θ
2
vr
− vl
f (x, u) =
1
rb2
r 2
2rb 2rb
r2
rb2
(8.10)
m+ J C1 vl + 1
− Jb C3 vr + m 1
+ Jb C2 Vl + m1
− C 4 r
V
m J
rb2 r 2 r 2 rb2
m − − Jb C2 Vl + m
1 1 1 1
J C1 vl + m + Jb C3 vr + m + J C V
4 r
As mentioned in chapter 8, one can approximate a nonlinear system via linearizations around points
of interest in the state-space and design controllers for those linearized subspaces. If we sample
linearization points progressively closer together, we converge on a control policy for the original
nonlinear system. Since the linear plant being controlled varies with time, its controller is called a
linear time-varying (LTV) controller.
If we use LQRs for the linearized subspaces, the nonlinear control policy will also be locally optimal.
We’ll be taking this approach with a differential drive. To create an LQR, we need to linearize
88 Chapter 8. Nonlinear control
equation (8.10).
0 0 − vl +v r
2 sin θ
1
2 cos θ 1
2 cos θ
0 0 vl +vr 1 1
2 cos θ 2 sin θ 2 sin θ
∂f (x, u) 0 0 0 − 2rb
1 1
=
r 2
2rb
rb2
∂x 0 0 0 1
+ Jb C1 1
− C 3
m m J
r2 rb2
0 0 0 1
m − Jb C1 1
m + J C 3
0 0
0 0
∂f (x, u)
0 0
=
∂u rb2 rb2
m 1
+ J C2 m − J C4
1
rb2 rb2
1
m − J C 2
1
m + J C 4
Therefore,
ẋ = Ax + Bu
y = Cx + Du
T T T
x = x y θ v l vr y = θ v l vr u = V l Vr
0 0 −vs 1
2c
1
2c 0 0
0 0 vc 1 1
2s 2s 0 0
0 0 0 − 2r1b 1 0 0
A=
r2
2rb
r 2
B =
r 2
r 2
0 0 0 1
+ Jb C1 1
− Jb C3 m1
+ Jb C2 1
− Jb C4
m m m
r2 r2 rb2 rb2
0 0 0 1
− Jb C1 1
+ Jb C3 1
m − J C 2
1
m + J C4
m
m
0 0 1 0 0
C= 0 0 0 1 0 D = 03×2
0 0 0 0 1
(8.11)
G2 K Gr Kt 2
where v = vl +v2 , c = cos θ, s = sin θ, C1 = − Kv Rr 2 , C2 = Rr , C3 = − Kv Rr 2 , and
r l t Gl Kt
C4 = GRr
r Kt
. The constants C1 through C4 are from the derivation in section 12.6.
We can also use this in an extended Kalman filter as is since the measurement model (y = Cx+Du)
is linear.
being nonzero.
0 0 − vl +v r
2 cos θ 0 0
0 0 − 2 sin θ
vl +vr
0 0
∂ 2 f (x, u)
=
0 0 0 0 0
∂x2 0 0 0 0 0
0 0 0 0 0
∂f (x, u) 1 ∂ 2 f (x, u)
f (x, u0 ) ≈ f (x0 , u0 ) + (x − x0 ) + (x − x0 )2
∂x 2 ∂x2
To include higher-order dynamics in the linearized differential drive model integration, we’ll apply
the Dormand-Prince integration method (RKDP) from theorem 7.9.3 to equation (8.10).
Figures 8.6 and 8.7 show a simulation using RKDP instead of the first-order model.
where the the superscript R represents the robot’s coordinate frame and the superscript G represents
the global coordinate frame.
With this transformation, the x and y error cost in LQR penalize the error ahead of the robot and cross-
track error respectively instead of global pose error. Since the cross-track error is always measured
from the robot’s coordinate frame, the model used to compute the LQR should be linearized around
θ = 0 at all times.
0 0 − vl +v r
2 sin 0
1
2 cos 0
1
2 cos 0
0 0 vl +vr cos 0 1 1
2 2 sin 0 2 sin 0
0 0 0 − 1 1
A= 2r b 2r b
r 2 r 2
0 0 0 1
+ J C1
b 1
− J C3
b
m
m
rb2 rb2
0 0 0 1
m − J C 1
1
m + J C3
1 1
0 0 0 2 2
0 0 l r v +v
0 0
2
0 0 0 − 2rb1 1
A= 2r
b
rb2 rb2
0 0 0 1
+ C 1
− C 3
m J
1
m J
rb2 rb2
0 0 0 1
m − J C 1
1
m + J C 3
8.7 Differential drive 91
Theorem 8.7.4 — Linear time-varying differential drive controller. Let the differential drive
T T
dynamics be of the form ẋ = f (x) + Bu where x = x y θ vl vr , u = Vl Vr , and
(x)
A = ∂f∂x .
θ=0
1 1
0 0 0 2 2 0 0
0 0 v 0 0 0 0
0 0 0 − 2r1b 1 0 0
A=
rb2
2rb
rb2
B=
1 2
rb
r 2
0 0 0 1
+ J C1 1
− J C3 m+ J C2
1
− Jb C4
m m m
rb2 rb2 rb2 r2
m −
1 1
0 0 0 1
m − J C1 1
m + J C3 J C2 m + Jb C4
(8.12)
G2 K G r Kt2
2 , C1 = − Kv Rr 2 , C2 = Rr , C3 = − Kv Rr 2 , and C4 =
where v = vl +v l t Gl Kt G r Kt
Rr . The constants
r
At each timestep, the LQR controller gain K is computed for the (A, B) pair evaluated at the
current state.
With the model in theorem 8.7.4, y is uncontrollable at v = 0 because the row corresponding to y
becomes the zero vector. This means the state dynamics and inputs can no longer affect y. This is
obvious given that nonholonomic drivetrains can’t move sideways. Some DARE solvers throw errors
in this case, but one can avoid it by linearizing the model around a slightly nonzero velocity instead.
The controller in theorem 8.7.4 results in figures 8.8 and 8.9, which show slightly better tracking
performance than the previous formulation.
T
This produces the following linear subspace over x = vl vr xl xr .
rb2 rb2 rb2 rb2
1
+ J C1
1
− J C3 0 0 1
+ J C2
1
− J C4
m m m m
1 rb2 rb2 1 rb2 rb2
A= m − J C1
1
+ J C3 0 0 B= m − J C2
1
+ J C4 (8.14)
m m
1 0 0 0 0 0
0 1 0 0 0 0
T
The measurement model for the complete nonlinear model is now y = θ xl xr instead of
T
y = θ v l vr .
U error estimation
As per subsection 6.7.2, we will now augment the model so uerror states are added to the control
inputs.
The plant and observer augmentations should be performed before the model is discretized. After the
controller gain is computed with the unaugmented discrete model, the controller may be augmented.
Therefore, the plant and observer augmentations assume a continuous model and the controller aug-
mentation assumes a discrete controller.
The three uerror states we’ll be adding are uerror,l , uerror,r , and uerror,heading for left voltage error,
right voltage error, and heading error respectively. The left and right wheel positions are filtered
encoder positions and are not adjusted for heading error. The turning angle computed from the
left and right wheel positions is adjusted by the gyroscope heading. The heading uerror state is the
heading error between what the wheel positions imply and the gyroscope measurement.
T
The full state is thus x = x y θ vl vr xl xr uerror,l uerror,r uerror,heading .
The complete nonlinear model is as follows. Let v = vl +v 2 . The three uerror states augment the
r
The left and right voltage error states should be mapped to the corresponding velocity states, so the
system matrix should be augmented with B.
The heading uerror is measuring counterclockwise encoder understeer relative to the gyroscope head-
ing, so it should add to the left position and subtract from the right position for clockwise correction
of encoder positions. That corresponds to the following input mapping vector.
0
0
Bθ = 1
−1
Now we’ll augment the linear system matrix horizontally to accomodate the uerror states.
vl
˙ vr
vl
xl
vr
= A B Bθ x + Bu (8.16)
xl r
uerror,l
xr
uerror,r
uerror,heading
R The process noise for the voltage error states should be how much the voltage can be expected
to drop. The heading error state should be the encoder model uncertainty.
controller for left and right position and velocity states, the controller only deals with the local pose.
If the robot deviates from the path, there is no way for the controller to correct and the robot may
not reach the desired global pose. This is due to multiple endpoints existing for the robot which have
the same encoder path arc lengths.
Instead of using wheel path arc lengths (which are in the robot’s local coordinate frame), nonlinear
controllers like pure pursuit and Ramsete use global pose. The controller uses this extra information
to guide a linear reference tracker like an LQR controller back in by adjusting the references of the
LQR controller.
The paper Control of Wheeled Mobile Robots: An Experimental Overview describes a nonlinear con-
troller for a wheeled vehicle with unicycle-like kinematics; a global pose consisting of x, y, and θ;
and a desired pose consisting of xd , yd , and θd [28]. We’ll call it Ramsete because that’s the acronym
for the title of the book it came from in Italian (“Robotica Articolata e Mobile per i SErvizi e le
TEcnologie”).
where ex is the tracking error in x, ey is the tracking error in y, and eθ is the tracking error in θ. The
3 × 3 matrix is a rotation matrix that transforms the error in the pose (represented by xd − x, yd − y,
and θd − θ) from the global coordinate frame into the vehicle’s coordinate frame.
We will use the following control laws u1 and u2 for velocity and turning rate respectively.
u1 = −k1 ex
(8.19)
u2 = −k3 eθ − k2 vd sinc(eθ )ey
where k1 , k2 , and k3 are time-varying gains and sinc(eθ ) is defined as sineθeθ . This choice of control
law may seem arbitrary, and that’s because it is. The only requirement on our choice is that there
exist an associated Lyapunov candidate function that proves the control law is globally asymptotically
stable. We’ll provide a sketch of a proof in theorem 8.8.1.
Our velocity and turning rate commands for the vehicle will use the following nonlinear transforma-
tion of the inputs.
v = vd cos eθ − u1
ω = ωd − u2
v = vd cos eθ + k1 ex
ω = k3 eθ + ωd + k2 vd sinc(eθ )ey
8.8 Ramsete unicycle controller 95
Theorem 8.8.1 Assuming that vd and ωd are bounded with bounded derivatives, and that
vd (t) → 0 or ωd (t) → 0 when t → ∞, the control laws in equation (8.19) globally asymptotically
stabilize the origin e = 0.
Proof:
To prove convergence, the paper previously mentioned uses the following Lyapunov function.
k2 2 e2
V = (ex + e2y ) + θ
2 2
where k2 is a tuning constant, ex is the tracking error in x, ey is the tracking error in y, and eθ is
the tracking error in θ.
The time derivative along the solutions of the closed-loop system is nonincreasing since
Thus, ∥e(t)∥ is bounded, V̇ (t) is uniformly continuous, and V (t) tends to some limit value. Using
the Barbalat lemma, V̇ (t) tends to zero [28].
v and ω should be the references for a drivetrain reference tracker. A good choice would be using
equations (11.1) and (11.2) to convert v and ω to left and right velocities, then applying LQR to the
96 Chapter 8. Nonlinear control
Figure 8.10: Ramsete nonlinear controller x-y Figure 8.11: Ramsete nonlinear controller re-
plot sponse
sin(eθ )
sinc(eθ ) =
eθ
1
[sinc(eθ )] =
A
[sinc(eθ )] = A−1
v = vd cos eθ + kex
[v] = [vd ][cos eθ ] + [k][ex ]
LT −1 = LT −1 · 1 + [k]L
LT −1 = LT −1 + [k]L
LT −1 = [k]L
T −1 = [k]
[k] = T −1
AT −1 = [k]A
T −1 = [k]
[k] = T −1
This is consistent with the result from the Ramsete velocity command equation.
Next, we’ll find the units of b.
The left-hand side and second term of equation (8.25) must have equivalent units.
AT −1 = [b]A−1 L2 T −1
A2 L−2 = [b]
[b] = A2 L−2
Ramsete k equation
Start from equation (8.23).
q
k = 2ζ ωd2 + bvd2
p
[k] = [ζ] [ωd ]2 + [b][vd ]2
p
T −1 = [ζ] (AT −1 )2 + [b](LT −1 )2
p
T −1 = [ζ] A2 T −2 + [b]L2 T −2 (8.26)
(AT −1 )2 = [b](LT −1 )2
A2 T −2 = [b]L2 T −2
A2 L−2 = [b]
[b] = A2 L−2
This is consistent with the result from the angular velocity command equation, so we can use it when
determining the units of ζ.
98 Chapter 8. Nonlinear control
T T
Here’s the model as a vector function where x = x y θ and u = v ω .
v cos θ
f (x, u) = v sin θ (8.29)
ω
We’re going to make a cross-track error controller, so we’ll apply a clockwise rotation matrix to the
global tracking error to transform it into the robot’s coordinate frame. Since the cross-track error is
always measured from the robot’s coordinate frame, the model used to compute the LQR should be
linearized around θ = 0 at all times.
0 0 −v sin 0 cos 0 0
A = 0 0 v cos 0 B = sin 0 0
0 0 0 0 1
0 0 0 1 0
A = 0 0 v B = 0 0
0 0 0 0 1
8.10 Further reading 99
Therefore,
Theorem 8.9.1 — Linear time-varying unicycle controller. Let the unicycle dynamics be
T T T
ẋ = f (x, u) = v cos θ v sin θ ω where x = x y θ and u = v ω .
0 0 0 1 0
∂f (x, u) ∂f (x, u)
A= = 0 0 v B= = 0 0 (8.30)
∂x θ=0 ∂u θ=0
0 0 0 0 1
At each timestep, the LQR controller gain K is computed for the (A, B) pair evaluated at the
current input.
Stochastic control theory is a subfield of control theory that deals with the existence of uncertainty
either in observations or in noise that drives the evolution of a system. We assign probability distri-
butions to this random noise and aim to achieve a desired control task despite the presence of this
uncertainty.
Stochastic optimal control is concerned with doing this with minimum cost defined by some cost
functional, like we did with LQR earlier. First, we’ll cover the basics of probability and how we rep-
resent linear stochastic systems in state-space representation. Then, we’ll derive an optimal estimator
using this knowledge, the Kalman filter, and demonstrate creative applications of the Kalman filter
theory.
This will be a rather math-heavy introduction, so we recommend reading Kalman and Bayesian Filters
in Python by Roger Labbe first [25].
9.1 Terminology
First, we should provide definitions for terms that have specific meanings in this field.
A causal system is one that uses only past information. A noncausal system also uses information
from the future. A filter is a causal system that filters information through a probabilistic model to
produce an estimate of a desired quantity that can’t be measured directly. A smoother is a noncausal
system, so it uses information from before and after the current state to produce a better estimate.
One type of state estimator is LQE. “LQE” stands for “Linear-Quadratic Estimator”. Similar to
LQR, it places the estimator poles such that it minimizes the sum of squares of the estimation error.
The Luenberger observer and Kalman filter are examples of these, where the latter chooses the pole
locations optimally based on the model and measurement uncertainties.
Computer vision can also be used for localization. By extracting features from an image taken by
the agent’s camera, like a retroreflective target in FRC, and comparing them to known dimensions,
one can determine where the agent’s camera would have to be to see that image. This can be used to
correct our state estimate in the same way we do with an encoder or gyroscope.
Variables denoted with a hat are estimates of the corresponding variable. For example, x̂ is the
estimate of the true state x.
Notice that a Luenberger observer has an extra term in the state evolution equation. This term uses
the difference between the estimated outputs and measured outputs to steer the estimated state toward
the true state. L approaching C+ trusts the measurements more while L approaching 0 trusts the
9.2 State observers 105
model more.
R Using an estimator forfeits the performance guarantees from earlier, but the responses are still
generally very good if the process and measurement noises are small enough. See John Doyle’s
paper Guaranteed Margins for LQG Regulators for a proof.
A Luenberger observer combines the prediction and update steps of an estimator. To run them
separately, use the equations in theorem 9.2.2 instead.
Predict step
x̂− −
k+1 = Ax̂k + Buk (9.5)
Update step
− −1
k+1 = x̂k+1 + A L(yk − ŷk )
x̂+ (9.6)
ŷk = Cx̂−
k (9.7)
For equation (9.8) to have a bounded output, the eigenvalues of A−LC must be within the unit circle.
These eigenvalues represent how fast the estimator converges to the true state of the given model. A
fast estimator converges quickly while a slow estimator avoids amplifying noise in the measurements
used to produce a state estimate.
The effect of noise can be seen if it is modeled stochastically as
uk = −Kx̂k
With the estimation error defined as ek = xk − x̂k , we get the observer dynamics derived in equation
(9.8).
ek+1 = (A − LC)ek
Also, after rearranging the error equation to be x̂k = xk − ek , the controller can be rewritten as
uk = −K(xk − ek )
Since the closed-loop system matrix is triangular, the eigenvalues are those of A − BK and A − LC.
Therefore, the stability of the feedback controller and observer are independent.
that the sum of all probabilities is 1. If the probabilities sum to 1, that means one of those outcomes
must happen. In other words, Z∞
p(x) ≥ 0, p(x) dx = 1
−∞
or given that the probability of a given sample is greater than or equal to zero, the sum of probabilities
for all possible input values is equal to one.
The mean of a random variable is denoted by an overbar (e.g., x) pronounced x-bar. The expectation
of the difference between a random variable and its mean x − x converges to zero. In other words,
the expectation of a random variable is its mean. Here’s a proof.
Z ∞
E[x − x] = (x − x) p(x) dx
−∞
Z ∞ Z ∞
E[x − x] = x p(x) dx − x p(x) dx
−∞ −∞
Z ∞ Z ∞
E[x − x] = x p(x) dx − x p(x) dx
−∞ −∞
E[x − x] = x − x · 1
E[x − x] = 0
9.3.3 Variance
Informally, variance is a measure of how far the outcome of a random variable deviates from its mean.
Later, we will use variance to quantify how confident we are in the estimate of a random variable;
we can’t know the true value of that variable without randomness, but we can give a bound on its
randomness. Z ∞
var(x) = σ = E[(x − x) ] =
2 2
(x − x)2 p(x) dx
−∞
The variance of a joint PDF measures how a variable correlates with itself (we’ll cover variances with
respect to other variables shortly).
Z ∞Z ∞
var(x) = Σxx = E[(x − x)2 ] = (x − x)2 p(x, y) dx dy
Z −∞
∞ Z ∞
−∞
9.3.5 Covariance
A covariance is a measurement of how a variable correlates with another. If they vary in the same
direction, the covariance increases. If they vary in opposite directions, the covariance decreases.
Z ∞Z ∞
cov(x, y) = Σxy = E[(x − x)(y − y)] = (x − x)(y − y) p(x, y) dx dy
−∞ −∞
9.3.6 Correlation
Two random variables are correlated if the result of one random variable affects the result of another.
Correlation is defined as
Σxy
ρ(x, y) = p , |ρ(x, y)| ≤ 1
Σxx Σyy
So two variable’s correlation is defined as their covariance over the geometric mean of their variances.
Uncorrelated sources have a covariance of zero.
9.3.7 Independence
Two random variables are independent if the following relation is true.
This means that the values of x do not correlate with the values of y. That is, the outcome of one
random variable does not affect another’s outcome. If we assume independence,
Z ∞Z ∞
E[xy] = xy p(x, y) dx dy
−∞ −∞
Z ∞Z ∞
E[xy] = xy p(x) p(y) dx dy
Z−∞∞
−∞
Z ∞
E[xy] = x p(x) dx y p(y) dy
−∞ −∞
E[xy] = E[x]E[y]
E[xy] = x y
Therefore, the covariance Σxy is zero, as expected. Furthermore, ρ(x, y) = 0, which means they are
uncorrelated.
1
The scale factor C(y ∗ ) is used to scale the area under the PDF to 1.
If x and y are independent, then p(x|y) = p(x), p(y|x) = p(y), and p(x, y) = p(x) p(y).
The elements of x are scalar variables jointly distributed with a joint density p(x1 , . . . , xn ). The
expectation is
Z ∞
E[x] = x = x p(x) dx
−∞
112 Chapter 9. Stochastic control theory
E[x1 ]
E[x] = ...
E[xn ]
Z ∞ Z ∞
E[xi ] = ... xi p(x1 , . . . , xn ) dx1 . . . dxn
Z−∞
∞
−∞
This n × n matrix is symmetric and positive semidefinite. A positive semidefinite matrix satisfies the
relation that for any v ∈ Rn for which v ̸= 0, vT Σv ≥ 0. In other words, the eigenvalues of Σ are
all greater than or equal to zero.
Σxy = cov(x, y)
Σxy = E[(x − x)(y − y)T ]
Σxy = E[xyT ] − E[xyT ] − E[xyT ] + E[xyT ]
Σxy = E[xyT ] − E[x]yT − xE[yT ] + xyT
Σxy = E[xyT ] − xyT − xyT + xyT
Σxy = E[xyT ] − xyT (9.9)
Factor out constants from the inner integral. This includes variables which are held constant for each
inner integral evaluation.
Z Z
T
E[xy ] = p(x) x dx p(y) yT dyT
X Y
9.3 Introduction to probability 113
Each of these integrals is just the expected value of their respective integration variable.
E[xyT ] = xyT (9.10)
Definition 9.3.1 — Central limit theorem. When independent random variables are added,
their properly normalized sum tends toward a normal distribution (a Gaussian distribution or “bell
curve”).
This is the case even if the original variables themselves are not normally distributed. The theorem is a
key concept in probability theory because it implies that probabilistic and statistical methods that work
for normal distributions can be applicable to many problems involving other types of distributions.
For example, suppose that a sample is obtained containing a large number of independent observa-
tions, and that the arithmetic mean of the observed values is computed. The central limit theorem
says that the computed values of the mean will tend toward being distributed according to a normal
distribution.
114 Chapter 9. Stochastic control theory
E[wk ] = 0
E[wk wkT ] = Qk
E[vk ] = 0
E[vk vkT ] = Rk
where Qk is the process noise covariance matrix and Rk is the measurement noise covariance matrix.
We assume the noise samples are independent, so E[wk wjT ] = 0 and E[vk vjT ] = 0 where k ̸= j.
Furthermore, process noise samples are independent from measurement noise samples.
We’ll compute the expectation of these equations and their covariance matrices, which we’ll use later
for deriving the Kalman filter.
Since the error and noise are independent, the cross terms are zero.
Sk = E[(C(xk − xk ) + vk )(C(xk − xk ) + vk )T ]
Sk = E[(C(xk − xk ) + vk )((xk − xk )T CT + vkT )]
Sk = E[(C(xk − xk )(xk − xk )T CT ] + E[C(xk − xk )vkT ]
+ E[vk (xk − xk )T CT ] + E[vk vkT ]
Sk = CE[(xk − xk )(xk − xk )T ]CT + CE[(xk − xk )vkT ]
+ E[vk (xk − xk )T ]CT + E[vk vkT ]
Sk = CPk CT + CE[(xk − xk )vkT ] + E[vk (xk − xk )T ]CT + Rk
Since the error and noise are independent, the cross terms are zero.
R Even in the single measurement case, the estimation of the variable x is a data/information
fusion problem. We combine prior probability with the probability resulting from the measure-
ment.
This means that if we’re given an initial estimate x0 and a measurement z1 with associated means
and variances represented by Gaussian distributions, this information can be combined into a third
Gaussian distribution with its own mean value and variance. The expected value of x given z1 is
σ02 σ2
E[x|z1 ] = µ = z 1 + x0 (9.11)
σ02 + σ 2 σ02 + σ 2
118 Chapter 9. Stochastic control theory
The expected value, which is also the maximum likelihood value, is the linear combination of the
prior expected (maximum likelihood) value and the measurement. The expected value is a reasonable
estimator of x.
σ02 σ2
x̂ = E[x|z1 ] = z 1 + x0 (9.13)
σ02 + σ2 2
σ0 + σ 2
x̂ = w1 z1 + w2 x0
Note that the weights w1 and w2 sum to 1. When the prior (i.e., prior knowledge of state) is uninfor-
mative (a large variance),
σ02
w1 = lim 2 =1 (9.14)
σ02 →∞ σ0 + σ 2
σ2
w2 = lim 2 =0 (9.15)
σ02 →∞ σ0 + σ 2
and x̂ = z1 . That is, the weight is on the observations and the estimate is equal to the measurement.
Let us assume we have a model providing an almost exact prior for x. In that case, σ02 approaches 0
and
σ02
w1 = lim 2 =0 (9.16)
σ02 →0 σ0 + σ 2
σ2
w2 = lim 2 =1 (9.17)
σ02 →0 σ0 + σ 2
The Kalman filter uses this optimal fusion as the basis for its operation.
9.6.1 Derivations
−
k+1 = x̂k+1 + Kk+1 (yk+1 − ŷk+1 ), we want to find the
Given the a posteriori update equation x̂+
value of Kk+1 that minimizes the a posteriori estimate covariance (the error covariance) because this
minimizes the estimation error.
a posteriori estimate covariance update equation
The following is the definition of the a posteriori estimate covariance matrix.
Substitute in the a posteriori update equation and expand the measurement equations.
−
k+1 = cov(xk+1 − (x̂k+1 + Kk+1 (yk+1 − ŷk+1 )))
P+
9.6 Kalman filter 119
−
k+1 = cov(xk+1 − x̂k+1 − Kk+1 (yk+1 − ŷk+1 ))
P+
−
k+1 = cov(xk+1 − x̂k+1 − Kk+1 (
P+
(Ck+1 xk+1 + Dk+1 uk+1 + vk+1 )
− (Ck+1 x̂−
k+1 + Dk+1 uk+1 )))
−
k+1 = cov(xk+1 − x̂k+1 − Kk+1 (
P+
Ck+1 xk+1 + Dk+1 uk+1 + vk+1
− Ck+1 x̂−
k+1 − Dk+1 uk+1 ))
Reorder terms.
−
k+1 = cov(xk+1 − x̂k+1 − Kk+1 (
P+
Ck+1 xk+1 − Ck+1 x̂−
k+1
+ Dk+1 uk+1 − Dk+1 uk+1 + vk+1 ))
−
k+1 = cov((I − Kk+1 Ck+1 )(xk+1 − x̂k+1 ) − Kk+1 vk+1 )
P+
Covariance is a linear operator, so it can be applied to each term separately. Covariance squares
terms internally, so the negative sign on Kk+1 vk+1 is removed.
−
k+1 = cov((I − Kk+1 Ck+1 )(xk+1 − x̂k+1 )) + cov(Kk+1 vk+1 )
P+
P+k+1 is positive definite, so we know all the eigenvalues are positive. Therefore, a reasonable quantity
to minimize with our choice of Kalman gain is the sum of the eigenvalues. We don’t have direct access
to the eigenvalues, but we can use the fact that the sum of the eigenvalues is equal to the trace of
P+ [2]
k+1 and minimize that instead.
−
k+1 = (I − Kk+1 Ck+1 )Pk+1 (I − Kk+1 Ck+1 ) + Kk+1 Rk+1 Kk+1
P+ T T
−
We’re going to expand the equation for P+
k+1 and collect terms. First, multiply in Pk+1 .
− −
k+1 = (Pk+1 − Kk+1 Ck+1 Pk+1 )(I − Kk+1 Ck+1 ) + Kk+1 Rk+1 Kk+1
P+ T T
Multiply in I − CT T
k+1 Kk+1 .
− −
k+1 = Pk+1 (I − Ck+1 Kk+1 ) − Kk+1 Ck+1 Pk+1 (I − Ck+1 Kk+1 )
P+ T T T T
+ Kk+1 Rk+1 KT
k+1
Expand terms.
− − −
k+1 = Pk+1 − Pk+1 Ck+1 Kk+1 − Kk+1 Ck+1 Pk+1
P+ T T
+ Kk+1 Ck+1 P− T T T
k+1 Ck+1 Kk+1 + Kk+1 Rk+1 Kk+1
− − −
k+1 = Pk+1 − Pk+1 Ck+1 Kk+1 − Kk+1 Ck+1 Pk+1
P+ T T
+ Kk+1 (Ck+1 P− T T
k+1 Ck+1 + Rk+1 )Kk+1
Ck+1 P− T
k+1 Ck+1 +Rk+1 is the innovation (measurement residual) covariance at timestep k+1. We’ll
let this expression equal Sk+1 . We won’t need it in the final theorem, but it makes the derivations
after this point more concise.
− − −
k+1 = Pk+1 − Pk+1 Ck+1 Kk+1 − Kk+1 Ck+1 Pk+1 + Kk+1 Sk+1 Kk+1
P+ T T T
(9.18)
+ tr(Kk+1 Sk+1 KT
k+1 )
as well as p(t) = (t−λ1 ) . . . (t−λn ) where λ1 , . . . , λn are the eigenvalues of P. The coefficient for tn−1 in the second
polynomial’s expansion is −(λ1 +· · ·+λn ). Therefore, by matching coefficients for tn−1 , we get tr(P) = λ1 +· · ·+λn .
9.6 Kalman filter 121
+ tr(Kk+1 Sk+1 KT
k+1 )
P−
k+1 is symmetric, so we can drop the transpose.
− − −
k+1 ) = tr(Pk+1 ) − tr((Kk+1 Ck+1 Pk+1 ) ) − tr(Kk+1 Ck+1 Pk+1 )
tr(P+ T
+ tr(Kk+1 Sk+1 KT
k+1 )
The trace of a matrix is equal to the trace of its transpose since the elements used in the trace are on
the diagonal.
− − −
k+1 ) = tr(Pk+1 ) − tr(Kk+1 Ck+1 Pk+1 ) − tr(Kk+1 Ck+1 Pk+1 )
tr(P+
+ tr(Kk+1 Sk+1 KT
k+1 )
− −
k+1 ) = tr(Pk+1 ) − 2 tr(Kk+1 Ck+1 Pk+1 ) + tr(Kk+1 Sk+1 Kk+1 )
tr(P+ T
∂
Theorem 9.6.1 ∂A tr(ABAT ) = 2AB where B is symmetric.
∂
Theorem 9.6.2 ∂A tr(AC) = CT
Kk+1 = P− T −1
k+1 Ck+1 Sk+1
Kk+1 Sk+1 = P− T
k+1 Ck+1
−
Kk+1 Sk+1 KT T T
k+1 = Pk+1 Ck+1 Kk+1
− −
k+1 = Pk+1 − Kk+1 Ck+1 Pk+1
P+
Factor out P−
k+1 to the right.
−
k+1 = (I − Kk+1 Ck+1 )Pk+1
P+
Predict step
x̂− +
k+1 = Ax̂k + Buk (9.19)
P− − T
k+1 = APk A + Q (9.20)
Update step
Kk+1 = P− T − T
k+1 C (CPk+1 C + R)
−1
(9.21)
x̂+
k+1 = x̂−
k+1 + Kk+1 (yk+1 − Cx̂−
k+1 − Duk+1 ) (9.22)
+
Pk+1 = (I − Kk+1 C)P−
k+1 (9.23)
C, D, Q, and R from the equations derived earlier are made constants here.
R To implement a discrete time Kalman filter from a continuous model, the model and continuous
time Q and R matrices can be discretized using theorem 7.3.1.
Unknown states in a Kalman filter are generally represented by a Wiener (pronounced VEE-ner)
process.[3] This process has the property that its variance increases linearly with time t.
9.6.3 Setup
Equations to model
The following example system will be used to describe how to define and initialize the matrices for a
Kalman filter.
A robot is between two parallel walls. It starts driving from one wall to the other at a velocity of
0.8 cm/s and uses ultrasonic sensors to provide noisy measurements of the distances to the walls in
front of and behind it. To estimate the distance between the walls, we will define three states: robot
position, robot velocity, and distance between the walls.
xk+1 = xk + vk ∆T (9.24)
vk+1 = vk (9.25)
xw
k+1 = xw
k (9.26)
where the Gaussian random variable wk has a mean of 0 and a variance of 1. The observation model
is
1 0 0
yk = x + θk (9.29)
−1 0 1 k
[3]
Explaining why we use the Wiener process would require going much more in depth into stochastic processes and
Itô calculus, which is outside the scope of this book.
124 Chapter 9. Stochastic control theory
where the covariance matrix of Gaussian measurement noise θ is a 2 × 2 matrix with both diagonals
10 cm2 .
The state vector is usually initialized using the first measurement or two. The covariance matrix
entries are assigned by calculating the covariance of the expressions used when assigning the state
vector. Let k = 2.
Q= 1 (9.30)
10 0
R= (9.31)
0 10
yk,1
x̂ = (yk,1 − yk−1,1 )/dt (9.32)
yk,1 + yk,2
10 10/dt 10
P = 10/dt 20/dt2 10/dt (9.33)
10 10/dt 20
Initial conditions
To fill in the P matrix, we calculate the covariance of each combination of state variables. The
resulting value is a measure of how much those variables are correlated. Due to how the covariance
calculation works out, the covariance between two variables is the sum of the variance of matching
terms which aren’t constants multiplied by any constants the two have. If no terms match, the variables
are uncorrelated and the covariance is zero.
In P11 , the terms in x1 correlate with itself. Therefore, P11 is x1 ’s variance, or P11 = 10. For
P21 , One term correlates between x1 and x2 , so P21 = 10 dt . The constants from each are sim-
ply multiplied together. For P22 , both measurements are correlated, so the variances add together.
20
Therefore, P22 = dt 2 . It continues in this fashion until the matrix is filled up. Order doesn’t matter
for correlation, so the matrix is symmetric.
Selection of priors
Choosing good priors is important for a well performing filter, even if little information is known.
This applies to both the measurement noise and the noise model. The act of giving a state variable a
large variance means you know something about the system. Namely, you aren’t sure whether your
initial guess is close to the true state. If you make a guess and specify a small variance, you are telling
the filter that you are very confident in your guess. If that guess is incorrect, it will take the filter a
long time to move away from your guess to the true value.
Covariance selection
While one could assume no correlation between the state variables and set the covariance matrix
entries to zero, this may not reflect reality. The Kalman filter is still guarenteed to converge to the
steady-state covariance after an infinite time, but it will take longer than otherwise.
Noise model selection
We typically use a Gaussian distribution for the noise model because the sum of many independent
random variables produces a normal distribution by the central limit theorem. Kalman filters only
require that the noise is zero-mean. If the true value has an equal probability of being anywhere
within a certain range, use a uniform distribution instead. Each of these communicates information
regarding what you know about a system in addition to what you do not.
9.6 Kalman filter 125
9.6.4 Simulation
Figure 9.3 shows the state estimates and measurements of the Kalman filter over time. Figure 9.4
shows the position estimate and variance over time. Figure 9.5 shows the wall position estimate
and variance over time. Notice how the variances decrease over time as the filter gathers more
measurements. This means that the filter becomes more confident in its state estimates.
The final precisions in estimating the position of the robot and the wall are the square roots of the
corresponding elements in the covariance matrix. That is,√0.5188 m and 0.4491 m respectively. They
are smaller than the precision of the raw measurements, 10 = 3.1623 m. As expected, combining
the information from several measurements produces a better estimate than any one measurement
alone.
K = PCT S−1
126 Chapter 9. Stochastic control theory
Figure 9.4: Robot position estimate and variance with Kalman filter
9.6 Kalman filter 127
Figure 9.5: Wall position estimate and variance with Kalman filter
KS = PCT
(KS)T = (PCT )T
ST KT = CPT
The solution of Ax = b can be found via x = solve(A, b).
KT = solve(ST , CPT )
K = solve(ST , CPT )T
import numpy as np
import scipy as sp
Keyword arguments:
A -- numpy.array(states x states), system matrix.
C -- numpy.array(outputs x states), output matrix.
Q -- numpy.array(states x states), process noise covariance matrix.
R -- numpy.array(outputs x outputs), measurement noise covariance matrix.
Returns:
K -- numpy.array(outputs x states), Kalman gain matrix.
"""
P = sp.linalg.solve_discrete_are(a=A.T, b=C.T, q=Q, r=R)
return np.linalg.solve(C @ P @ C.T + R, C @ P.T).T
9.7.2 Example
We will modify the robot model so that instead of a velocity of 0.8 cm/s with random noise, the
velocity is modeled as a random walk from the current velocity.
xk
xk = vk (9.45)
w
xk
1 1 0 0
xk+1
= 0 1 0 xk + 0.1 wk (9.46)
0 0 1 0
9.7 Kalman smoother 129
[4]
https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python/blob/master/13-Smoothing.ipynb
130 Chapter 9. Stochastic control theory
From there, the continuous Kalman filter equations are used like normal to compute the error covari-
ance matrix P and Kalman gain matrix. The state estimate update can still use the function h(x) for
accuracy.
− −
k+1 = x̂k+1 + Kk+1 (yk+1 − h(x̂k+1 ))
x̂+
[5]
https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python/blob/master/10-Unscented-Kalman-Filter.
ipynb
132 Chapter 9. Stochastic control theory
The original paper on the UKF is also an option [22]. See also the equations for van der Merwe’s sigma
point algorithm [40]. Here’s a paper on a quaternion-based Unscented Kalman filter for orientation
tracking [24].
Here’s an interview about the origin of the UKF with its creator [39].
[6]
MMAE section of https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python/blob/master/
14-Adaptive-Filtering.ipynb
Road next to Stevenson Academic building at UCSC
Pose is defined as the position and orientation of an agent (a system with a controller). The plant
usually includes the pose in its state vector. We’ll cover several methods for estimating an agent’s
pose from local measurements such as encoders and gyroscope heading.
xk+1 = xk + vk cos θk T
yk+1 = yk + vk sin θk T
θk+1 = θgyro,k+1
where T is the sample period. This odometry approach assumes that the robot follows a straight path
between samples (that is, ω = 0 at all but the sample times).
Associativity means that within an expression containing two or more occurrences in a row of the
same associative operator, the order in which the operations are performed does not matter as long
as the sequence of the operands is not changed. In other words, different groupings of the operations
produces the same result.
Identity, or an identity element, is a special type of element of a set with respect to a binary operation
on that set, which leaves any element of the set unchanged when combined with it. For example,
the additive identity of the set of integers is zero, which means that any integer summed with zero
produces that integer.
Invertibility means there is an element that can “undo” the effect of combination with another given
element. For integers and the addition operator, the inverse element would be the negation.
We use the pose exponential to take encoder measurement deltas and gyro angle deltas (which are in
the tangent space and are thus a twist) and turn them into a change in pose. This gets added to the
pose from the last update.
10.2.4 Derivation
We can obtain a more accurate approximation of the pose than Euler integration by including first-
order dynamics for the heading θ.
x
x = y
θ
vx , vy , and ω are the x and y velocities of the robot within its local coordinate frame, which will be
treated as constants.
R There are two coordinate frames used here: robot and global. A superscript on the left side of a
matrix denotes the coordinate frame in which that matrix is represented. The robot’s coordinate
frame is denoted by R and the global coordinate frame is denoted by G.
To transform this into the global frame SE(2), we apply a counterclockwise rotation matrix where θ
changes over time.
G R
dx cos θ(t) − sin θ(t) 0 vx
dy = sin θ(t) cos θ(t) 0 vy dt
dθ 0 0 1 ω
G R
dx cos ωt − sin ωt 0 vx
dy = sin ωt cos ωt 0 vy dt
dθ 0 0 1 ω
Now, integrate the matrix equation (matrices are integrated element-wise). This derivation heavily
utilizes the integration method described in section 4.3.
G sin ωt cos ωt
R t
∆x 0 vx
∆y = − cos ωt sin ωt 0 vy
ω ω
ω ω
∆θ 0 0 t ω
0
G sin ωt cos ωt−1
R
∆x ω ω 0 vx
∆y = 1−cos ωt sin ωt
0 vy
ω ω
∆θ 0 0 t ω
This equation assumes a starting orientation of θ = 0. For nonzero starting orientations, we can apply
a counterclockwise rotation by θ.
G sin ωt R
∆x cos θ − sin θ 0 ω
cos ωt−1
ω 0 vx
∆y = sin θ cos θ 0 1−cos ωt sin ωt
0 v y (10.1)
ω ω
∆θ 0 0 1 0 0 t ω
R Control system implementations will generally have a model update and a controller update in
a given iteration. Equation (10.1) (the model update) uses the current velocity to advance the
state to the next timestep (into the future). Since controllers use the current state, the controller
update should be run before the model update.
If we factor out a t, we can use change in pose between updates instead of velocities.
G sin ωt R
∆x cos θ − sin θ 0 ω
cos ωt−1
ω 0 vx
∆y = sin θ cos θ 0 1−cos ωt sin ωt
0 vy
ω ω
∆θ 0 0 1 0 0 t ω
G R
∆x cos θ − sin θ 0 sin ωt
ωt
cos ωt−1
ωt 0 vx
∆y = sin θ cos θ 0 1−cos ωt sin ωt
0 vy t
ωt ωt
∆θ 0 0 1 0 0 1 ω
G R
∆x cos θ − sin θ 0 sin ωt
ωt
cos ωt−1
ωt 0 vx t
∆y = sin θ cos θ 0 1−cos ωt sin ωt
0 vy t
ωt ωt
∆θ 0 0 1 0 0 1 ωt
136 Chapter 10. Pose estimation
G R sin ∆θ R
∆x cos θ − sin θ 0 ∆θ
cos ∆θ−1
∆θ 0 ∆x
∆y = sin θ cos θ 0 1−cos ∆θ sin ∆θ
0 ∆y (10.2)
∆θ ∆θ
∆θ 0 0 1 0 0 1 ∆θ
R
The vector ∆x ∆y ∆θ T is a twist because it’s an element of the tangent space (the robot’s
local coordinate frame).
R Control system implementations will generally have a model update and a controller update
in a given iteration. Equation (10.2) (the model update) uses local distance and heading deltas
between the previous and current timestep, so it advances the state to the current timestep. Since
controllers use the current state, the controller update should be run after the model update.
When the robot is traveling on a straight trajectory (∆θ = 0), some expressions within the equation
above are indeterminate. We can approximate these with Taylor series expansions.
sin ∆θ ∆θ2 ∆θ2
=1− + ... ≈1−
∆θ 6 6
cos ∆θ − 1 ∆θ ∆θ3 ∆θ
=− + − ... ≈ −
∆θ 2 4 2
1 − cos ∆θ ∆θ ∆θ3 ∆θ
= − + ... ≈
∆θ 2 4 2
where G denotes global coordinate frame and R denotes robot’s coordinate frame.
For sufficiently small ∆θ:
Figures 10.1 through 10.4 show the pose estimation errors of forward Euler odometry and pose
exponential odometry for a feedforward S-curve trajectory (dt = 20 ms).
The highest errors for the 8.84 m by 5.0 m trajectory are 3.415 cm in x, 0.158 cm in y, and −0.644
deg in heading. The difference would be even more noticeable for paths with higher curvatures and
longer durations. The error returns to near zero in this case because the curvature is symmetric, so
the second half cancels the error accrued in the first half.
Using a smaller update period somewhat mitigates the forward Euler pose estimation error. However,
there are bigger sources of error like turning scrub on skid steer robots that should be dealt with before
odometry numerical accuracy.
10.3 Pose correction 137
Figure 10.1: Pose estimation comparison Figure 10.2: Pose estimation comparison
(y vs x) (x error vs time)
Figure 10.3: Pose estimation comparison Figure 10.4: Pose estimation comparison
(y error vs time) (heading error vs time)
11 Dynamics . . . . . . . . . . . . . . . . . . . . . . . . . . 141
11.1 Linear motion
11.2 Angular motion
11.3 Vectors
11.4 Curvilinear motion
11.5 Differential drive kinematics
11.6 Mecanum drive kinematics
11.7 Swerve drive kinematics
11. Dynamics
1
x(t) = x0 + v0 t + at2
2
where x(t) is an object’s position at time t, x0 is the initial position, v0 is the initial velocity, and a is
the acceleration.
where θ(t) is an object’s angle at time t, θ0 is the initial angle, ω0 is the initial angular velocity, and
α is the angular acceleration.
142 Chapter 11. Dynamics
11.3 Vectors
Vectors are quantities with a magnitude and a direction. Vectors in three-dimensional space have a
coordinate for each spatial direction x, y, and z. Let’s take the vector ⃗a = ⟨1, 2, 3⟩. ⃗a is a three-
dimensional vector that describes a movement 1 unit in the x direction, 2 units in the y direction, and
3 units in the z direction.
We define î, ĵ, and k̂ as vectors that represent the fundamental movements one can make the three-
dimensional space: 1 unit of movement in the x direction, 1 unit of movement y direction, and 1 unit
of movement in the z direction respectively. These three vectors form a basis of three-dimensional
space because copies of them can be added together to reach any point in three-dimensional space.
î = ⟨1, 0, 0⟩
ĵ = ⟨0, 1, 0⟩
k̂ = ⟨0, 0, 1⟩
⃗a = ⟨1, 2, 3⟩
î × ĵ = k̂
ĵ × k̂ = î
k̂ × î = ĵ
They proceed in a cyclic fashion through i, j, and k. If a vector is crossed with itself, it produces the
zero vector (a scalar zero for each coordinate). The cross products of the basis vectors in the opposite
order progress backwards and include a negative sign.
î × k̂ = −ĵ
k̂ × ĵ = −î
ĵ × î = −k̂
11.4 Curvilinear motion 143
Given vectors ⃗u = aî + bĵ + ck̂ and ⃗v = dî + eĵ + f k̂, ⃗u × ⃗v is computed using the distributive
property.
+x
+y
Figure 11.1: 2D projection of North-West-Up (NWU) axes convention. The positive z-axis is pointed
out of the page toward the reader.
where ⃗vB is the velocity vector at point B, ⃗vA is the velocity vector at point A, ωA is the angular
velocity vector at point A, and ⃗rB|A is the distance vector from point A to point B (also described as
the “distance to B relative to A”).
ωl ωr
J
r
rb
Now, project this vector onto the left wheel, which is pointed in the î direction.
î
vl = (vc − ωrb )î ·
∥î∥
The magnitude of î is 1, so the denominator cancels.
vl = (vc − ωrb )î · î
vl = vc − ωrb (11.1)
Now, project this vector onto the right wheel, which is pointed in the î direction.
î
vr = (vc + ωrb )î ·
∥î∥
The magnitude of î is 1, so the denominator cancels.
vr = (vc + ωrb )î · î
vr = vc + ωrb (11.2)
vr = vc + ωrb
vc = vr − ωrb (11.5)
vl = vc − ωrb
vl = (vr − ωrb ) − ωrb
vl = vr − 2ωrb
2ωrb = vr − vl
vr − vl
ω=
2rb
vc = vr − ωrb
vr − vl
vc = vr − rb
2rb
vr − vl
vc = vr −
2
vr vl
vc = vr − +
2 2
vr + vl
vc =
2
vf l vf r
vrl vrr
+x
+y
î − ĵ
vrr = ((vx − ωrrry )î + (vy + ωrrrx )ĵ) · √
2
1
vrr = ((vx − ωrrry ) − (vy + ωrrrx )) √
2
1
vrr = (vx − ωrrry − vy − ωrrrx ) √
2
1
vrr = (vx − vy − ωrrry − ωrrrx ) √
2
1
vrr = (vx − vy − ω(rrrx + rrry )) √
2
1 1 1
vrr = √ vx − √ vy − √ ω(rrrx + rrry ) (11.11)
2 2 2
v1
v3 v2
+x
v4
+y
⃗ robot × ⃗rrobot2wheel1
⃗vwheel1 = ⃗vrobot + ω
⃗ robot × ⃗rrobot2wheel2
⃗vwheel2 = ⃗vrobot + ω
⃗ robot × ⃗rrobot2wheel3
⃗vwheel3 = ⃗vrobot + ω
⃗ robot × ⃗rrobot2wheel4
⃗vwheel4 = ⃗vrobot + ω
where ⃗vwheel is the wheel velocity vector, ⃗vrobot is the robot velocity vector, ω ⃗ robot is the robot
angular velocity vector, ⃗rrobot2wheel is the displacement vector from the robot’s center of rotation to
11.7 Swerve drive kinematics 149
the wheel,[1] ⃗vrobot = vx î+vy ĵ, and ⃗rrobot2wheel = rx î+ry ĵ. The number suffixes denote a specific
wheel in figure 11.4.
v1x = vx − ωr1y
v2x = vx − ωr2y
v3x = vx − ωr3y
v4x = vx − ωr4y
v1y = vy + ωr1x
v2y = vy + ωr2x
v3y = vy + ωr3x
v4y = vy + ωr4x
[1]
The robot’s center of rotation need not coincide with the robot’s geometric center.
150 Chapter 11. Dynamics
To convert the swerve module x and y velocity components to a velocity and heading, use the
Pythagorean theorem and arctangent respectively. Here’s an example for module 1.
q
v1 = v1x 2 + v2 (11.15)
1y
v1y
θ1 = tan−1 (11.16)
v1x
A model is a set of differential equations describing how the system behaves over time. There are
two common approaches for developing them.
1. Collecting data on the physical system’s behavior and performing system identification with it.
2. Using physics to derive the system’s model from first principles.
This chapter covers the second approach using Newtonian mechanics.
The models derived here should cover most types of motion seen on an FRC robot. Furthermore,
they can be easily tweaked to describe many types of mechanisms just by pattern-matching. There’s
only so many ways to hook up a mass to a motor in FRC. The flywheel model can be used for spinning
mechanisms, the elevator model can be used for spinning mechanisms transformed to linear motion,
and the single-jointed arm model can be used for rotating servo mechanisms (it’s just the flywheel
model augmented with a position state).
These models assume all motor controllers driving DC brushed motors are set to brake mode instead
of coast mode. Brake mode behaves the same as coast mode except where the applied voltage is zero.
In brake mode, the motor leads are shorted together to prevent movement. In coast mode, the motor
leads are an open circuit.
V
ω
Vemf = Kv
V is the voltage applied to the motor, I is the current through the motor in Amps, R is the resistance
across the motor in Ohms, ω is the angular velocity of the motor in radians per second, and Kv is the
angular velocity constant in radians per second per Volt. This circuit reflects the following relation.
ω
V = IR + (12.1)
Kv
τ = Kt I (12.2)
where τ is the torque produced by the motor in Newton-meters and Kt is the torque constant in
Newton-meters per Amp. Therefore
τ
I=
Kt
τ ω
V = R+ (12.3)
Kt Kv
τ = Kt I
τ
Kt =
I
τstall
Kt = (12.4)
Istall
where τstall is the stall torque and Istall is the stall current of the motor from its datasheet.
12.1 DC brushed motor 153
Resistance R
Recall equation (12.1).
ω
V = IR +
Kv
When the motor is stalled, ω = 0.
V = Istall R
V
R= (12.5)
Istall
where Istall is the stall current of the motor and V is the voltage applied to the motor at stall.
Angular velocity constant Kv
Recall equation (12.1).
ω
V = IR +
Kv
ω
V − IR =
Kv
ω
Kv =
V − IR
When the motor is spinning under no load,
ωf ree
Kv = (12.6)
V − If ree R
where ωf ree is the angular velocity of the motor under no load (also known as the free speed), and
V is the voltage applied to the motor when it’s spinning at ωf ree , and If ree is the current drawn by
the motor under no load.
If several identical motors are being used in one gearbox for a mechanism, multiply the stall torque
by the number of motors.
154 Chapter 12. Newtonian mechanics examples
12.2 Elevator
This elevator consists of a DC brushed motor attached to a pulley that drives a mass up or down.
R ωp
I ωm
Vemf
m v
V G
r
circuit mechanics
Gear ratios are written as output over input, so G is greater than one in figure 12.3.
τm G = τp (12.7)
12.2 Elevator 155
where G is the gear ratio between the motor and the pulley and τp is the torque produced by the
pulley.
rFm = τp (12.8)
where r is the radius of the pulley. Substitute equation (12.7) into τm in the DC brushed motor
equation (12.3).
τp
G ωm
V = R+
Kt Kv
τp ωm
V = R+
GKt Kv
Substitute in equation (12.8) for τp .
rFm ωm
V = R+ (12.9)
GKt Kv
ωm = Gωp (12.10)
where ωp is the angular velocity of the pulley. The velocity of the mass (the elevator carriage) is
v = rωp
v
ωp = (12.11)
r
Substitute equation (12.11) into equation (12.10).
v
ωm = G (12.12)
r
rFm Gv
V = R+ r
GKt Kv
RrFm G
V = + v
GKt rKv
Solve for Fm .
RrFm G
=V − v
GKt rKv
G GKt
Fm = V − v
rKv Rr
GKt 2
G Kt
Fm = V − v (12.13)
Rr Rr2 Kv
ma = Fm
GKt G2 K t
ma = V − v
Rr Rr2 Kv
GKt G2 Kt
a= V − v
Rrm Rr2 mKv
G2 K t GKt
a=− 2 v+ V (12.15)
Rr mKv Rrm
R Gravity is not part of the modeled dynamics because it complicates the state-space model and
the controller will behave well enough without it.
12.3 Flywheel
This flywheel consists of a DC brushed motor attached to a spinning mass of non-negligible moment
of inertia.
R ωf
I ωm J
Vemf
V G
circuit mechanics
Gear ratios are written as output over input, so G is greater than one in figure 12.4.
Solve for τm .
R 1
V = τm + ωm
Kt Kv
R 1
τm =V − ωm
Kt Kv
Kt Kt
τm = V − ωm
R Kv R
Since τm G = τf and ωm = Gωf ,
τ Kt Kt
f
= V − (Gωf )
G R Kv R
τf Kt GKt
= V − ωf
G R Kv R
GKt G2 Kt
τf = V − ωf (12.16)
R Kv R
The torque applied to the flywheel is defined as
τf = J ω̇f (12.17)
where J is the moment of inertia of the flywheel and ω̇f is the angular acceleration. Substitute
equation (12.17) into equation (12.16).
GKt G2 Kt
(J ω̇f ) = V − ωf
R Kv R
GKt G2 Kt
ω̇f = V − ωf
RJ Kv RJ
G2 Kt GKt
ω̇f = − ωf + V
Kv RJ RJ
We’ll relabel ωf as ω for convenience.
G2 Kt GKt
ω̇ = − ω+ V (12.18)
Kv RJ RJ
JKv R GKt Kv R
ω̇ = −ω + · 2 V
G2 K t R G Kt
158 Chapter 12. Newtonian mechanics examples
JKv R Kv
2
ω̇ = −ω + V
G Kt G
JKv R Kv
ω = − 2 ω̇ + V (12.19)
G Kt G
m
R ωarm
l
I ωm
Vemf
V G
circuit mechanics
Gear ratios are written as output over input, so G is greater than one in figure 12.5.
JKv R GKt Kv R
ω̇ = −ω + · 2 V
G2 K t R G Kt
160 Chapter 12. Newtonian mechanics examples
JKv R Kv
2
ω̇ = −ω + V
G Kt G
JKv R Kv
ω = − 2 ω̇ + V (12.25)
G Kt G
12.5 Pendulum
Kinematics and dynamics are a rather large topics, so for now, we’ll just focus on the basics required
for working with the models in this book. We’ll derive the same model, a pendulum, using three
approaches: sum of forces, sum of torques, and conservation of energy.
θ
y0
y1 θ0
mg sin θ
mg cos θ
θ h
mg
F = ma
where F is the sum of forces on the object, m is mass, and a is the acceleration. Because we are only
concerned with changes in speed, and because the bob is forced to stay in a circular path, we apply
Newton’s equation to the tangential axis only. The short violet arrow represents the component of the
12.5 Pendulum 161
gravitational force in the tangential axis, and trigonometry can be used to determine its magnitude.
Therefore
−mg sin θ = ma
a = −g sin θ
where g is the acceleration due to gravity near the surface of the earth. The negative sign on the right
hand side implies that θ and a always point in opposite directions. This makes sense because when a
pendulum swings further to the left, we would expect it to accelerate back toward the right.
This linear acceleration a along the red axis can be related to the change in angle θ by the arc length
formulas; s is arc length and l is the length of the pendulum.
s = lθ (12.26)
ds dθ
v= =l
dt dt
d2 s d2 θ
a= 2 =l 2
dt dt
Therefore,
d2 θ
l = −g sin θ
dt2
d2 θ g
2
= − sin θ
dt l
g
θ̈ = − sin θ
l
τ =r×F
First start by defining the torque on the pendulum bob using the force due to gravity.
τ = l × Fg
where l is the length vector of the pendulum and Fg is the force due to gravity.
For now just consider the magnitude of the torque on the pendulum.
|τ | = −mgl sin θ
where m is the mass of the pendulum, g is the acceleration due to gravity, l is the length of the
pendulum and θ is the angle between the length vector and the force due to gravity.
Next rewrite the angular momentum.
L = r × p = mr × (ω × r)
|L| = mr2 ω
162 Chapter 12. Newtonian mechanics examples
dθ
|L| = ml2
dt
d d 2θ
|L| = ml2 2
dt dt
dL
According to τ = dt , we can just compare the magnitudes.
d2 θ
−mgl sin θ = ml2
dt2
g d2 θ
− sin θ = 2
l dt
g
θ̈ = − sin θ
l
∆U = mgh
dθ p
v=l = 2gh
dt
dθ 2gh
= (12.27)
dt l
where h is the vertical distance the pendulum fell. Look at figure 12.6b, which presents the trigonom-
etry of a pendulum. If the pendulum starts its swing from some initial angle θ0 , then y0 , the vertical
distance from the pivot point, is given by
y0 = l cos θ0
y1 = l cos θ
12.6 Differential drive 163
h = l(cos θ − cos θ0 )
d2 θ g
= − sin θ
dt2 l
g
θ̈ = − sin θ
l
vr
vl
+x
θ
+y
GKt G2 Kt
τ= V − ω (12.28)
R Kv R
where τ is the torque applied by one wheel of the differential drive, G is the gear ratio of the differ-
ential drive, Kt is the torque constant of the motor, R is the resistance of the motor, and Kv is the
angular velocity constant. Since τ = rF and ω = vr where v is the velocity of a given drive side
along the ground and r is the drive wheel radius
GKt G2 K t v
(rF ) = V −
R Kv R r
GKt G2 K t
rF = V − v
R Kv Rr
GKt G2 Kt
F = V − v
Rr Kv Rr2
G2 Kt GKt
F =− 2
v+ V
Kv Rr Rr
Therefore, for each side of the robot,
G2l Kt Gl Kt
Fl = − 2
vl + Vl
Kv Rr Rr
G2 Kt Gr Kt
Fr = − r 2 v r + Vr
Kv Rr Rr
where the l and r subscripts denote the side of the robot to which each variable corresponds.
G2 K 2
Let C1 = − KvlRrt2 , C2 = Gl Kt
Rr , C3 = − KGvrRr
Kt
2 , and C4 =
G r Kt
Rr .
Fl = C 1 v l + C 2 V l (12.29)
Fr = C 3 v r + C 4 V r (12.30)
Substitute equation (12.32) back into equation (12.31) to obtain an expression for v̇l .
2 1 rb2
v̇l = (Fl + Fr ) − (Fl + Fr ) + (−Fl + Fr )
m m J
r 2
1
v̇l = (Fl + Fr ) − b (−Fl + Fr )
m J
1 r2
v̇l = (Fl + Fr ) + b (Fl − Fr )
m J
1 1 r2 r2
v̇l = Fl + Fr + b Fl − b Fr
m
m J J
r 2 r2
1 1
v̇l = + b Fl + − b Fr (12.34)
m J m J
τ1 = r × F
τ1 = rma
where τ1 is the torque applied by a drive motor during only linear acceleration, r is the wheel radius,
m is the robot mass, and a is the linear acceleration.
τ2 = Iα
where τ2 is the torque applied by a drive motor during only angular acceleration, I is the moment of
inertia (same as J), and α is the angular acceleration. If a constant voltage is applied during both the
linear and angular acceleration tests, τ1 = τ2 . Therefore,
rma = Iα
rmv + C1 = Iω + C2
rmv = Iω + C3
I
v= ω + C3 (12.37)
rm
where v is linear velocity and ω is angular velocity. C1 , C2 , and C3 are arbitrary constants of inte-
gration that won’t be needed. The test procedure is as follows.
1. Run the drivetrain forward at a constant voltage. Record the linear velocity over time using
encoders.
2. Rotate the drivetrain around its center by applying the same voltage as the linear acceleration
test with the motors driving in opposite directions. Record the angular velocity over time using
a gyroscope.
3. Perform a linear regression of linear velocity versus angular velocity. The slope of this line has
I
the form rm as per equation (12.37).
4. Multiply the slope by rm to obtain a least squares estimate of I.
Hills by northbound freeway between Santa Maria and Ventura
A model is a set of differential equations describing how the system behaves over time. There are
two common approaches for developing them.
1. Collecting data on the physical system’s behavior and performing system identification with it.
2. Using physics to derive the system’s model from first principles.
This chapter covers the second approach using Lagrangian mechanics.
We suggest reading An introduction to Lagrangian and Hamiltonian Mechanics by Simon J.A. Malham
for the basics [29].
13.3 Cart-pole
See https://underactuated.mit.edu/acrobot.html#cart_pole for a derivation of the kinematics and dy-
namics of a cart-pole via Lagrangian mechanics.
This page intentionally left blank
Hills by northbound freeway between Santa Maria and Ventura
First, we’ll cover a system identification procedure for generating a velocity system feedforward model
from performance data. Then, we’ll use that feedforward model to create state-space models for
several common mechanisms.
each row corresponds to a datapoint, and n > p (more datapoints than unknowns). OLS is a type
of linear least squares method that estimates the unknown parameters β in a linear regression model
y = Xβ + ϵ where ϵ is the error in the observations y. β is chosen by the method of least squares:
minimizing the sum of the squares of the difference between y (observations of the dependent vari-
able) and Xβ (predictions of y using a linear function of the independent variable β).
Geometrically, this is the sum of the squared distances, parallel to the y-axis, between each value in
y and the corresponding value in Xβ. Smaller differences mean a better model fit.
To find the β that fits best, we can solve the following quadratic minimization problem
β̂ = arg min(y − Xβ)T (y − Xβ)
β
arg minβ means “find the value of β that minimizes the following function of β”. Given corollary
5.12.3, take the partial derivative of the cost function with respect to β and set it equal to zero, then
170 Chapter 14. System identification
14.1.1 Examples
While this is a linear regression, we can fit nonlinear functions by making the contents of X nonlinear
functions of the independent variables. For example, we can find the quadratic equation y = ax2 +
bx + c that best fits a set of x-y tuples. Lets assume we have a set of observations as follows.
y1 = ax21 + bx1 + c
..
.
yn = ax2n + bxn + c
We want to find a, b, and c, so let’s factor those out.
2
y1 x1 x1 1 a
.. .. .. .. b
. = . . .
yn 2
xn xn 1 c
Plug these matrices into equation (14.1) to obtain the coefficients a, b, and c.
2
y1 x1 x1 1 a
.. .. β = b
y = ... X = ... . .
yn 2
xn xn 1 c
where u is input voltage, v is velocity, a is acceleration, and Ks , Kv , and Ka are constants reflecting
how much each variable contributes to the required voltage.
Since this is a linear multiple regression, the most obvious approach for obtaining the feedforward
gains Ks , Kv , and Ka is to use ordinary least squares (OLS) on 4-tuples of recorded voltage, veloc-
ity sign, velocity, and acceleration. The problem is we can’t cleanly measure acceleration directly,
and numerical differentiation of velocity is noisy. Ideally, we could find the feedforward gains with
samples of current velocity, current input, next velocity, and the nominal sample period instead.
14.2.2 Overview
First, we’ll put equation (14.2) into the form dx
dt = Ax + Bu + c. Then, we’ll discretize it to
obtain an equation of the form xk+1 = αxk + βuk + γ sgn(xk ). Then, we’ll perform OLS on
xk+1 = αxk + βuk + γ sgn(xk ) using 4-tuples of current velocity, next velocity, input voltage, and
velocity sign to obtain α, β, and γ. Since we solved for those in the discretization step earlier, we
have a system of three equations we can solve for Ks , Kv , and Ka .
14.2 1-DOF mechanism feedforward model 171
14.2.3 Derivation
First, solve u = Ks sgn(v) + Kv v + Ka a for a.
Ka a = u − Ks sgn(v) − Kv v
1 Ks Kv
a= u− sgn(v) − v
Ka Ka Ka
Kv 1 Ks
a=− v+ u− sgn(v)
Ka Ka Ka
Let x = v, dx
dt = a, A = − K
Kv
a
,B = 1
Ka , and c = − K
Ks
a
sgn(x).
dx
= Ax + Bu + c
dt
Since Bu + c is a constant over the time interval [0, T ) where T is the sample period, this equation
can be integrated according to appendix D.1, which gives
This equation has the form xk+1 = αxk +βuk +γ sgn(xk ). Running OLS with (xk+1 , xk , uk , sgn(xk ))
4-tuples will give α, β, and γ. To obtain Ks , Kv , and Ka , solve the following system.
α = e
AT
β = A−1 eAT − 1 B
Ks −1
γ = −K a
A e AT − 1
Divide the second equation by the third equation and solve for Ks .
β A−1 (α − 1)B
= Ks
γ − Ka A−1 (α − 1)
β Ka B
=−
γ Ks
1
β K a Ka
=−
γ Ks
172 Chapter 14. System identification
β 1
=−
γ Ks
γ
Ks = − (14.4)
β
Solve the second equation in (14.3) for Kv .
β = A−1 (α − 1)B
Kv −1 1
β= − (α − 1)
Ka Ka
Ka 1
β=− (α − 1)
Kv Ka
1
β= (1 − α)
Kv
Kv β = 1 − α
1−α
Kv = (14.5)
β
Solve the first equation in (14.3) for Ka .
Kv
α = e − Ka T
Kv
ln α = − T
Ka
Ka ln α = −Kv T
Kv T
Ka = −
ln α
Substitute in Kv from equation (14.5).
1−α
β T
Ka = −
ln α
(1 − α)T
Ka = −
β ln α
(α − 1)T
Ka = (14.6)
β ln α
14.2.4 Results
The new system identification process is as follows.
1. Gather input voltage and velocity from a dynamic acceleration event
2. Given an equation of the form xk+1 = αxk +βuk +γ sgn(xk ), perform OLS on (xk+1 , xk , uk , sgn(xk ))
4-tuples to obtain α, β, and γ
The feedforward gains are
γ
Ks = − (14.7)
β
1−α
Kv = (14.8)
β
(α − 1)T
Ka = (14.9)
β ln α
14.3 1-DOF mechanism state-space model 173
α > 0, β ̸= 0
We want to derive what A and B are from the following feedforward model
u = Kv x + Ka ẋ
Since this equation is a linear multiple regression, the constants Kv and Ka can be determined by
applying ordinary least squares (OLS) to vectors of recorded input voltage, velocity, and acceleration
data from quasistatic velocity tests and acceleration tests.
Kv is a proportional constant that describes how much voltage is required to maintain a given con-
stant velocity by offsetting the electromagnetic resistance of the motor and any friction that increases
linearly with speed (viscous drag). The relationship between speed and voltage (for a given initial
acceleration) is linear for permanent-magnet DC motors in the FRC operating regime.
Ka is a proportional constant that describes how much voltage is required to induce a given acceler-
ation in the motor shaft. As with Kv , the relationship between voltage and acceleration (for a given
initial velocity) is linear.
To convert u = Kv x + Ka ẋ to state-space form, simply solve for ẋ.
u = Kv x + Ka ẋ
Ka ẋ = u − Kv x
Ka ẋ = −Kv x + u
Kv 1
ẋ = − x+ u
Ka Ka
By inspection, A = − K
Kv
a
and B = 1
Ka . A model with position and velocity states would be
ẋ = Ax + Bu
position
x= u = voltage
velocity
0 1 0
ẋ = Kv x + u (14.10)
0 −K a
1
Ka
174 Chapter 14. System identification
The model in theorem 14.3.1 is undefined when Ka = 0. If one wants to design an LQR for such
a system, use the model in theorem 14.3.2. As Ka tends to zero, acceleration requires no effort and
velocity becomes an input for position control.
ẋ = Ax + Bu
x = position u = velocity
ẋ = 0 x + 1 u (14.11)
We want to derive what A and B are from linear and angular feedforward models. Since the left and
right dynamics are symmetric, we’ll guess the model has the form
A1 A2 B1 B2
A= B=
A2 A1 B2 B1
T
Let u = Kv,linear v Kv,linear v be the input that makes both sides of the drivetrain move at a
T T
constant velocity v. Therefore, x = v v and ẋ = 0 0 . Substitute these into the state-space
model.
0 A1 A2 v B1 B2 Kv,linear v
= +
0 A2 A1 v B2 B1 Kv,linear v
Since the column vectors contain the same element, the elements in the second row can be rearranged.
0 A1 A2 v B1 B2 Kv,linear v
= +
0 A1 A2 v B1 B2 Kv,linear v
Since the rows are linearly dependent, we can use just one of them.
0 = A1 A2 v + B1 B2 Kv,linear v
A1
A2
0 = v v Kv,linear v Kv,linear v B1
B2
A1
A2
0 = 1 1 Kv,linear Kv,linear B1
B2
T
Let u = Kv,linear v + Ka,linear a Kv,linear v + Ka,linear a be the input that accelerates both
T T
sides of the drivetrain by a from an initial velocity of v. Therefore, x = v v and ẋ = a a .
14.4 Drivetrain left/right velocity state-space model 175
T
Let u = −Kv,angular v Kv,angular v be the input that rotates the drivetrain in place where each
T T
wheel has a constant velocity v. Therefore, x = −v v and ẋ = 0 0 .
0 A1 A2 −v B1 B2 −Kv,angular v
= +
0 A2 A1 v B2 B1 Kv,angular v
0 −A1 A2 v −B1 B2 Kv,angular v
= +
0 −A2 A1 v −B2 B1 Kv,angular v
0 −A1 A2 v −B1 B2 Kv,angular v
= +
0 A1 −A2 v B1 −B2 Kv,angular v
Since the column vectors contain the same element, the elements in the second row can be rearranged.
0 −A1 A2 v −B1 B2 Kv,angular v
= +
0 −A1 A2 v −B1 B2 Kv,angular v
Since the rows are linearly dependent, we can use just one of them.
0 = −A1 A2 v + −B1 B2 Kv,angular v
0 = −vA1 + vA2 − Kv,angular vB1 + Kv,angular vB2
A1
A2
0 = −v v −Kv,angular v Kv,angular v
B1
B2
A1
A2
0 = −1 1 −Kv,angular Kv,angular
B1
B2
T
Let u = −Kv,angular v − Ka,angular a Kv,angular v + Ka,angular a be the input that rotates
the drivetrain in place where each wheel has an initial speed of v and accelerates by a. Therefore,
T T
x = −v v and ẋ = −a a .
−a A1 A2 −v B1 B2 −Kv,angular v − Ka,angular a
= +
a A2 A1 v B2 B1 Kv,angular v + Ka,angular a
176 Chapter 14. System identification
−a −A1 A2 v −B1 B2 Kv,angular v + Ka,angular a
= +
a −A2 A1 v −B2 B1 Kv,angular v + Ka,angular a
−a −A1 A2 v −B1 B2 Kv,angular v + Ka,angular a
= +
a A1 −A2 v B1 −B2 Kv,angular v + Ka,angular a
Since the column vectors contain the same element, the elements in the second row can be rearranged.
−a −A1 A2 v −B1 B2 Kv,angular v + Ka,angular a
= +
−a −A1 A2 v −B1 B2 Kv,angular v + Ka,angular a
Since the rows are linearly dependent, we can use just one of them.
−a = −A1 A2 v + −B1 B2 Kv,angular v + Ka,angular a
−a = −vA1 + vA2 − (Kv,angular v + Ka,angular a)B1 + Kv,angular v + Ka,angular a)B2
A1
A2
−a = −v v −(Kv,angular v + Ka,angular a) Kv,angular v + Ka,angular a
B1
B2
A1
A2
a = v −v Kv,angular v + Ka,angular a −(Kv,angular v + Ka,angular a)
B1
B2
Solve for matrix elements with Wolfram Alpha. Let b = Kv,linear , c = Ka,linear , d = Kv,angular ,
and f = Ka,angular .
inverse of {{1, 1, b, b}, {v, v, b v + c a, b v + c a},
{-1, 1, -d, d}, {v, -v, d v + f a, -(d v + f a)}} * {{0}, {a}, {0}, {a}}
A1 −cd − bf
A2
= 1 cd − bf
B1 2cf c + f
B2 f −c
A1 −Ka,linear Kv,angular − Kv,linear Ka,angular
A2 1 Ka,linear Kv,angular − Kv,linear Ka,angular
=
B1 2Ka,linear Ka,angular Ka,linear + Ka,angular
B2 Ka,angular − Ka,linear
Ka,linear Kv,angular Kv,linear Ka,angular
− Ka,linear Ka,angular − Ka,linear Ka,angular
A1 K
A2 1 a,linear Kv,angular Kv,linear Ka,angular
− Ka,linear
= Ka,linear Ka,angular Ka,angular
B1 2 Ka,linear Ka,angular
Ka,linear Ka,angular + Ka,linear Ka,angular
B2 Ka,angular Ka,linear
Ka,linear Ka,angular − Ka,linear Ka,angular
14.4 Drivetrain left/right velocity state-space model 177
K
− Ka,angular
v,angular Kv,linear
− Ka,linear
A1
A2 1 Kv,angular − Kv,linear
= Ka,angular Ka,linear
B1 2 1 1
Ka,angular + Ka,linear
B2
Ka,linear − Ka,angular
1 1
−
Kv,linear
+
Kv,angular
A1 Ka,linear Ka,angular
A2 1 − K Kv,angular
Ka,linear − Ka,angular
v,linear
=
B1 2 1 1
Ka,linear + Ka,angular
B2
Ka,linear − Ka,angular
1 1
To summarize,
ẋ = Ax + Bu
left velocity left voltage
x= u=
right velocity right voltage
A1 A2 B1 B2
ẋ = x+ u
A2 A1 B2 B1
−
Kv,linear
+
Kv,angular
A1 Ka,linear Ka,angular
A2 1 Kv,linear Kv,angular
= − Ka,linear − Ka,angular
B1 2 1 1
(14.12)
Ka,linear + Ka,angular
B2
Ka,linear − Ka,angular
1 1
V V
Kv,angular and Ka,angular have units of L/T and L/T 2
respectively where V means voltage units,
L means length units, and T means time units.
If Kv and Ka are the same for both the linear and angular cases, it devolves to the one-dimensional
case. This means the left and right sides are decoupled.
− Kv
+ Kv
A1 Ka Ka
A2 1 − Kv − Kv
= Ka
B1 2 Ka
K1 + K1
B2 a a
Ka − Ka
1 1
Kv
A1 −2 Ka
A2 1 0
= 2
B1 2
Ka
B2 0
Kv
A1 − Ka
A2 0
= 1
B1
Ka
B2 0
178 Chapter 14. System identification
We want to write this model in terms of left and right voltages. The linear and angular voltages have
the following relations.
ulef t = ulinear − uangular
uright = ulinear + uangular
Factor them into a matrix equation, then solve for the linear and angular voltages.
ulef t 1 −1 ulinear
=
uright 1 1 uangular
ulinear 0.5 0.5 ulef t
=
uangular −0.5 0.5 uright
ẋ = Ax + Bu
linear velocity left voltage
x= u=
angular velocity right voltage
" Kv,linear # " #
− Ka,linear 0 0.5
Ka,linear
0.5
Ka,linear
ẋ = x+ u
0
K
− v,angular − Ka,angular
0.5 0.5
Ka,angular
Ka,angular
V V
Kv,angular and Ka,angular have units of A/T and A/T 2
respectively where V means voltage units,
A means angle units, and T means time units.
V
Motion planning
If smooth, predictable motion of a system over time is desired, it’s best to only change a system’s
reference as fast as the system is able to physically move. Motion profiles, also known as trajectories,
are used for this purpose. For multi-state systems, each state is given its own trajectory. Since these
states are usually position and velocity, they share different derivatives of the same profile.
These profiles are given their names based on the shape of their velocity trajectory. The trapezoid
profile has a velocity trajectory shaped like a trapezoid and the S-curve profile has a velocity trajectory
182 Chapter 15. Motion profiles
15.1.1 Jerk
The motion characteristic that defines the change in acceleration, or transitional period, is known as
“jerk”. Jerk is defined as the rate of change of acceleration with time. In a trapezoid profile, the jerk
(change in acceleration) is infinite at the phase transitions, while in the S-curve profile the jerk is a
constant value, spreading the change in acceleration over a period of time.
From figures 15.1 and 15.2, we can see S-curve profiles are smoother than trapezoid profiles. Why,
however, do the S-curve profile result in less load oscillation? For a given load, the higher the jerk,
the greater the amount of unwanted vibration energy will be generated, and the broader the frequency
spectrum of the vibration’s energy will be.
This means that more rapid changes in acceleration induce more powerful vibrations, and more vibra-
tional modes will be excited. Because vibrational energy is absorbed in the system mechanics, it may
cause an increase in settling time or reduced accuracy if the vibration frequency matches resonances
in the mechanical system.
the overall transfer time. However, the reduced load oscillation at the end of the move considerably
decreases the total effective transfer time. Trial and error using a motion measurement system is gen-
erally the best way to determine the right amount of “S” because modeling high frequency dynamics
is difficult to do accurately.
Another consideration is whether that “S” segment will actually lead to smoother control of the system.
If the high frequency dynamics at play are negligible, one can use the simpler trapezoid profile.
R S-curve profiles are unnecesary for FRC mechanisms. Motors in FRC effectively have first-
order velocity dynamics because the inductance effects are on the order of microseconds; FRC
dynamics operate on the order of milliseconds. First-order motor models can achieve the in-
stantaneous acceleration changes of trapezoid profiles because voltage is electromotive force,
which is analogous to acceleration. That is, we can instantaneously achieve any desired ac-
celeration with a finite voltage, and we can follow any trapezoid profile perfectly with only
feedforward control.
where x(t) is the position at time t, x0 is the initial position, v0 is the initial velocity, and a is the
acceleration at time t.
Snippet 15.1 shows a Python implementation.
"""Function for generating a trapezoid profile."""
import math
Returns:
t_rec -- list of timestamps
x_rec -- list of positions at each timestep
v_rec -- list of velocities at each timestep
a_rec -- list of accelerations at each timestep
Keyword arguments:
max_v -- maximum velocity of profile
time_to_max_v -- time from rest to maximum velocity
dt -- timestep
goal -- final position when the profile is at rest
"""
t_rec = [0.0]
x_rec = [0.0]
v_rec = [0.0]
a_rec = [0.0]
a = max_v / time_to_max_v
time_at_max_v = goal / max_v - time_to_max_v
184 Chapter 15. Motion profiles
# If profile is short
if max_v * time_to_max_v > goal:
time_to_max_v = math.sqrt(goal / a)
time_from_max_v = time_to_max_v
time_total = 2.0 * time_to_max_v
profile_max_v = a * time_to_max_v
else:
time_from_max_v = time_to_max_v + time_at_max_v
time_total = time_from_max_v + time_to_max_v
profile_max_v = max_v
S-curve profile
The S-curve profile equations also include jerk.
1 1
x(t) = x0 + v0 t + at2 + jt3
2 6
1 2
v(t) = v0 + at + jt
2
a(t) = a0 + jt
where j is the jerk at time t, a(t) is the acceleration at time t, and a0 is the initial acceleration.
Snippet 15.2 shows a Python implementation.
"""Function for generating an S-curve profile."""
import math
Returns:
t_rec -- list of timestamps
x_rec -- list of positions at each timestep
15.1 1-DOF motion profiles 185
Keyword arguments:
max_v -- maximum velocity of profile
max_a -- maximum acceleration of profile
time_to_max_a -- time from rest to maximum acceleration
dt -- timestep
goal -- final position when the profile is at rest
"""
t_rec = [0.0]
x_rec = [0.0]
v_rec = [0.0]
a_rec = [0.0]
j = max_a / time_to_max_a
short_profile = max_v * (time_to_max_a + max_v / max_a) > goal
if short_profile:
profile_max_v = max_a * (
math.sqrt(goal / max_a - 0.75 * time_to_max_a**2) - 0.5 *
time_to_max_a
)
else:
profile_max_v = max_v
A path is a set of (x, y) points for the drivetrain to follow. A drivetrain trajectory is a path that
includes both the states (e.g., position and velocity) and control inputs (e.g., voltage) of the drivetrain
as functions of time.
Currently, the most common form of multidimensional trajectory planning in FRC is based on poly-
nomial splines. The splines determine the path of the trajectory, and the path is parameterized by a
trapezoidal motion profile to create a trajectory. A Dive into WPILib Trajectories by Declan Freeman-
Gleason introduces 2-DOF trajectory planning in FRC using polynomial splines [20].
Planning Motion Trajectories for Mobile Robots Using Splines by Christoph Sprunk provides a more
general treatment of spline-based trajectory generation [32].
This page intentionally left blank
OPERS field at UCSC
16.1 Introduction
When a robot can interfere with itself, we need a motion profiling solution that ensures the robot
doesn’t destroy itself. Now that we’ve demonstrated various methods of motion profiling, how can
we incorporate safe zones into the planning process or implement mechanism collision avoidance?
1-DOF systems are straightforward. We define the minimum and maximum position constraints for
the arm, elevator, etc. and ensure we stay between them. To do so, we might use some combination
of:
1. Rejecting, coercing, or clamping setpoints so that they are always within the valid range
2. Soft limits on the speed controller
3. Limit switches, and/or physical hard stops
Multi-DOF systems are more complex. In the 2-DOF case (e.g., an arm with a shoulder and a wrist,
or an elevator and an arm), each DOF has some limits that are independent of the rest of the system
(e.g., min and max angles), but there are also dependent constraints (e.g., if the shoulder is angled
down, the wrist must be angled up to avoid hitting the ground). Examples of such constraints could
include:
• Minimum/maximum angles
• Maximum extension rules
• Robot chassis
• Angles that require an infeasible amount of holding torque
One intuitive way to think about this is to envision an N-D space (2D for 2 DOFs, etc.) where the
x and y axes are the positions of the degrees of freedom. A given point (x, y) can either be a valid
configuration or an invalid configuration (meaning it violates one or more constraints). So, our 2D
plot may have regions (half-planes, rectangles, etc.) representing constraints.
190 Chapter 16. Configuration spaces
Figure 16.2: Elevator-arm configuration space requiring elevator to be above a certain height when
arm is pointing down
Figure 16.3: Elevator-arm configuration space with initial state x and goal state r
192 Chapter 16. Configuration spaces
Figure 16.4: Elevator-arm configuration space with path between initial state x and final state r
A trajectory is a collection of samples defined over some time interval. A drivetrain trajectory would
include its states (e.g., x position, y position, heading, and velocity) and control inputs (e.g., voltage).
Trajectory optimization finds the best choice of trajectory (for some mathematical definition of “best”)
by formulating and solving a constrained optimization problem.
where f (x) is the scalar cost function, x is the vector of decision variables (variables the solver can
tweak to minimize the cost function), ce (x) is the vector-valued function whose rows are equality
constraints, and ci (x) is the vector-valued function whose rows are inequality constraints. Constraints
are equations or inequalities of the decision variables that constrain what values the solver is allowed
to use when searching for an optimal solution.
The nice thing about Sleipnir is users don’t have to put their system in the form shown above manually;
they can write it in natural mathematical form and it’ll be converted for them. We’ll cover some
examples next.
#include <Eigen/Core>
#include <fmt/core.h>
#include <sleipnir/optimization/OptimizationProblem.hpp>
int main() {
using namespace std::chrono_literals;
sleipnir::OptimizationProblem problem;
// 1x1 input vector with N timesteps (input at last state doesn't matter)
auto U = problem.DecisionVariable(1, N);
// Limit velocity
problem.SubjectTo(-1 <= X.Row(1));
problem.SubjectTo(X.Row(1) <= 1);
// Limit acceleration
problem.SubjectTo(-1 <= U);
problem.SubjectTo(U <= 1);
The solver will find the decision variable values that minimize the cost function while satisfying the
constraints.
Accessing the solution
You can obtain the solution by querying the values of the variables like so.
double position = X.Value(0, 0);
double velocity = X.Value(1, 0);
double acceleration = U.Value(0);
Figure 17.1: Double integrator position (left), velocity (middle), and acceleration (right)
Other applications
In retrospect, the solution here seems obvious: if you want to reach the desired position in the mini-
mum time, you just apply positive max input to accelerate to the max speed, coast for a while, then
apply negative max input to decelerate to a stop at the desired position. Optimization problems can
get more complex than this though. In fact, we can use this same framework to design optimal trajec-
tories for a drivetrain while satisfying dynamics constraints, avoiding obstacles, and driving through
points of interest.
196 Chapter 17. Trajectory optimization
C Feedforwards . . . . . . . . . . . . . . . . . . . . . . 213
C.1 QR-weighted linear plant inversion
C.2 Steady-state feedforward
D Derivations . . . . . . . . . . . . . . . . . . . . . . . . 219
D.1 Linear system zero-order hold
D.2 Kalman filter as Luenberger observer
Glossary . . . . . . . . . . . . . . . . . . . . . . . . . . . 249
Bibliography . . . . . . . . . . . . . . . . . . . . . . . 251
Online
Index . . . . . . . . . . . . . . . . . . . . . . . . . . . . . . 255
This page intentionally left blank
Sunset in an airplane over New Mexico
X P1 P2 Y
X P1 P2 Y
+
X P1 Y
±
P2
X P1 ± P2 Y
+
X P1 Y
±
P2
P1 +
X P2 Y
P2
±
+
X P1 Y
∓
P2
P1
X 1±P1 P 2 Y
+
X P1 Y
∓
P2
1 −
X P1 P2 Y
P2
∓
B. Linear-quadratic regulator
This appendix will go into more detail on the linear-quadratic regulator’s derivation and interesting
applications.
B.1 Derivation
Let there be a discrete time linear system defined as
where J represents a trade-off between state excursion and control effort with the weighting factors
Q, R, and N. Q is the weight matrix for error, R is the weight matrix for control effort, and N is
a cross weight matrix between error and control effort. N is commonly utilized when penalizing the
output in addition to the state and input.
∞
X T
xk Qxk + Nuk
J=
uk NT xk + Ruk
k=0
X∞
Qxk + Nuk
J= xT T
uk
k NT xk + Ruk
k=0
∞
X
J= (xT T T
k (Qxk + Nuk ) + uk (N xk + Ruk ))
k=0
∞
X
J= (xT T T T T
k Qxk + xk Nuk + uk N xk + uk Ruk )
k=0
204 Appendix B. Linear-quadratic regulator
∞
X
J= (xT T T T T
k Qxk + xk Nuk + xk Nuk + uk Ruk )
k=0
∞
X
J= (xT T T
k Qxk + 2xk Nuk + uk Ruk )
k=0
X∞
J= (xT T T
k Qxk + uk Ruk + 2xk Nuk )
k=0
The feedback control law which minimizes J subject to the constraint xk+1 = Axk + Buk is
uk = −Kxk
where K is given by
K = (R + BT SB)−1 (BT SA + NT )
and S is found by solving the discrete time algebraic Riccati equation defined as
or alternatively
AT SA − S − AT SB(R + BT SB)−1 BT SA + Q = 0
with
A = A − BR−1 NT
Q = Q − NR−1 NT
If there is no cross-correlation between error and control effort, N is a zero matrix and the cost
functional simplifies to
∞
X
J= (xT T
k Qxk + uk Ruk )
k=0
The feedback control law which minimizes this J subject to xk+1 = Axk + Buk is
uk = −Kxk
where K is given by
K = (R + BT SB)−1 BT SA
and S is found by solving the discrete time algebraic Riccati equation defined as
AT SA − S − AT SB(R + BT SB)−1 BT SA + Q = 0
import numpy as np
import scipy as sp
Keyword arguments:
A -- numpy.array(states x states), system matrix.
B -- numpy.array(states x inputs), input matrix.
Q -- numpy.array(states x states), state cost matrix.
R -- numpy.array(inputs x inputs), control effort cost matrix.
N -- numpy.array(states x inputs), cross weight matrix.
Returns:
K -- numpy.array(inputs x states), controller gain matrix.
"""
P = sp.linalg.solve_discrete_are(a=A, b=B, q=Q, r=R, s=N)
return np.linalg.solve(R + B.T @ P @ B, B.T @ P @ A + N.T)
Other formulations of LQR for finite horizon and discrete time can be seen on Wikipedia [17].
MIT OpenCourseWare has a rigorous proof of the results shown above [36].
However, we may not know how to select costs for some of the states, or we don’t care what certain
internal states are doing. We can address this by writing the cost functional in terms of the output
vector instead of the state vector. Not only can we make our output contain a subset of states, but we
can use any other cost metric we can think of as long as it’s representable as a linear combination of
the states and inputs.[1]
For state feedback with an output cost, we want to minimize the following cost functional.
∞
X
J= (ykT Qyk + uT
k Ruk )
k=0
X∞ T T T !
xk C xk xk 0 0 xk
J= Q C D +
uk DT uk uk 0 R uk
k=0
X∞ !
xk
T
CT 0 0 xk
J= Q C D +
uk DT 0 R uk
k=0
Multiply in Q.
∞
X T T !
xk C Q 0 0 xk
J= C D +
uk DT Q 0 R uk
k=0
Thus, state feedback with an output cost can be defined as the following optimization problem.
The optimal control policy u∗k is K(rk − xk ) where rk is the desired state. Note that the Q in
CT QC is outputs × outputs instead of states × states. K can be computed via the typical LQR
equations based on the algebraic Ricatti equation.
If the output is just the state vector, then C = I, D = 0, and the cost functional simplifies to that of
LQR with a state cost.
∞
X T
xk Q 0 xk
J=
uk 0 R uk
k=0
B.3 Implicit model following 207
yk+1 = Cxk+1
yk+1 = C(Axk + Buk )
yk+1 = CAxk + CBuk
zk+1 = Aref yk
zk+1 = Aref Cxk
Therefore,
X∞ T
xk (CA − Aref C)T xk
J= Q CA − Aref C CB
uk (CB)T uk
k=0
T !
xk 0 0 xk
+
uk 0 R uk
X∞ !
xk
T
(CA − Aref C)T 0 0 xk
J= T Q CA − Aref C CB +
uk (CB) 0 R uk
k=0
Multiply in Q.
∞
X T !
xk (CA − Aref C)T Q 0 0 xk
J= CA − Aref C CB +
uk (CB)T Q 0 R uk
k=0
X∞ T
xk (CA − Aref C)T Q(CA − Aref C) (CA − Aref C)T Q(CB)
J=
uk (CB)T Q(CA − Aref C) (CB)T Q(CB)
k=0
0 0 xk
+
0 R uk
The optimal control policy u∗k is −Kxk . K can be computed via the typical LQR equations based
on the algebraic Ricatti equation.
The control law uimf,k = −Kxk makes xk+1 = Axk + Buimf,k match the open-loop response of
zk+1 = Aref zk .
B.4 Time delay compensation 209
If the original and desired system have the same states, then C = I and the cost functional simplifies
to
(A − Aref )T Q(A − Aref ) (A − Aref )T QB
X∞ T | {z } | {z }
xk Q N xk
J= (B.6)
uk B Q(A − Aref )
T
B QB + R uk
T
k=0 | {z } | {z }
NT R
Let x = z.
xk+1 = zk+1
Axk + Buimf,k = Aref xk + Bref uk
Buimf,k = Aref xk − Axk + Bref uk
Buimf,k = (Aref − A)xk + Bref uk
uimf,k = B+ ((Aref − A)xk + Bref uk )
uimf,k = −B+ (A − Aref )xk + B+ Bref uk
The first term makes the open-loop poles match that of the reference model, and the second term
makes the input behave like that of the reference model.
time delays. During startup, the inputs we use to predict the future state are zero because there’s
initially no input history. This means the initial inputs are larger to give the system a kick in the right
direction. As the input delay buffer fills up, the controller gain converges to a smaller steady-state
value. If one uses the steady-state controller gain during startup, the transient response may be slow.
All figures shown here use the steady-state control law (the second case in equation (B.12)).
We’ll show how to derive this controller gain compensation for continuous and discrete systems.
u(t) = −Kx(t + L)
We need to find x(t + L) given x(t). Since we know u(t) = −Kx(t) will be applied over the time
interval [t, t + L), substitute it into the continuous model.
ẋ = Ax(t) + Bu(t)
ẋ = Ax(t) + B(−Kx(t))
ẋ = Ax(t) − BKx(t)
ẋ = (A − BK)x(t)
We now have a differential equation for the closed-loop system dynamics. Take the matrix exponential
from the current time t to L in the future to obtain x(t + L).
This works for t ≥ L, but if t < L, we have no input history for the time interval [t, L). If we
assume the inputs for [t, L) are zero, the state prediction for that interval is
The time interval [0, t) has nonzero inputs since it’s in the past and was using the normal control law.
Therefore, equations (B.7) and (B.8) give the latency-compensated control law for all t ≥ 0.
u(t) = −Kx(t + L)
(
−Ke(A−BK)t eA(L−t) x(t) if 0 ≤ t < L
u(t) = (B.9)
−Ke(A−BK)L x(t) if t ≥ L
uk = −Kxk+L/T
212 Appendix B. Linear-quadratic regulator
We need to find xk+L/T given xk . Since we know uk = −Kxk will be applied for the timesteps k
through k + TL , substitute it into the discrete model.
Let T be the duration between timesteps in seconds and L be the amount of time delay in seconds.
L
T gives the number of timesteps represented by L.
L
xk+L/T = (A − BK) T xk (B.10)
This works for kT ≥ L where kT is the current time, but if kT < L, we have no input history for
the time interval [kT, L). If we assume the inputs for [kT, L) are zero, the state prediction for that
interval is
L−kT
xL/T = A T xk
L
−k
xL/T = A T xk
The time interval [0, kT ) has nonzero inputs since it’s in the past and was using the normal control
law.
Therefore, equations (B.10) and (B.11) give the latency-compensated control law for all t ≥ 0.
uk = −Kxk+L/T
(
−K(A − BK)k A T −k xk
L
if 0 ≤ k < L
T
uk = L (B.12)
−K(A − BK) T xk if k ≥ L
T
If the delay L isn’t a multiple of the sample period T in equation (B.12), we have to evaluate frac-
tional matrix powers, which can be tricky. Eigen (a C++ library) supports fractional powers with the
pow() member function provided by <unsupported/Eigen/MatrixFunctions>. SciPy
(a Python library) supports fractional powers with the free function scipy.linalg.fractional_matrix_power
If the language you’re using doesn’t provide such a function, you can try the following approach in-
stead.
Let there be a matrix M raised to a fractional power n. If M is diagonalizable, we can obtain an
exact answer for Mn by decomposing M into PDP−1 where D is a diagonal matrix, computing
Dn as each diagonal element raised to n, then recomposing Mn as PDn P−1 .
If a matrix raised to a fractional power in equation (B.12) isn’t diagonalizable, we have to approximate
by rounding TL to the nearest integer. This approximation gets worse as L mod T approaches T2 .
Sunset in an airplane over New Mexico
C. Feedforwards
This appendix will show the derivations for alternate feedforward formulations.
where uk is the feedforward input. Note that this feedforward equation does not and should not take
into account any feedback terms. We want to find the optimal uk such that we minimize the tracking
error between rk+1 and rk .
rk+1 − Ark = Buk
To solve for uk , we need to take the inverse of the nonsquare matrix B. This isn’t possible, but we
can find the pseudoinverse given some constraints on the state tracking error and control effort. To
find the optimal solution for these sorts of trade-offs, one can define a cost function and attempt to
minimize it. To do this, we’ll first solve the expression for 0.
This expression will be the state tracking cost we use in our cost function.
Our cost function will use an H2 norm with Q as the state cost matrix with dimensionality states ×
states and R as the control input cost matrix with dimensionality inputs × inputs.
C.1.2 Minimization
Given theorem 5.12.1 and corollary 5.12.3, find the minimum of J by taking the partial derivative
with respect to uk and setting the result to 0.
∂J
= 2BT Q(Buk − (rk+1 − Ark )) + 2Ruk
∂uk
0 = 2BT Q(Buk − (rk+1 − Ark )) + 2Ruk
0 = BT Q(Buk − (rk+1 − Ark )) + Ruk
0 = BT QBuk − BT Q(rk+1 − Ark ) + Ruk
BT QBuk + Ruk = BT Q(rk+1 − Ark )
(BT QB + R)uk = BT Q(rk+1 − Ark )
uk = (BT QB + R)−1 BT Q(rk+1 − Ark )
Theorem C.1.1 — QR-weighted linear plant inversion. Given the discrete model xk+1 =
Axk + Buk , the plant inversion feedforward is
uk = Kf f (rk+1 − Ark )
where Kf f = (BT QB + R)−1 BT Q, rk+1 is the reference at the next timestep, and rk is the
reference at the current timestep.
Figure C.1 shows plant inversion applied to a second-order CIM motor model.
Plant inversion isn’t as effective with both Q and R cost because the R matrix penalized control
effort. The reference tracking with no cost matrices is much better.
C.2 Steady-state feedforward 215
Nx converts desired outputs yc to desired states xc (also known as r). For steady-state, that is
The second steady-state feedforward converts the desired outputs y to the control input required at
steady-state.
uc = Nu yc
Nu converts the desired outputs y to the control input u required at steady-state. For steady-state,
that is
uss = Nu yss (C.2)
ẋ = Ax + Bu
y = Cx + Du
0 = Axss + Buss
yss = Cxss + Duss
yk = Cxk + Duk
0 = (A − I)xss + Buss
yss = Cxss + Duss
xss = Nx yss
+
Nx xss = yss
uss = Nu yss
uss = Nu (N+
x xss )
uss = Nu N+
x xss
uf f = Nu N+
xr
Continuous:
+
Nx A B 0
= (C.3)
Nu C D 1
uf f = Nu N+
xr (C.4)
Discrete:
+
Nx A−I B 0
= (C.5)
Nu C D 1
uf f,k = Nu N+
x rk (C.6)
In the augmented matrix, B should contain one column corresponding to an actuator and C should
contain one row whose output will be driven by that actuator. More than one actuator or output can
be included in the computation at once, but the result won’t be the same as if they were computed
independently and summed afterward.
After computing the feedforward for each actuator-output pair, the respective collections of Nx
and Nu matrices can summed to produce the combined feedforward.
If the augmented matrix in theorem C.2.1 is square (number of inputs = number of outputs), the
normal matrix inverse can be used instead.
Case study: second-order CIM motor model
Each feedforward implementation has advantages. The steady-state feedforward allows using specific
actuators to maintain the reference at steady-state. Plant inversion doesn’t support this, but can be
used for reference tracking as well with the same tuning parameters as LQR design. Figure C.2 shows
both types of feedforwards applied to a second-order CIM motor model.
Figure C.2: Second-order CIM motor response Figure C.3: Second-order CIM motor response
with various feedforwards with plant inversions
Plant inversion isn’t as effective in figure C.2 because the R matrix penalized control effort. If the
R cost matrix is removed from the plant inversion calculation, the reference tracking is much better
(see figure C.3).
This page intentionally left blank
Sunset in an airplane over New Mexico
D. Derivations
which is an analytical solution to the continuous model. Now we want to discretize it.
def
xk = x(kT )
220 Appendix D. Derivations
Z kT
xk = e AkT
x(0) + eA(kT −τ ) Bu(τ ) dτ
0
Z (k+1)T
xk+1 = e A(k+1)T
x(0) + eA((k+1)T −τ ) Bu(τ ) dτ
0
Z kT Z (k+1)T
xk+1 = eA(k+1)T x(0) + eA((k+1)T −τ ) Bu(τ ) dτ + eA((k+1)T −τ ) Bu(τ ) dτ
0 kT
Z kT Z (k+1)T
xk+1 = eA(k+1)T x(0) + eA((k+1)T −τ ) Bu(τ ) dτ + eA(kT +T −τ ) Bu(τ ) dτ
0 kT
Z kT Z (k+1)T
xk+1 = eAT eAkT x(0) + eA(kT −τ ) Bu(τ ) dτ + eA(kT +T −τ ) Bu(τ ) dτ
0 kT
| {z }
xk
We assume that u is constant during each timestep, so it can be pulled out of the integral.
Z (k+1)T !
xk+1 = eAT xk + eA(kT +T −τ ) dτ Buk
kT
The second term can be simplified by substituting it with the function v(τ ) = kT + T − τ . Note
that dτ = −dv.
Z v((k+1)T ) !
xk+1 = eAT xk − eAv dv Buk
v(kT )
Z 0
xk+1 = e AT
xk − e Av
dv Buk
T
Z T
xk+1 = eAT xk + eAv dv Buk
0
xk+1 = eAT xk + A−1 eAv |T0 Buk
xk+1 = eAT xk + A−1 (eAT − eA0 )Buk
xk+1 = eAT xk + A−1 (eAT − I)Buk
where a superscript of minus denotes a priori and plus denotes a posteriori estimate. Combining
equation (D.1) and equation (D.2) gives
− −
k+1 = Ax̂k + Buk + L(yk − Cx̂k )
x̂+ (D.3)
The following is a Kalman filter that considers the current update step and the next predict step
together rather than the current predict step and current update step.
Update step
D.2 Kalman filter as Luenberger observer 221
K k = P− T − T
k C (CPk C + R)
−1
(D.4)
x̂+
k = x̂−
k + Kk (yk − Cx̂−
k) (D.5)
P+k = (I − Kk C)P−
k (D.6)
Predict step
x̂+ +
k+1 = Ax̂k + Buk (D.7)
P−
k+1 = AP+
kA
T
+Q (D.8)
Let L = AKk .
− −
k+1 = Ax̂k + Buk + L(yk − Cx̂k )
x̂+ (D.9)
which matches equation (D.3). Therefore, the eigenvalues of the Kalman filter observer can be ob-
tained by
eig(A − LC)
eig(A − (AKk )(C))
eig(A(I − Kk C)) (D.10)
The predict step is the same as the Kalman filter’s. Therefore, a Luenberger observer run with pre-
diction and update steps is written as follows.
Predict step
x̂− −
k+1 = Ax̂k + Buk (D.11)
Update step
− −1
k+1 = x̂k+1 + A L(yk+1 − ŷk+1 )
x̂+ (D.12)
ŷk+1 = Cx̂−
k+1 (D.13)
This page intentionally left blank
Sunset in an airplane over New Mexico
This appendix is provided for those who are curious about a lower-level interpretation of control
systems. It describes what a transfer function is and shows how they can be used to analyze dynamical
systems. Emphasis is placed on the geometric intuition of this analysis rather than the frequency
domain math. Many tools exclusive to classical control theory (root locus, Bode plots, Nyquist plots,
etc.) aren’t useful for or relevant to the examples presented in the main chapters, so they would only
complicate the learning process.
With classical control theory’s geometric interpretation, one can perform stability and robustness
analyses and design reasonable controllers for systems on the back of a napkin. However, computing
power is much more plentiful nowadays; we should take advantage of the modern tools this enables
to better express the controls designer’s intent (for example, via optimal control criteria rather than
frequency response characteristics).
Classical control theory should only be used when the controls designer cares about directly shaping
the frequency response of a system. Electrical engineers do this a lot, but all the other university
controls students have been forced to learn it too regardless of its utility in other disciplines.
[1]
This book primarily focuses on analysis and control of linear systems. See chapter 8 for more on nonlinear control.
224 Appendix E. Classical control theory
within which to understand results from the mathematical machinery of modern control as well as
vocabulary with which to communicate that understanding. For example, faster poles (poles moved
to the left in the s-plane) mean faster decay, and oscillation means there is at least one pair of complex
conjugate poles. Not only can you describe what happened succinctly, but you know why it happened
from a theoretical perspective.
This book uses LQR and modern control over, say, loop shaping with Bode and Nyquist plots be-
cause we have accurate dynamical models to leverage, and LQR allows directly expressing what the
author is concerned with optimizing: state excursion relative to control effort. Applying lead and
lag compensators, while effective for robust controller design, doesn’t provide the same expressive
power.
R Imaginary poles and zeroes always come in complex conjugate pairs (e.g., −2 + 3i, −2 − 3i).
[2]
We are handwaving Laplace transform derivations because they are complicated and neither relevant nor useful.
E.2 Transfer functions 225
The locations of the closed-loop poles in the complex plane determine the stability of the system.
Each pole represents a frequency mode of the system, and their location determines how much of
each response is induced for a given input frequency. Figure E.2 shows the impulse responses in the
time domain for transfer functions with various pole locations. They all have an initial condition of
1.
Im
Stable Unstable
t
t
t
LHP RHP
t
t t
Re
t t t
Poles in the left half-plane (LHP) are stable; the system’s output may oscillate but it converges to
steady-state. Poles on the imaginary axis are marginally stable; the system’s output oscillates at a
constant amplitude forever. Poles in the right half-plane (RHP) are unstable; the system’s output
grows without bound.
226 Appendix E. Classical control theory
Y (s) = Z(s)G(s)
Z(s) = X(s) − Y (s)H(s)
X(s) = Z(s) + Y (s)H(s)
X(s) = Z(s) + Z(s)G(s)H(s)
E.2 Transfer functions 227
+ Z(s)
X(s) G(s) Y (s)
−
H(s)
Y (s) Z(s)G(s)
=
X(s) Z(s) + Z(s)G(s)H(s)
Y (s) G(s)
= (E.2)
X(s) 1 + G(s)H(s)
where positive feedback uses the top sign and negative feedback uses the bottom sign.
Control system with feedback
+
X(s) K G Y (s)
−
Following equation (E.3), the transfer function of figure E.4, a control system diagram with negative
feedback, from input to output is
Y (s) KG
Gcl (s) = = (E.4)
X(s) 1 + KGH
The numerator is the open-loop gain and the denominator is one plus the gain around the feedback
loop, which may include parts of the open-loop gain. As another example, the transfer function from
the input to the error is
E(s) 1
Gcl (s) = = (E.5)
X(s) 1 + KGH
The roots of the denominator of Gcl (s) are different from those of the open-loop transfer function
KG(s). These are called the closed-loop poles.
228 Appendix E. Classical control theory
Compare the step response of this system (figure E.5) with the step response of this system with L set
to zero (figure E.6). For small values of K, both systems are stable and have nearly indistinguishable
step responses due to the exceedingly small contribution from the fast pole. The high frequency
dynamics only cause instability for large values of K that induce fast system responses. In other
words, the system responses of the second-order model and its first-order approximation are similar
for low frequency operating regimes.
Figure E.5: Step response of second-order DC Figure E.6: Step response of first-order DC
brushed motor plant augmented with position brushed motor plant augmented with position
(L = 230 μH) (L = 0 μH)
Why can’t unstable poles close to the origin be ignored in the same way? The response of high
frequency stable poles decays rapidly. Unstable poles, on the other hand, represent unstable dynamics
which cause the system output to grow to infinity. Regardless of how slow these unstable dynamics
are, they will eventually dominate the response.
[3]
This also has the effect of augmenting the system with a position state, making it a third-order system.
E.3 Laplace domain analysis 229
First, we will define mathematically what Laplace transforms and transfer functions are, which is
rooted in the concept of orthogonal projections.
E.3.1 Projections
Consider a two-dimensional Euclidean space R2 shown in figure E.7 (each R is a dimension whose
domain is the set of real numbers, so R2 is the standard x-y plane).
Ordinarily, we notate points in this plane by their components in the set of basis vectors {î, ĵ}, where
î (pronounced i-hat) is the unit vector in the positive x direction and ĵ is the unit vector in the positive
y direction. Figure E.8 shows an example vector v in this basis.
How do we find the coordinates of v in this basis mathematically? As long as the basis is orthogonal
(i.e., the basis vectors are at right angles to each other), we simply take the orthogonal projection of
v onto î and ĵ. Intuitively, this means finding “the amount of v that points in the direction of î or ĵ”.
Note that a set of orthogonal vectors have a dot product of zero with respect to each other.
More formally, we can calculate projections with the dot product - the projection of v onto any other
vector w is as follows.
v·w
projw v =
|w|
Since î and ĵ are unit vectors, their magnitudes are 1 so the coordinates of v are v · î and v · ĵ.
We can use this same process to find the coordinates of v in any orthogonal basis. For example,
imagine the basis {î + ĵ, î − ĵ} - the coordinates in this basis are given by v·(√î+2 ĵ) and v·(√î−2 ĵ) . Let’s
230 Appendix E. Classical control theory
2
v = 2î + 1.5ĵ
1.5
ĵ
x
î
“unwrap” the formula for dot product and look a bit more closely.
1 X
n
v · (î + ĵ)
√ =√ vi (î + ĵ)i
2 2 i=0
where the subscript i denotes which component of each vector and n is the total number of compo-
nents. To change coordinates, we expanded both v and î + ĵ in a basis, multiplied their components,
and added them up. Here’s a more concrete example. Let v = 2î + 1.5ĵ from figure E.8. First, we’ll
project v onto the î + ĵ basis vector.
v · (î + ĵ) 1
√ = √ (2î · î + 1.5ĵ · ĵ)
2 2
v · (î + ĵ) 1
√ = √ (2 + 1.5)
2 2
v · (î + ĵ) 3.5
√ =√
2 2
√
v · (î + ĵ) 3.5 2
√ =
2 2
v · (î + ĵ) √
√ = 1.75 2
2
v · (î − ĵ) 1
√ = √ (2î · î − 1.5ĵ · ĵ)
2 2
v · (î − ĵ) 1
√ = √ (2 − 1.5)
2 2
v · (î − ĵ) 0.5
√ =√
2 2
√
v · (î − ĵ) 0.5 2
√ =
2 2
E.3 Laplace domain analysis 231
v · (î − ĵ) √
√ = 0.25 2
2
Figure E.9 shows this result geometrically with respect to the basis {î + ĵ, î − ĵ}.
y
√
0.25 2
v
î + ĵ √
1.75 2
x
î − ĵ
The previous example was only a change of coordinates in a finite-dimensional vector space. However,
as we will see, the core idea does not change much when we move to more complicated structures.
Observe the formula for the Fourier transform.
Z ∞
ˆ
f (ξ) = f (x)e−2πixξ dx where ξ ∈ R
−∞
This is fundamentally the same formula we had before. f (x) has taken the place of vn , e−2πixξ has
taken the place of (î + ĵ)i , and the sum over i has turned into an integral over dx, but the underlying
concept is the same. To change coordinates in a function space, we simply take the orthogonal pro-
jection onto our new basis functions. In the case of the Fourier transform, the function basis is the
family of functions of the form f (x) = e−2πixξ for ξ ∈ R. Since these functions are oscillatory at a
frequency determined by ξ, we can think of this as a “frequency basis”.
R Watch the “Abstract vector spaces” video from 3Blue1Brown’s Essence of linear algebra series
(17 minutes) [3] for a more geometric introduction to using functions as a basis.
Now, the Laplace transform is somewhat more complicated - as it turns out, the Fourier basis is
orthogonal, so the analogy to the simpler vector space holds almost-precisely. The Laplace transform
is not orthogonal, so we can’t interpret it strictly as a change of coordinates in the traditional sense.
However, the intuition is the same: we are taking the orthogonal projection of our original function
onto the functions of our new basis set.
Z ∞
F (s) = f (t)e−st dt, where s ∈ C
0
Here, it becomes obvious that the Laplace transform is a generalization of the Fourier transform in
that the basis family is strictly larger (we have allowed the “frequency” parameter to take complex
values, as opposed to merely real values). As a result, the Laplace basis contains functions that grow
and decay, while the Fourier basis does not.
232 Appendix E. Classical control theory
Note that this explanation as a basis isn’t exact because the Laplace basis isn’t orthogonal (that is,
the x and y coordinates affect each other and have cross-talk). In the frequency domain, we had a
basis of sine waves that we represented as delta functions in the frequency domain. Each frequency
contribution was independent of the others. In the Laplace domain, this is not the case; a pure
1
exponential is s−a (a rational function where a is a real number) instead of a delta function. This
function is nonzero at points that aren’t actually frequencies present in the time domain. Figure E.14
demonstrates this, which shows the Laplace transform of the Fmajor4 chord plotted in 3D.
Notice how the values of the function around each component frequency decrease according to
√ 1 in the x and y directions (in just the x direction, it would be x1 ).
2
x +y2
We won’t be computing any Laplace transforms by hand using this formula (everyone in the real world
looks these up in a table anyway). Common Laplace transforms (assuming zero initial conditions)
are shown in table E.1. Of particular note are the Laplace transforms for the derivative, unit step,[5]
and exponential decay. We can see that a derivative is equivalent to multiplying by s, and an integral
is equivalent to multiplying by 1s .
[5]
The unit step u(t) is defined as 0 for t < 0 and 1 for t ≥ 0.
234 Appendix E. Classical control theory
Im(jω)
Re(σ)
Table E.1: Common Laplace transforms and Laplace transform properties with zero initial conditions
velocity (θ̇) of
Θ̇(s) K
G(s) = = (E.7)
V (s) (Js + b)(Ls + R) + K 2
K(s) = Kp
When these are in unity feedback, the transfer function from the input voltage to the error is
E(s) 1
=
V (s) 1 + K(s)G(s)
1
E(s) = V (s)
1 + K(s)G(s)
1
E(s) = V (s)
K
1 + (Kp ) (Js+b)(Ls+R)+K 2
1
E(s) = Kp K
V (s)
1+ (Js+b)(Ls+R)+K 2
E.3 Laplace domain analysis 235
Notice that the steady-state error is nonzero. To fix this, an integrator must be included in the con-
troller.
Ki
K(s) = Kp +
s
The same steady-state calculations are performed as before with the new controller.
E(s) 1
=
V (s) 1 + K(s)G(s)
1
E(s) = V (s)
1 + K(s)G(s)
1 1
E(s) =
1 + Kp + Ksi K s
(Js+b)(Ls+R)+K 2
1 1
ess = lim s
s→0
1 + Kp + Ksi K s
(Js+b)(Ls+R)+K 2
1
ess = lim
s→0 Ki K
1 + Kp + s (Js+b)(Ls+R)+K 2
1 s
ess = lim
s→0
1 + Kp + Ki K s
s (Js+b)(Ls+R)+K 2
s
ess = lim
s→0 K
s + (Kp s + Ki ) (Js+b)(Ls+R)+K 2
0
ess =
K
0 + (Kp (0) + Ki ) (J(0)+b)(L(0)+R)+K 2
0
ess = K
Ki bR+K 2
E.3 Laplace domain analysis 237
For an explanation of where these equations come from, read section 12.1.
dω
First, we’ll solve for dt in terms of V .
Substitute equation (E.11) into equation (E.10).
ω
V = IR +
K
v
τ ω
V = R+
Kt Kv
J dω
dt ω
V = R+
Kt Kv
238 Appendix E. Classical control theory
ω J dω
V − = dt R
Kv Kt
dω Kt ω
= V −
dt JR Kv
dω Kt Kt
=− ω+ V
dt JRKv JR
Now take the Laplace transform. Because the Laplace transform is a linear operator, we can take the
Laplace transform of each term individually. Based on table E.1, dω
dt becomes sω and ω(t) and V (t)
become ω(s) and V (s) respectively (the parenthetical notation has been dropped for clarity).
Kt Kt
sω = − ω+ V (E.13)
JRKv JR
ω
Solve for the transfer function H(s) = V.
Kt Kt
sω = − ω+ V
JRKv JR
Kt Kt
s+ ω= V
JRKv JR
Kt
ω JR
= Kt
V s + JRK v
V = Kp (ωgoal − ω)
Kt K t Kp
ω+ sω = − (ωgoal − ω)
JRKv JR
Kt K t Kp Kt Kp
sω = − ω+ ωgoal − ω
JRKv JR JR
Kt Kt Kp Kt Kp
s+ + ω= ωgoal
JRKv JR JR
Kt Kp
ω
= JR
ωgoal s+ Kt
+
Kt Kp
JRKv JR
Kt Kp
This has a pole at − Kt
JRKv + JR . Assuming that that quantity is negative (i.e., we are stable),
1
that pole corresponds to a time constant of Kt Kt Kp .
JRKv
+ JR
E.3 Laplace domain analysis 239
As can be seen above, a flywheel has a single pole. It therefore only needs a single pole controller to
place that pole anywhere on the real axis.
This analysis assumes that the motor is well coupled to the mass and that the time constant of the
inductor is small enough that it doesn’t factor into the motor equations. The latter is a pretty good
assumption for a CIM motor (see figures E.15 and E.16). If more mass is added to the motor armature,
the response timescales increase and the inductance matters even less.
Figure E.15: Step response of second-order DC Figure E.16: Step response of first-order DC
brushed motor plant augmented with position brushed motor plant augmented with position
(L = 230 μH) (L = 0 μH)
Next, we’ll try a PD loop. (This will use a perfect derivative, but anyone following along closely
already knows that we can’t really take a derivative here, so the math will need to be updated at some
point. We could switch to discrete time and pick a differentiation method, or pick some other way
of modeling the derivative.)
V = Kp (ωgoal − ω) + Kd s(ωgoal − ω)
Kt Kd s Kt Kt Kp Kt Kp Kt Kd s
sω + ω+ ω+ ω= ωgoal + ωgoal
JR JRKv JR JR JR
Kt Kd s Kt K t Kp Kt Kp Kt Kd s
s+ + + ω= + ωgoal
JR JRKv JR JR JR
Kt K d Kt K t Kp Kt
s 1+ + + ω= (Kp + Kd s) ωgoal
JR JRKv JR JR
240 Appendix E. Classical control theory
ω
Solve for ωgoal .
Kt
ω
JR (K
p + Kd s)
=
ωgoal s 1+ Kt Kd Kt
+ JRK
Kt Kp
+ JR
JR v
Kt Kt Kp
K +
So, we added a zero at − Kpd and moved our pole to − JRKvKt KJR
d
. This isn’t progress. We’ve added
1+ JR
more complexity to our system and, practically speaking, gotten nothing good in return. Zeroes
should be avoided if at all possible because they amplify unwanted high frequency modes of the
system and are noisier the faster the system is sampled. At least this is a stable zero, but it’s still
undesirable.
In summary, derivative doesn’t help on an ideal flywheel. Kd may compensate for unmodeled dy-
namics such as accelerating projectiles slowing the flywheel down, but that effect may also increase
recovery time; Kd drives the acceleration to zero in the undesired case of negative acceleration as
well as well as the actually desired case of positive acceleration.
Subsection 6.7.2 covers a superior compensation method that avoids zeroes in the controller, doesn’t
act against the desired control action, and facilitates better tracking.
s-plane z-plane
(0, 0) (1, 0)
imaginary axis edge of unit circle
(−∞, 0) (0, 0)
Figure E.17: Mapping of complex plane from s-plane (left) to z-plane (right)
Figure E.18: Single poles in various locations in Figure E.19: Complex conjugate poles in vari-
z-plane ous locations in z-plane
Figure E.20: Zero-order hold of a system re- Figure E.21: Discretization methods applied to
sponse velocity data
Forward Euler 1 + Ts 1 + Ts
1
Backward Euler 1−T s 1 + T s + T 2 s2 + T 3 s3 + . . .
Table E.3: Taylor series expansions of discretization methods (scalar case). The zero-order hold
discretization method is exact.
244 Appendix E. Classical control theory
Figure E.23: Sampling methods for system sim- Figure E.24: Sampling methods for system sim-
ulation with T = 0.1 s ulation with T = 0.05 s
Glossary
agent An independent actor being controlled through autonomy or human-in-the-loop (e.g., a robot,
aircraft, etc.).
control effort A term describing how much force, pressure, etc. an actuator is exerting.
control input The input of a plant used for the purpose of controlling it.
control law Also known as control policy, is a mathematical formula used by the controller to deter-
mine the input u that is sent to the plant. This control law is designed to drive the system
from its current state to some other desired state.
control system Monitors and controls the behavior of a system.
controller Applies an input to a plant to bring about a desired system state by driving the difference
between a reference signal and the output to zero.
discretization The process by which a continuous (e.g., analog) system or controller design is con-
verted to discrete (e.g., digital).
disturbance An external force acting on a system that isn’t included in the system’s model.
disturbance rejection The quality of a feedback control system to compensate for external forces
to reach a desired reference.
error Reference minus an output or state.
feedback controller Used in positive or negative feedback with a plant to bring about a desired
system state by driving the difference between a reference signal and the output to zero.
feedback gain The gain from the output to an earlier point in a control system diagram.
feedforward controller A controller that injects information about the system’s dynamics (like a
model does) or the desired movement. The feedforward handles parts of the control actions
we already know must be applied to make a system track a reference, then the feedback
controller compensates for what we do not or cannot know about the system’s behavior at
runtime.
gain A proportional value that shows the relationship between the magnitude of an input signal to
the magnitude of an output signal at steady-state.
248 Glossary
linearization A method by which a nonlinear system’s dynamics are approximated by a linear system.
localization The process of using measurements of the environment to determine an agent’s pose.
model A set of mathematical equations that reflects some aspect of a physical system’s behavior.
noise immunity The quality of a system to have its performance or stability unaffected by noise in
the outputs (see also: robustness).
observer In control theory, a system that estimates the internal state of a given real system from
measurements of the input and output of the real system.
open-loop gain The gain directly from the input to the output, ignoring loops.
output Measurements from sensors.
output-based control Controls the system’s state via the outputs.
overshoot The amount by which a system’s state surpasses the reference after rising toward it.
time-invariant The system’s fundamental response does not change over time.
Glossary 249
tracking In control theory, the process of making the output of a control system follow the reference.
unity feedback A feedback network in a control system diagram with a feedback gain of 1.
This page intentionally left blank
Sunset near Porter Academic building at UCSC
Bibliography
Online
[1] FRC team 254. Motion Planning and Control in FRC. 2015. URL: https://www.youtube.com/
watch?v=8319J1BEHwM (cited on page 186).
[2] 3Blue1Brown. What is Euler’s formula actually saying? | Ep. 4 Lockdown live math. 2020. URL:
https://www.youtube.com/watch?v=ZxYOEwM6Wbk (cited on page 36).
[3] 3Blue1Brown. Abstract vector spaces. 2022. URL: https://www.3blue1brown.com/lessons/
abstract-vector-spaces (cited on page 231).
[4] 3Blue1Brown. Eigenvectors and eigenvalues. 2022. URL: https : / / www . 3blue1brown . com /
lessons/eigenvalues (cited on page 28).
[5] 3Blue1Brown. Essence of calculus. 2022. URL: https://www.3blue1brown.com/topics/calculus
(cited on page 21).
[6] 3Blue1Brown. Essence of linear algebra preview. 2022. URL: https://www.3blue1brown.com/
lessons/eola-preview (cited on page 27).
[7] 3Blue1Brown. How (and why) to raise e to the power of a matrix. 2022. URL: https://www.
3blue1brown.com/lessons/matrix-exponents (cited on page 62).
[8] 3Blue1Brown. Inverse matrices, column space, and null space. 2022. URL: https : / / www .
3blue1brown.com/lessons/inverse-matrices (cited on page 28).
[9] 3Blue1Brown. Linear combinations, span, and basis vectors. 2022. URL: https://www.3blue1brown.
com/lessons/span (cited on page 27).
[10] 3Blue1Brown. Linear transformations and matrices. 2022. URL: https://www.3blue1brown.
com/lessons/linear-transformations (cited on page 27).
[11] 3Blue1Brown. Matrix multiplication as composition. 2022. URL: https://www.3blue1brown.
com/lessons/matrix-multiplication (cited on page 27).
[12] 3Blue1Brown. Nonsquare matrices as transformations between dimensions. 2022. URL: https:
//www.3blue1brown.com/lessons/nonsquare-matrices (cited on page 28).
[13] 3Blue1Brown. Taylor series. 2022. URL: https://www.3blue1brown.com/lessons/taylor-series
(cited on page 61).
252 Bibliography
[33] Zach Star. What does the Laplace Transform really tell us? A visual explanation (plus applica-
tions). 2019. URL: https://www.youtube.com/watch?v=n2y7n6jw5d0 (cited on page 224).
[34] Russ Tedrake. 6.832 Underactuated Robotics. 2019. URL: https://www.youtube.com/channel/
UChfUOAhz7ynELF-s_1LPpWg/videos (cited on page 99).
[35] Russ Tedrake. Underactuated Robotics. 2019. URL: https://underactuated.mit.edu (cited on
page 99).
[36] Russ Tedrake. Chapter 9. Linear Quadratic Regulators. URL: https://underactuated.mit.edu/
lqr.html (visited on 03/22/2020) (cited on page 205).
[37] Gabriel A. Terejanu. Unscented Kalman Filter Tutorial. URL: https : / / web . archive . org /
web / 20220000000000 * /https : / / cse . sc . edu / ~terejanu / files / tutorialUKF . pdf (visited on
09/28/2022) (cited on page 132).
[38] Michael Triantafyllou. lec19.pdf | Maneuvering and Control of Surface and Underwater Vehi-
cles (13.49). URL: https://ocw.mit.edu/courses/2-154-maneuvering-and-control-of-surface-
and-underwater-vehicles-13-49-fall-2004/resources/lec19/ (visited on 04/02/2022) (cited
on page 69).
[39] Jeffrey Uhlmann. First-Hand:The Unscented Transform. URL: https://ethw.org/First- Hand:
The_Unscented_Transform (visited on 07/27/2021) (cited on page 132).
[40] Eric A. Wan and Rudolph van der Merwe. The Unscented Kalman Filter for Nonlinear Esti-
mation. URL: https://groups.seas.harvard.edu/courses/cs281/papers/unscented.pdf (visited on
06/26/2018) (cited on page 132).
This page intentionally left blank
Sunset near Porter Academic building at UCSC
Index