Merge "Third robot commit."
diff --git a/NO_BUILD_ROBORIO b/NO_BUILD_ROBORIO
index f056f6b..839238a 100644
--- a/NO_BUILD_ROBORIO
+++ b/NO_BUILD_ROBORIO
@@ -1,6 +1,7 @@
 -@slycot_repo//...
 -//frc971/control_loops/python/...
 -//y2012/control_loops/python/...
+-//y2014_bot3/control_loops/python/...
 -//y2014/control_loops/python/...
 -//y2014_bot3/control_loops/python/...
 -//y2015/control_loops/python/...
diff --git a/aos/common/event.cc b/aos/common/event.cc
index ae32d39..af9c9c5 100644
--- a/aos/common/event.cc
+++ b/aos/common/event.cc
@@ -11,25 +11,28 @@
 }
 
 void Event::Wait() {
-  int ret;
-  do {
-    ret = futex_wait(&impl_);
-  } while (ret == 1);
-  if (ret == 0) return;
-  CHECK_EQ(-1, ret);
-  PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+  while (__atomic_load_n(&impl_, __ATOMIC_SEQ_CST) == 0) {
+    const int ret = futex_wait(&impl_);
+    if (ret != 0) {
+      CHECK_EQ(-1, ret);
+      PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+    }
+  }
 }
 
 bool Event::WaitTimeout(const ::aos::time::Time &timeout) {
   const auto timeout_timespec = timeout.ToTimespec();
-  int ret;
-  do {
-    ret = futex_wait_timeout(&impl_, &timeout_timespec);
-  } while (ret == 1);
-  if (ret == 0) return true;
-  if (ret == 2) return false;
-  CHECK_EQ(-1, ret);
-  PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+  while (true) {
+    if (__atomic_load_n(&impl_, __ATOMIC_SEQ_CST) != 0) {
+      return true;
+    }
+    const int ret = futex_wait_timeout(&impl_, &timeout_timespec);
+    if (ret != 0) {
+      if (ret == 2) return false;
+      CHECK_EQ(-1, ret);
+      PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+    }
+  }
 }
 
 // We're not going to expose the number woken because that's not easily portable
diff --git a/aos/common/time.h b/aos/common/time.h
index 40b72b0..ba795a9 100644
--- a/aos/common/time.h
+++ b/aos/common/time.h
@@ -28,8 +28,10 @@
 
   // Returns the epoch (0).
   static constexpr monotonic_clock::time_point epoch() {
-    return time_point(duration(0));
+    return time_point(zero());
   }
+
+  static constexpr monotonic_clock::duration zero() { return duration(0); }
 };
 
 namespace time {
@@ -146,8 +148,10 @@
   }
 
   // Construct a time representing the period of hertz.
-  static constexpr Time FromRate(int hertz) {
-    return Time(0, kNSecInSec / hertz);
+  static constexpr ::std::chrono::nanoseconds FromRate(int hertz) {
+    return ::std::chrono::duration_cast<::std::chrono::nanoseconds>(
+               ::std::chrono::seconds(1)) /
+           hertz;
   }
 
   // Checks whether or not this time is within amount nanoseconds of other.
diff --git a/aos/common/time_test.cc b/aos/common/time_test.cc
index 3ae82ab..e1811db 100644
--- a/aos/common/time_test.cc
+++ b/aos/common/time_test.cc
@@ -255,7 +255,7 @@
 }
 
 TEST(TimeTest, FromRate) {
-  EXPECT_EQ(MACRO_DARG(Time(0, Time::kNSecInSec / 100)), Time::FromRate(100));
+  EXPECT_EQ(::std::chrono::milliseconds(10), Time::FromRate(100));
 }
 
 // Test the monotonic_clock and sleep_until functions.
diff --git a/aos/common/type_traits.h b/aos/common/type_traits.h
index 4b5fa8c..53fae23 100644
--- a/aos/common/type_traits.h
+++ b/aos/common/type_traits.h
@@ -12,7 +12,7 @@
 struct has_trivial_copy_assign : public std::integral_constant<bool,
 // This changed between 4.4.5 and 4.6.3. Unless somebody discovers otherwise,
 // 4.6 seems like a reasonable place to switch.
-#if ((__GNUC__ < 4) || (__GNUC_MINOR__ < 6)) && !defined(__clang__)
+#if ((__GNUC__ < 4) || (__GNUC__ == 4 && __GNUC_MINOR__ < 6)) && !defined(__clang__)
     ::std::has_trivial_assign<Tp>::value> {};
 #else
     ::std::has_trivial_copy_assign<Tp>::value> {};
diff --git a/aos/common/util/phased_loop.cc b/aos/common/util/phased_loop.cc
index b5804c8..9c81ffb 100644
--- a/aos/common/util/phased_loop.cc
+++ b/aos/common/util/phased_loop.cc
@@ -10,15 +10,21 @@
              frequency + Time::InUS(offset));
 }
 
-int PhasedLoop::Iterate(const Time &now) {
-  const Time next_time = Time::InNS(((now - offset_).ToNSec() + 1) /
-                                    interval_.ToNSec() * interval_.ToNSec()) +
-                         ((now < offset_) ? Time::kZero : interval_) + offset_;
+int PhasedLoop::Iterate(const monotonic_clock::time_point now) {
+  const monotonic_clock::time_point next_time =
+      monotonic_clock::time_point(
+          (((now - offset_).time_since_epoch() + monotonic_clock::duration(1)) /
+           interval_) *
+          interval_) +
+      ((now.time_since_epoch() < offset_) ? monotonic_clock::zero()
+                                          : interval_) +
+      offset_;
 
-  const Time difference = next_time - last_time_;
-  const int result = difference.ToNSec() / interval_.ToNSec();
+  const monotonic_clock::duration difference = next_time - last_time_;
+  const int result = difference / interval_;
   CHECK_EQ(difference, interval_ * result);
-  CHECK_EQ(0, (next_time - offset_).ToNSec() % interval_.ToNSec());
+  CHECK_EQ(
+      0, (next_time - offset_).time_since_epoch().count() % interval_.count());
   CHECK_GE(next_time, now);
   CHECK_LE(next_time - now, interval_);
   last_time_ = next_time;
diff --git a/aos/common/util/phased_loop.h b/aos/common/util/phased_loop.h
index fc0f247..7614ed2 100644
--- a/aos/common/util/phased_loop.h
+++ b/aos/common/util/phased_loop.h
@@ -22,40 +22,47 @@
   //   ...
   //   10000.1s
   // offset must be >= Time::kZero and < interval.
-  PhasedLoop(const Time &interval, const Time &offset = Time::kZero)
+  PhasedLoop(
+      const monotonic_clock::duration interval,
+      const monotonic_clock::duration offset = monotonic_clock::duration(0))
       : interval_(interval), offset_(offset), last_time_(offset) {
-    CHECK_GE(offset, Time::kZero);
-    CHECK_GT(interval, Time::kZero);
+    CHECK_GE(offset, monotonic_clock::duration(0));
+    CHECK_GT(interval, monotonic_clock::duration(0));
     CHECK_LT(offset, interval);
     Reset();
   }
 
   // Resets the count of skipped iterations.
-  // Iterate(now) will return 1 and set sleep_time() to something within
-  // interval of now.
-  void Reset(const Time &now = Time::Now()) { Iterate(now - interval_); }
+  // Iterate(monotonic_now) will return 1 and set sleep_time() to something
+  // within interval of monotonic_now.
+  void Reset(const monotonic_clock::time_point monotonic_now =
+                 monotonic_clock::now()) {
+    Iterate(monotonic_now - interval_);
+  }
 
-  // Calculates the next time to run after now.
+  // Calculates the next time to run after monotonic_now.
   // The result can be retrieved with sleep_time().
   // Returns the number of iterations which have passed (1 if this is called
-  // often enough). This can be < 1 iff now goes backwards between calls.
-  int Iterate(const Time &now = Time::Now());
+  // often enough). This can be < 1 iff monotonic_now goes backwards between
+  // calls.
+  int Iterate(const monotonic_clock::time_point monotonic_now =
+                  monotonic_clock::now());
 
   // Sleeps until the next time and returns the number of iterations which have
   // passed.
   int SleepUntilNext() {
-    const int r = Iterate(Time::Now());
-    SleepUntil(sleep_time());
+    const int r = Iterate(monotonic_clock::now());
+    ::std::this_thread::sleep_until(sleep_time());
     return r;
   }
 
-  const Time &sleep_time() const { return last_time_; }
+  monotonic_clock::time_point sleep_time() const { return last_time_; }
 
  private:
-  const Time interval_, offset_;
+  const monotonic_clock::duration interval_, offset_;
 
   // The time we most recently slept until.
-  Time last_time_ = Time::kZero;
+  monotonic_clock::time_point last_time_ = monotonic_clock::epoch();
 };
 
 }  // namespace time
diff --git a/aos/common/util/phased_loop_test.cc b/aos/common/util/phased_loop_test.cc
index 1641a92..b013c2e 100644
--- a/aos/common/util/phased_loop_test.cc
+++ b/aos/common/util/phased_loop_test.cc
@@ -8,111 +8,115 @@
 namespace time {
 namespace testing {
 
+using ::std::chrono::milliseconds;
+
 class PhasedLoopTest : public ::testing::Test {
  protected:
-  PhasedLoopTest() {
-    ::aos::testing::EnableTestLogging();
-  }
+  PhasedLoopTest() { ::aos::testing::EnableTestLogging(); }
 };
 
 typedef PhasedLoopTest PhasedLoopDeathTest;
 
+monotonic_clock::time_point InMs(int ms) {
+  return monotonic_clock::time_point(::std::chrono::milliseconds(ms));
+}
+
 TEST_F(PhasedLoopTest, Reset) {
   {
-    PhasedLoop loop(Time::InMS(100), Time::kZero);
+    PhasedLoop loop(milliseconds(100), milliseconds(0));
 
-    loop.Reset(Time::kZero);
-    EXPECT_EQ(Time::InMS(0), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::kZero));
-    EXPECT_EQ(Time::InMS(100), loop.sleep_time());
+    loop.Reset(monotonic_clock::epoch());
+    EXPECT_EQ(InMs(0), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+    EXPECT_EQ(InMs(100), loop.sleep_time());
 
-    loop.Reset(Time::InMS(99));
-    EXPECT_EQ(Time::InMS(0), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(99)));
-    EXPECT_EQ(Time::InMS(100), loop.sleep_time());
+    loop.Reset(InMs(99));
+    EXPECT_EQ(InMs(0), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(99)));
+    EXPECT_EQ(InMs(100), loop.sleep_time());
 
-    loop.Reset(Time::InMS(100));
-    EXPECT_EQ(Time::InMS(100), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(199)));
-    EXPECT_EQ(Time::InMS(200), loop.sleep_time());
+    loop.Reset(InMs(100));
+    EXPECT_EQ(InMs(100), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(199)));
+    EXPECT_EQ(InMs(200), loop.sleep_time());
 
-    loop.Reset(Time::InMS(101));
-    EXPECT_EQ(Time::InMS(100), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(101)));
-    EXPECT_EQ(Time::InMS(200), loop.sleep_time());
+    loop.Reset(InMs(101));
+    EXPECT_EQ(InMs(100), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(101)));
+    EXPECT_EQ(InMs(200), loop.sleep_time());
   }
   {
-    PhasedLoop loop(Time::InMS(100), Time::InMS(1));
-    loop.Reset(Time::kZero);
-    EXPECT_EQ(Time::InMS(-99), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::kZero));
-    EXPECT_EQ(Time::InMS(1), loop.sleep_time());
+    PhasedLoop loop(milliseconds(100), milliseconds(1));
+    loop.Reset(monotonic_clock::epoch());
+    EXPECT_EQ(InMs(-99), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+    EXPECT_EQ(InMs(1), loop.sleep_time());
   }
   {
-    PhasedLoop loop(Time::InMS(100), Time::InMS(99));
+    PhasedLoop loop(milliseconds(100), milliseconds(99));
 
-    loop.Reset(Time::kZero);
-    EXPECT_EQ(Time::InMS(-1), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::kZero));
-    EXPECT_EQ(Time::InMS(99), loop.sleep_time());
+    loop.Reset(monotonic_clock::epoch());
+    EXPECT_EQ(InMs(-1), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+    EXPECT_EQ(InMs(99), loop.sleep_time());
 
-    loop.Reset(Time::InMS(98));
-    EXPECT_EQ(Time::InMS(-1), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(98)));
-    EXPECT_EQ(Time::InMS(99), loop.sleep_time());
+    loop.Reset(InMs(98));
+    EXPECT_EQ(InMs(-1), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(98)));
+    EXPECT_EQ(InMs(99), loop.sleep_time());
 
-    loop.Reset(Time::InMS(99));
-    EXPECT_EQ(Time::InMS(99), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(99)));
-    EXPECT_EQ(Time::InMS(199), loop.sleep_time());
+    loop.Reset(InMs(99));
+    EXPECT_EQ(InMs(99), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(99)));
+    EXPECT_EQ(InMs(199), loop.sleep_time());
 
-    loop.Reset(Time::InMS(100));
-    EXPECT_EQ(Time::InMS(99), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(100)));
-    EXPECT_EQ(Time::InMS(199), loop.sleep_time());
+    loop.Reset(InMs(100));
+    EXPECT_EQ(InMs(99), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(100)));
+    EXPECT_EQ(InMs(199), loop.sleep_time());
   }
 }
 
 TEST_F(PhasedLoopTest, Iterate) {
   {
-    PhasedLoop loop(Time::InMS(100), Time::InMS(99));
-    loop.Reset(Time::kZero);
-    EXPECT_EQ(1, loop.Iterate(Time::kZero));
-    EXPECT_EQ(Time::InMS(99), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(100)));
-    EXPECT_EQ(Time::InMS(199), loop.sleep_time());
-    EXPECT_EQ(0, loop.Iterate(Time::InMS(100)));
-    EXPECT_EQ(Time::InMS(199), loop.sleep_time());
-    EXPECT_EQ(0, loop.Iterate(Time::InMS(101)));
-    EXPECT_EQ(Time::InMS(199), loop.sleep_time());
-    EXPECT_EQ(0, loop.Iterate(Time::InMS(198)));
-    EXPECT_EQ(Time::InMS(199), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(199)));
-    EXPECT_EQ(Time::InMS(299), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(300)));
-    EXPECT_EQ(Time::InMS(399), loop.sleep_time());
-    EXPECT_EQ(3, loop.Iterate(Time::InMS(600)));
-    EXPECT_EQ(Time::InMS(699), loop.sleep_time());
+    PhasedLoop loop(milliseconds(100), milliseconds(99));
+    loop.Reset(monotonic_clock::epoch());
+    EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+    EXPECT_EQ(InMs(99), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(100)));
+    EXPECT_EQ(InMs(199), loop.sleep_time());
+    EXPECT_EQ(0, loop.Iterate(InMs(100)));
+    EXPECT_EQ(InMs(199), loop.sleep_time());
+    EXPECT_EQ(0, loop.Iterate(InMs(101)));
+    EXPECT_EQ(InMs(199), loop.sleep_time());
+    EXPECT_EQ(0, loop.Iterate(InMs(198)));
+    EXPECT_EQ(InMs(199), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(199)));
+    EXPECT_EQ(InMs(299), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(300)));
+    EXPECT_EQ(InMs(399), loop.sleep_time());
+    EXPECT_EQ(3, loop.Iterate(InMs(600)));
+    EXPECT_EQ(InMs(699), loop.sleep_time());
   }
   {
-    PhasedLoop loop(Time::InMS(100), Time::InMS(1));
-    loop.Reset(Time::kZero);
-    EXPECT_EQ(1, loop.Iterate(Time::kZero));
-    EXPECT_EQ(Time::InMS(1), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(100)));
-    EXPECT_EQ(Time::InMS(101), loop.sleep_time());
-    EXPECT_EQ(0, loop.Iterate(Time::InMS(100)));
-    EXPECT_EQ(Time::InMS(101), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(103)));
-    EXPECT_EQ(Time::InMS(201), loop.sleep_time());
-    EXPECT_EQ(0, loop.Iterate(Time::InMS(198)));
-    EXPECT_EQ(Time::InMS(201), loop.sleep_time());
-    EXPECT_EQ(0, loop.Iterate(Time::InMS(200)));
-    EXPECT_EQ(Time::InMS(201), loop.sleep_time());
-    EXPECT_EQ(1, loop.Iterate(Time::InMS(201)));
-    EXPECT_EQ(Time::InMS(301), loop.sleep_time());
-    EXPECT_EQ(3, loop.Iterate(Time::InMS(600)));
-    EXPECT_EQ(Time::InMS(601), loop.sleep_time());
+    PhasedLoop loop(milliseconds(100), milliseconds(1));
+    loop.Reset(monotonic_clock::epoch());
+    EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+    EXPECT_EQ(InMs(1), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(100)));
+    EXPECT_EQ(InMs(101), loop.sleep_time());
+    EXPECT_EQ(0, loop.Iterate(InMs(100)));
+    EXPECT_EQ(InMs(101), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(103)));
+    EXPECT_EQ(InMs(201), loop.sleep_time());
+    EXPECT_EQ(0, loop.Iterate(InMs(198)));
+    EXPECT_EQ(InMs(201), loop.sleep_time());
+    EXPECT_EQ(0, loop.Iterate(InMs(200)));
+    EXPECT_EQ(InMs(201), loop.sleep_time());
+    EXPECT_EQ(1, loop.Iterate(InMs(201)));
+    EXPECT_EQ(InMs(301), loop.sleep_time());
+    EXPECT_EQ(3, loop.Iterate(InMs(600)));
+    EXPECT_EQ(InMs(601), loop.sleep_time());
   }
 }
 
@@ -120,40 +124,42 @@
 // This seems like a rare case at first, but starting from zero needs to
 // work, which means negatives should too.
 TEST_F(PhasedLoopTest, CrossingZero) {
-  PhasedLoop loop(Time::InMS(100), Time::InMS(1));
-  loop.Reset(Time::InMS(-1000));
-  EXPECT_EQ(Time::InMS(-1099), loop.sleep_time());
-  EXPECT_EQ(9, loop.Iterate(Time::InMS(-250)));
-  EXPECT_EQ(Time::InMS(-199), loop.sleep_time());
-  EXPECT_EQ(1, loop.Iterate(Time::InMS(-199)));
-  EXPECT_EQ(Time::InMS(-99), loop.sleep_time());
-  EXPECT_EQ(1, loop.Iterate(Time::InMS(-90)));
-  EXPECT_EQ(Time::InMS(1), loop.sleep_time());
-  EXPECT_EQ(0, loop.Iterate(Time::InMS(0)));
-  EXPECT_EQ(Time::InMS(1), loop.sleep_time());
-  EXPECT_EQ(1, loop.Iterate(Time::InMS(1)));
-  EXPECT_EQ(Time::InMS(101), loop.sleep_time());
+  PhasedLoop loop(milliseconds(100), milliseconds(1));
+  loop.Reset(InMs(-1000));
+  EXPECT_EQ(InMs(-1099), loop.sleep_time());
+  EXPECT_EQ(9, loop.Iterate(InMs(-250)));
+  EXPECT_EQ(InMs(-199), loop.sleep_time());
+  EXPECT_EQ(1, loop.Iterate(InMs(-199)));
+  EXPECT_EQ(InMs(-99), loop.sleep_time());
+  EXPECT_EQ(1, loop.Iterate(InMs(-90)));
+  EXPECT_EQ(InMs(1), loop.sleep_time());
+  EXPECT_EQ(0, loop.Iterate(InMs(0)));
+  EXPECT_EQ(InMs(1), loop.sleep_time());
+  EXPECT_EQ(1, loop.Iterate(InMs(1)));
+  EXPECT_EQ(InMs(101), loop.sleep_time());
 
-  EXPECT_EQ(0, loop.Iterate(Time::InMS(2)));
-  EXPECT_EQ(Time::InMS(101), loop.sleep_time());
+  EXPECT_EQ(0, loop.Iterate(InMs(2)));
+  EXPECT_EQ(InMs(101), loop.sleep_time());
 
-  EXPECT_EQ(-2, loop.Iterate(Time::InMS(-101)));
-  EXPECT_EQ(Time::InMS(-99), loop.sleep_time());
-  EXPECT_EQ(1, loop.Iterate(Time::InMS(-99)));
-  EXPECT_EQ(Time::InMS(1), loop.sleep_time());
+  EXPECT_EQ(-2, loop.Iterate(InMs(-101)));
+  EXPECT_EQ(InMs(-99), loop.sleep_time());
+  EXPECT_EQ(1, loop.Iterate(InMs(-99)));
+  EXPECT_EQ(InMs(1), loop.sleep_time());
 
-  EXPECT_EQ(0, loop.Iterate(Time::InMS(-99)));
-  EXPECT_EQ(Time::InMS(1), loop.sleep_time());
+  EXPECT_EQ(0, loop.Iterate(InMs(-99)));
+  EXPECT_EQ(InMs(1), loop.sleep_time());
 }
 
 // Tests that passing invalid values to the constructor dies correctly.
 TEST_F(PhasedLoopDeathTest, InvalidValues) {
-  EXPECT_DEATH(PhasedLoop(Time::InMS(1), Time::InMS(2)), ".*offset<interval.*");
-  EXPECT_DEATH(PhasedLoop(Time::InMS(1), Time::InMS(1)), ".*offset<interval.*");
-  EXPECT_DEATH(PhasedLoop(Time::InMS(1), Time::InMS(-1)),
-               ".*offset>=Time::kZero.*");
-  EXPECT_DEATH(PhasedLoop(Time::InMS(0), Time::InMS(0)),
-               ".*interval>Time::kZero.*");
+  EXPECT_DEATH(PhasedLoop(milliseconds(1), milliseconds(2)),
+               ".*offset<interval.*");
+  EXPECT_DEATH(PhasedLoop(milliseconds(1), milliseconds(1)),
+               ".*offset<interval.*");
+  EXPECT_DEATH(PhasedLoop(milliseconds(1), milliseconds(-1)),
+               ".*offset>=monotonic_clock::duration\\(0\\).*");
+  EXPECT_DEATH(PhasedLoop(milliseconds(0), milliseconds(0)),
+               ".*interval>monotonic_clock::duration\\(0\\).*");
 }
 
 }  // namespace testing
diff --git a/aos/linux_code/ipc_lib/aos_sync.cc b/aos/linux_code/ipc_lib/aos_sync.cc
index 92eb1a1..b0b560e 100644
--- a/aos/linux_code/ipc_lib/aos_sync.cc
+++ b/aos/linux_code/ipc_lib/aos_sync.cc
@@ -954,9 +954,6 @@
 
 int futex_wait_timeout(aos_futex *m, const struct timespec *timeout) {
   RunObservers run_observers(m, false);
-  if (__atomic_load_n(m, __ATOMIC_SEQ_CST) != 0) {
-    return 0;
-  }
   const int ret = sys_futex_wait(FUTEX_WAIT, m, 0, timeout);
   if (ret != 0) {
     if (ret == -EINTR) {
diff --git a/aos/linux_code/ipc_lib/aos_sync.h b/aos/linux_code/ipc_lib/aos_sync.h
index 3495e73..5b7a865 100644
--- a/aos/linux_code/ipc_lib/aos_sync.h
+++ b/aos/linux_code/ipc_lib/aos_sync.h
@@ -111,9 +111,10 @@
 // example messages are available to read on a queue), use the condition_
 // functions or there will be race conditions.
 
-// Wait for the futex to be set. Will return immediately if it's already set.
+// Wait for the futex to be set. Will return immediately if it's already set
+// (after a syscall).
 // Returns 0 if successful or it was already set, 1 if interrupted by a signal,
-// or -1 with an error in errno.
+// or -1 with an error in errno. Can return 0 spuriously.
 int futex_wait(aos_futex *m) __attribute__((warn_unused_result));
 // The same as futex_wait except returns 2 if it times out.
 int futex_wait_timeout(aos_futex *m, const struct timespec *timeout)
diff --git a/aos/linux_code/ipc_lib/ipc_comparison.cc b/aos/linux_code/ipc_lib/ipc_comparison.cc
index 0a57ded..f375a17 100644
--- a/aos/linux_code/ipc_lib/ipc_comparison.cc
+++ b/aos/linux_code/ipc_lib/ipc_comparison.cc
@@ -17,6 +17,7 @@
 #include <thread>
 #include <memory>
 #include <string>
+#include <atomic>
 
 #include "aos/common/logging/logging.h"
 #include "aos/common/logging/implementations.h"
@@ -811,7 +812,7 @@
     return 1;
   }
 
-  bool done = false;
+  ::std::atomic<bool> done{false};
 
   ::std::thread server([&ping_ponger, &done]() {
     if (FLAGS_server_priority > 0) {
@@ -854,6 +855,11 @@
 
   const time::Time end = time::Time::Now();
 
+  // Try to make sure the server thread gets past its check of done so our
+  // Ping() down below doesn't hang. Kind of lame, but doing better would
+  // require complicating the interface to each implementation which isn't worth
+  // it here.
+  ::std::this_thread::sleep_for(::std::chrono::milliseconds(200));
   done = true;
   ping_ponger->PingData();
   ping_ponger->Ping();
diff --git a/frc971/wpilib/pdp_fetcher.cc b/frc971/wpilib/pdp_fetcher.cc
index 4e6be32..846de60 100644
--- a/frc971/wpilib/pdp_fetcher.cc
+++ b/frc971/wpilib/pdp_fetcher.cc
@@ -1,5 +1,7 @@
 #include "frc971/wpilib/pdp_fetcher.h"
 
+#include <chrono>
+
 #include "aos/common/logging/queue_logging.h"
 #include "aos/linux_code/init.h"
 #include "aos/common/util/phased_loop.h"
@@ -12,8 +14,8 @@
   ::aos::SetCurrentThreadName("PDPFetcher");
   ::std::unique_ptr<PowerDistributionPanel> pdp(new PowerDistributionPanel());
 
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
-                                      ::aos::time::Time::InMS(4));
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+                                      ::std::chrono::milliseconds(4));
 
   while (true) {
     {
diff --git a/y2012/wpilib/wpilib_interface.cc b/y2012/wpilib/wpilib_interface.cc
index 6702dc4..290f067 100644
--- a/y2012/wpilib/wpilib_interface.cc
+++ b/y2012/wpilib/wpilib_interface.cc
@@ -3,6 +3,7 @@
 #include <unistd.h>
 #include <inttypes.h>
 
+#include <chrono>
 #include <thread>
 #include <mutex>
 #include <functional>
@@ -104,8 +105,8 @@
         &DriverStation::GetInstance();
 #endif
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                        ::aos::time::Time::InMS(4));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                        ::std::chrono::milliseconds(4));
 
     ::aos::SetCurrentThreadRealtimePriority(40);
     while (run_) {
@@ -183,8 +184,8 @@
     ::aos::SetCurrentThreadName("Solenoids");
     ::aos::SetCurrentThreadRealtimePriority(27);
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
-                                        ::aos::time::Time::InMS(1));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+                                        ::std::chrono::milliseconds(1));
 
     while (run_) {
       {
diff --git a/y2014/control_loops/python/extended_lqr.tex b/y2014/control_loops/python/extended_lqr.tex
new file mode 100644
index 0000000..52d0949
--- /dev/null
+++ b/y2014/control_loops/python/extended_lqr.tex
@@ -0,0 +1,766 @@
+\documentclass[a4paper,12pt]{article}
+\usepackage{amsmath}
+\begin{document}
+
+% From http://www.eecs.tufts.edu/~khan/Courses/Spring2013/EE194/Lecs/Lec9and10.pdf
+% and http://www.cs.unc.edu/~wens/WAFR2014-Sun.pdf
+%   (which references http://maeresearch.ucsd.edu/skelton/publications/weiwei_ilqg_CDC43.pdf)
+% and http://arl.cs.utah.edu/pubs/ISRR2013.pdf
+
+\section{Backwards Pass}
+
+Let's start with some definitions for the standard LQR controller.
+$c_t(\boldsymbol{x}, \boldsymbol{u})$ is the cost for the iteration $t$ given that we are at $\boldsymbol{x}$ and are going to apply $\boldsymbol{u}$ for one cycle.
+$v_t(\boldsymbol{x})$ is the optimal cost-to-go for the starting point $\boldsymbol{x}$ at step $t$.
+$v_N(\boldsymbol{x})$ may be defined to be a different final cost from $v_t(\boldsymbol{x})$ if need be, where $N$ is the horizon.
+
+$$\begin{array}{rcl}
+c_t(\boldsymbol{x}, \boldsymbol{u}) &=&
+  \frac{1}{2}
+    \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+    \begin{bmatrix} Q_t & P_t^T \\ P_t & R_t \end{bmatrix}
+    \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix} +
+  \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+    \begin{bmatrix} \boldsymbol{q}_t \\ \boldsymbol{r}_t \end{bmatrix} +
+  q_t \\
+v_{t + 1}(\boldsymbol{x}) &=&
+  \frac{1}{2} \boldsymbol{x}^T S_{t + 1} \boldsymbol{x} + \boldsymbol{x}^T \boldsymbol{s}_{t + 1} + s_{t + 1} \\
+
+g_t(\boldsymbol{x}_t, \boldsymbol{u}_t) = \boldsymbol{x}_{t + 1}(\boldsymbol{u}_t) &=&
+  A_{t} \boldsymbol{x}_t + B_t \boldsymbol{u}_t + \boldsymbol{c}_{t} \\
+
+v_{t}(\boldsymbol{x}_t, \boldsymbol{u}_t) &=&
+  v_{t+1}(\boldsymbol{x}_{t+1}) +
+  c_t(\boldsymbol{x}_t, \boldsymbol{u}_t) \\\
+ &=&
+  v_{t+1}(g_t(\boldsymbol{x}_{t}, \boldsymbol{u}_t)) +
+  c_t(\boldsymbol{x}_t, \boldsymbol{u}_t)
+  \\
+\end{array}$$
+
+Now, let's calculate $v_t(\boldsymbol{x})$ given $v_{t+1}(\boldsymbol{x})$ and the step cost from $c_t(\boldsymbol{x})$.
+This tells us the cost of applying $\boldsymbol{u}$ starting from $\boldsymbol{x}$.
+We will then optimize over all $\boldsymbol{u}$ to find the optimal next state and cost for that state.
+This lets us then use dynamic programing methods to work out the optimal $\boldsymbol{x}$ and $\boldsymbol{u}$ at each timestep.
+
+We want to get a quadratic solution of the form
+$$v_{t}(\boldsymbol{x}) =
+  \frac{1}{2} \boldsymbol{x}^T S_{t} \boldsymbol{x} + \boldsymbol{x}^T \boldsymbol{s}_{t} + s_{t}$$ for each step.
+
+$$\begin{array}{rcl}
+v_{t}(\boldsymbol{x}, \boldsymbol{u}) &=&
+  \frac{1}{2} \left( A_{t}\boldsymbol{x} + B_{t}\boldsymbol{u} + \boldsymbol{c}_{t}\right)^T
+    S_{t + 1}
+    \left( A_{t}\boldsymbol{x} + B_{t}\boldsymbol{u} + \boldsymbol{c}_{t}\right) +
+  \left( A_{t}\boldsymbol{x} + B_{t}\boldsymbol{u} + \boldsymbol{c}_{t}\right)^T \boldsymbol{s}_{t + 1} +
+  s_{t + 1} + \\ &&
+  \frac{1}{2}
+    \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+    \begin{bmatrix} Q_{t} & P_{t}^T \\ P_{t} & R_{t} \end{bmatrix}
+    \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix} +
+  \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+    \begin{bmatrix} \boldsymbol{q}_{t} \\ \boldsymbol{r}_{t} \end{bmatrix} +
+    q_{t}
+\\
+&=&
+  \frac{1}{2} \left(
+    \boldsymbol{x}^T A_{t}^T S_{t + 1} A_{t} \boldsymbol{x} +
+    \boldsymbol{u}^T B_{t}^T S_{t + 1} A_{t} \boldsymbol{x} +
+    \boldsymbol{c}_t^T S_{t + 1} A_{t} \boldsymbol{x} + \right. \\ &&
+    \left. \boldsymbol{x}^T A_{t}^T S_{t + 1} B_{t} \boldsymbol{u} +
+    \boldsymbol{u}^T B_{t}^T S_{t + 1} B_{t} \boldsymbol{u} +
+    \boldsymbol{c}_t^T S_{t + 1} B_{t} \boldsymbol{u} + \right. \\ &&
+    \left. \boldsymbol{x}^T A_{t}^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{u}^T B_{t}^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+  \right) + \\ &&
+  \boldsymbol{x}^T A_{t}^T \boldsymbol{s}_{t + 1} +
+  \boldsymbol{u}^T B_{t}^T \boldsymbol{s}_{t + 1} +
+  \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} +
+  s_{t + 1} + \\ &&
+  \frac{1}{2} \left(\boldsymbol{x}^T Q_t \boldsymbol{x} + \boldsymbol{u}^T P_t \boldsymbol{x} + \boldsymbol{x}^T P_t^T \boldsymbol{u} + \boldsymbol{u}^T R_t \boldsymbol{u} \right) + \boldsymbol{x}^T \boldsymbol{q}_t + \boldsymbol{u}^T \boldsymbol{r}_t + q_t
+\\
+&=&
+  \frac{1}{2} \left(
+    \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} A_{t} + Q_t \right) \boldsymbol{x} +
+    \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} \right. + \\ &&
+    \left. \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) \boldsymbol{u} +
+    \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} \right) + \\ &&
+  \boldsymbol{x}^T \left(A_{t}^T \boldsymbol{s}_{t + 1} +
+  \boldsymbol{q}_t \right)+
+
+  \boldsymbol{u}^T \left( B_{t}^T \boldsymbol{s}_{t + 1} +
+  \boldsymbol{r}_t \right) +
+  \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} +
+  q_t + \\ &&
+  \frac{1}{2} \left( \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+     \boldsymbol{x}^T A_{t}^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{u}^T B_{t}^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{c}_t^T S_{t + 1} B_{t} \boldsymbol{u} +
+    \boldsymbol{c}_t^T S_{t + 1} A_{t} \boldsymbol{x} \right)
+\end{array}$$
+
+Now, let's find the optimal $\boldsymbol{u}$.  Do this by evaluating $\frac{\partial}{\partial \boldsymbol{u}} v_t(\boldsymbol{x}, \boldsymbol{u}) = 0$.
+
+$$\begin{array}{rcl}
+\frac{\partial}{\partial \boldsymbol{u}} v_{t}(\boldsymbol{x}, \boldsymbol{u}) &=& \frac{1}{2} \left( 2 \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) + 2 \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) + 2 \boldsymbol{c}_t^T S_{t + 1} B_{t} \right) + \\&&\boldsymbol{s}_{t + 1}^T B_{t} + \boldsymbol{r}_t^T \\
+
+\frac{\partial}{\partial \boldsymbol{u}} v_{t}(\boldsymbol{x}, \boldsymbol{u}) &=& \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) + \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) + \boldsymbol{c}_t^T S_{t + 1} B_{t} + \boldsymbol{s}_{t + 1}^T B_{t} + \boldsymbol{r}_t^T \\
+0 &=& \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) + \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) + \boldsymbol{c}_t^T S_{t + 1} B_{t} + \boldsymbol{s}_{t + 1}^T B_{t} + \boldsymbol{r}_t^T
+\end{array}$$
+$$\begin{array}{rcl}
+\boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) &=& - \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) - \boldsymbol{c}_t^T S_{t + 1} B_{t} - \boldsymbol{s}_{t + 1}^T B_{t} - \boldsymbol{r}_t^T \\
+\left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} &=& - \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} - B_t^T S_{t + 1} \boldsymbol{c}_t - B_{t}^T \boldsymbol{s}_{t + 1}- \boldsymbol{r}_t \\
+\boldsymbol{u} &=& - \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) ^{-1} \left( \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} + B_t^T S_{t + 1} \boldsymbol{c}_t + B_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{r}_t \right)
+\end{array}$$
+
+This gives us the optimal $\boldsymbol{u}$.  There are some substitutions defined here from the 2013 paper which make it easier to read.
+Note: the 2014 paper uses different letters for these same quantities\dots
+\\
+$$\begin{array}{rcl}
+C_t &=& B^T_t S_{t + 1} A_t + P_t \\
+E_t &=&  B_{t}^T S_{t + 1} B_{t} + R_t \\
+L_t &=& - E_t ^{-1} C_t \\
+
+\boldsymbol{e}_t &=& B_t^T S_{t + 1} \boldsymbol{c}_t + B_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{r}_t \\
+\boldsymbol{l}_t &=&  - E^{-1}_t \boldsymbol{e}_t \\
+
+D_t &=& A_t^T S_{t + 1} A_t + Q_t \\
+\boldsymbol{d}_t &=& A_t^T S_{t + 1} \boldsymbol{c}_t + A_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{q}_t
+\\
+\boldsymbol{u} &=& L_t \boldsymbol{x} + \boldsymbol{l}_t
+\end{array}$$
+
+With these, we can simplify $\boldsymbol{u}$ a bit and make it look like the 2014 paper has it.
+
+$$\begin{array}{rcl}
+  \boldsymbol{u} &=& -E_t^{-1} \left( C_t \boldsymbol{x} + \boldsymbol{e}_t \right) \\
+  \boldsymbol{u} &=& -E_t^{-1} C_t \boldsymbol{x} - E_t^{-1} \boldsymbol{e}_t
+\end{array}$$
+
+For reference, here are some equivalences between the symbols used in the 2013
+paper (the ones we use) and the 2014 paper.
+TODO(Brian): Figure out where the ones in the 2014 paper are defined instead of
+guessing by pattern-matching.
+\\ \begin{tabular}{ | r | l | }
+  \hline
+  2013 paper (ours) & 2014 paper \\
+  \hline
+  $C_t$ & $E_t$ \\
+  $D_t$ & $C_t$ \\
+  $\boldsymbol{d}_t$ & $\boldsymbol{c}_t$ \\
+  $E_t$ & $D_t$ \\
+  $\boldsymbol{e}_t$ & $\boldsymbol{d}_t$ \\
+  \hline
+\end{tabular} \\
+
+Now, let's solve for the new cost function.
+
+$$\begin{array}{rcl}
+v_{t}(\boldsymbol{x}, \boldsymbol{u}) &=&
+  \frac{1}{2} \left(
+    \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} A_{t} + Q_t \right) \boldsymbol{x} +
+    \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} \right. + \\ &&
+    \left. \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) \boldsymbol{u} +
+    \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} \right) + \\ &&
+  \boldsymbol{x}^T \left(A_{t}^T \boldsymbol{s}_{t + 1} +
+  \boldsymbol{q}_t \right)+
+
+  \boldsymbol{u}^T \left( B_{t}^T \boldsymbol{s}_{t + 1} +
+  \boldsymbol{r}_t \right) +
+  \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} +
+  q_t + \\ &&
+  \frac{1}{2} \left( \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+     \boldsymbol{x}^T A_{t}^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{u}^T B_{t}^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{c}_t^T S_{t + 1} B_{t} \boldsymbol{u} +
+    \boldsymbol{c}_t^T S_{t + 1} A_{t} \boldsymbol{x} \right)
+\\
+&=&
+  \frac{1}{2} \left(
+    \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} A_{t} + Q_t \right) \boldsymbol{x} +
+    \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} \right. + \\ &&
+    \left. \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) \boldsymbol{u} +
+    \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} \right) + \\ &&
+
+  \boldsymbol{x}^T \left(A_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{q}_t +
+    \frac{1}{2} A_{t}^T S_{t + 1} \boldsymbol{c}_t \right) + \\ &&
+
+  \boldsymbol{u}^T \left( B_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{r}_t +
+    \frac{1}{2} B_{t}^T S_{t + 1} \boldsymbol{c}_t \right) + \\ &&
+
+  \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \left( A_t \boldsymbol{x} +
+    B_t \boldsymbol{u} + \boldsymbol{c}_t \right) + \\ &&
+
+  \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+  \frac{1}{2} \left(
+    \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} A_{t} + Q_t \right) \boldsymbol{x} +
+    \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} \right. + \\ &&
+    \left. \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) \boldsymbol{u} +
+    \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} \right) + \\ &&
+
+  \boldsymbol{x}^T \left(A_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{q}_t +
+    A_{t}^T S_{t + 1} \boldsymbol{c}_t \right) + \\ &&
+
+  \boldsymbol{u}^T \left( B_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{r}_t +
+    B_{t}^T S_{t + 1} \boldsymbol{c}_t \right) + \\ &&
+
+  \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+  \frac{1}{2} \left(
+    \boldsymbol{x}^T D_t \boldsymbol{x} +
+    \boldsymbol{u}^T C_t \boldsymbol{x} +
+    \boldsymbol{x}^T C_t^T \boldsymbol{u} +
+    \boldsymbol{u}^T E_t \boldsymbol{u} \right) + \\ &&
+
+  \boldsymbol{x}^T \boldsymbol{d}_t +
+  \boldsymbol{u}^T \boldsymbol{e}_t + \\ &&
+
+  \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+  \frac{1}{2} \left(
+    \boldsymbol{x}^T D_t \boldsymbol{x} +
+    \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right)^T C_t \boldsymbol{x} \right. + \\ &&
+    \left. \boldsymbol{x}^T C_t^T \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right) +
+    \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right)^T E_t \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right) \right) + \\ &&
+
+  \boldsymbol{x}^T \boldsymbol{d}_t +
+  \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right)^T \boldsymbol{e}_t + \\&&
+
+  \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+  \frac{1}{2} \left(
+    \boldsymbol{x}^T D_t \boldsymbol{x} + \right.
+    \boldsymbol{x}^T L_t^T C_t \boldsymbol{x} + \boldsymbol{l}_t^T C_t \boldsymbol{x} + \\ &&
+
+    \left. \boldsymbol{x}^T C_t^T L_t \boldsymbol{x} + \boldsymbol{x}^T C_t^T \boldsymbol{l}_t +
+
+    \boldsymbol{x}^T L_t^T E_t L_t \boldsymbol{x} +
+    \boldsymbol{l}_t^T E_t L_t \boldsymbol{x} +
+    \boldsymbol{x}^T L_t^T E_t \boldsymbol{l}_t +
+    \boldsymbol{l}_t^T E_t \boldsymbol{l}_t \right) + \\&&
+
+  \boldsymbol{x}^T \boldsymbol{d}_t +
+  \boldsymbol{x}^T L_t^T \boldsymbol{e}_t + \boldsymbol{l}^T_t \boldsymbol{e}_t + \\&&
+
+  \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+    \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+  \frac{1}{2}
+    \boldsymbol{x}^T \left(
+      D_t +
+     L_t^T C_t +
+     C_t^T L_t +
+     L_t^T E_t L_t
+      \right) \boldsymbol{x} + \\ &&
+
+  \boldsymbol{x}^T \left(
+    \frac{1}{2} \left( C_t^T \boldsymbol{l}_t +
+    L_t^T E_t \boldsymbol{l}_t \right) +
+    \boldsymbol{d}_t +
+    L_t^T \boldsymbol{e}_t \right) +
+    \frac{1}{2} \left( \boldsymbol{l}_t^T E_t L_t + \boldsymbol{l}_t^T C_t \right) \boldsymbol{x} + \\ &&
+
+  \frac{1}{2} \boldsymbol{l}_t^T E_t \boldsymbol{l}_t +
+    \boldsymbol{l}^T_t \boldsymbol{e}_t +
+
+  \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t +
+    \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+\\
+&=&
+  \frac{1}{2}
+    \boldsymbol{x}^T \left(
+      D_t +
+     L_t^T C_t +
+     C_t^T L_t +
+     L_t^T E_t L_t
+      \right) \boldsymbol{x} + \\ &&
+
+  \boldsymbol{x}^T \left(
+    C_t^T \boldsymbol{l}_t +
+    L_t^T E_t \boldsymbol{l}_t +
+    \boldsymbol{d}_t +
+    L_t^T \boldsymbol{e}_t \right) + \\ &&
+
+  \frac{1}{2} \boldsymbol{l}_t^T E_t \boldsymbol{l}_t +
+    \boldsymbol{l}^T_t \boldsymbol{e}_t +
+
+  \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t +
+    \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+\end{array}$$
+
+Ok, let's now pull out the 3 variables of interest and do further simplification.
+
+$$\begin{array}{rcl}
+v_{t}(\boldsymbol{x}) &=&
+  \frac{1}{2} \boldsymbol{x}^T S_{t} \boldsymbol{x} + \boldsymbol{x}^T \boldsymbol{s}_{t} + s_{t} \\
+S_t &=&
+     D_t +
+     L_t^T C_t +
+     C_t^T L_t +
+     L_t^T E_t L_t \\
+    &=&
+     D_t -
+     C_t^T E_t^{-1} C_t -
+     C_t^T E_t^{-1} C_t +
+     C_t^T E_t^{-1} C_t \\
+    &=& D_t - C_t^T E_t^{-1} C_t
+\\
+\boldsymbol{s}_t &=&
+    \left( C_t^T + L_t^T E_t \right) \boldsymbol{l}_t +
+    \boldsymbol{d}_t +
+    L_t^T \boldsymbol{e}_t \\
+
+  &=&
+    \left( C_t^T - C_t^T E_t^{-1} E_t \right) \boldsymbol{l}_t +
+    \boldsymbol{d}_t -
+    C_t^T E_t^{-1} \boldsymbol{e}_t \\
+  &=& \boldsymbol{d}_t - C_t^T E_t^{-1} \boldsymbol{e}_t
+\\
+s_t &=&
+  \frac{1}{2} \boldsymbol{l}_t^T E_t \boldsymbol{l}_t +
+    \boldsymbol{l}^T_t \boldsymbol{e}_t +
+
+  \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t +
+  \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+\\
+&=&
+\frac{1}{2} \boldsymbol{e}_t^T E_t^{-1} E_t E_t^{-1} \boldsymbol{e}_t -
+  \boldsymbol{e}_t^T E_t^{-1} \boldsymbol{e}_t +
+
+  \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t +
+
+  \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+\\
+&=&
+q_t - \frac{1}{2} \boldsymbol{e}_t^T E_t^{-1} \boldsymbol{e}_t +
+
+  \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+  \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1}
+\end{array}$$
+
+For better or worse, everything but the constant term matches both the 2013
+paper (which has no constant term) and the 2014 paper.
+The constant term does not match the 2014 paper, but we're pretty sure it's
+correct (extended\_lqr\_derivation.py verifies what we have).
+The 2014 paper has this for the constant term instead:
+$$\begin{array}{rcl}
+s_t &=&
+  q_t - \frac{1}{2} \boldsymbol{e}_t^T E_t^{-1} \boldsymbol{e}_t
+\end{array}$$
+
+\section{Forwards Pass}
+
+Let's define the forwards pass to build the cost-to-come function.
+We must use the same cycle cost, $c_t(\boldsymbol{x}, \boldsymbol{u})$, as the backwards pass.
+The initial cost $v_0(\boldsymbol{x})$ needs to evaluate to $0$ at $\boldsymbol{x}_0$ since
+there is no cost needed to get from $\boldsymbol{x}_0$ to $\boldsymbol{x}_0$.
+
+$$\begin{array}{rcl}
+\bar v_{t}(\boldsymbol{x}) &=&
+  \frac{1}{2} \boldsymbol{x}^T \bar S_{t} \boldsymbol{x} + \boldsymbol{x}^T \boldsymbol{\bar s}_{t} + \bar s_{t} \\
+
+\bar g_t(\boldsymbol{x}_{t + 1}, \boldsymbol{u}) = \boldsymbol{x}_{t}(\boldsymbol{u}) &=&
+  \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t} \\
+
+\bar c_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u}) &=& c_t(\bar g_{t}(\boldsymbol{x}_{t + 1}, \boldsymbol{u}), \boldsymbol{u}) \\
+
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u}) &=&
+  \bar v_{t}(\boldsymbol{x}_{t}) +
+  \bar c_t(\boldsymbol{x}_{t + 1}, \boldsymbol{u}_t)
+  \\
+&=&
+  \bar v_{t}(\bar g_t(\boldsymbol{x}_{t + 1}, \boldsymbol{u})) +
+ c_t(\bar g_{t}(\boldsymbol{x}_{t + 1}, \boldsymbol{u}), \boldsymbol{u}) \\
+  \\
+\end{array}$$
+
+It is important to note that the optimal $\boldsymbol{u}$ used to get from $\boldsymbol{x}_t$ to $\boldsymbol{x}_{t+1}$
+when evaluating $g_t(\boldsymbol{x}, \boldsymbol{u})$ is the same optimal $\boldsymbol{u}$
+used to get from $\boldsymbol{x}_{t+1}$ to $\boldsymbol{x}_t$ when evaluating $\bar g_{t}(\boldsymbol{x}_{t + 1}, \boldsymbol{u})$.
+Conveniently, this means that the $\boldsymbol{u}_t$, $L_t$, and $\boldsymbol{l}_t$ calculated in both the forwards and backwards passes is the same.
+
+Like before, we want to get a quadratic solution of the form
+$$\bar v_{t + 1}(\boldsymbol{x}_{t+1}) =
+  \frac{1}{2} \boldsymbol{x}_{t+1}^T \bar S_{t + 1} \boldsymbol{x}_{t+1} + \boldsymbol{x}_{t+1}^T \boldsymbol{\bar s}_{t + 1} + \bar s_{t + 1}$$ for each step.
+
+$$\begin{array}{rcl}
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u}) &=&
+    \frac{1}{2} \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T
+        \bar S_{t}
+        \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \\ &&
+    \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) ^T \boldsymbol{\bar s}_{t} + \bar s_{t} +  \\&&
+  \frac{1}{2}
+    \begin{bmatrix} \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) \\ \boldsymbol{u} \end{bmatrix}^T
+    \begin{bmatrix} Q_t & P_t^T \\ P_t & R_t \end{bmatrix}
+    \begin{bmatrix} \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) \\ \boldsymbol{u} \end{bmatrix} + \\&&
+  \begin{bmatrix} \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) \\ \boldsymbol{u} \end{bmatrix}^T
+    \begin{bmatrix} \boldsymbol{q}_t \\ \boldsymbol{r}_t \end{bmatrix} +
+  q_t \\
+
+  &=&
+    \frac{1}{2} \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T
+        \bar S_{t}
+        \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \\ &&
+    \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) ^T \boldsymbol{\bar s}_{t} + \bar s_{t} +  \\&&
+
+      \frac{1}{2} \left(
+        \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T Q_t \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \right. \\&&
+        \boldsymbol{u}^T P_t \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \\&&
+        \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T P_t^T \boldsymbol{u} + \\&&
+        \left. \boldsymbol{u}^T R_t \boldsymbol{u} \right) + \\&&
+
+        \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T \boldsymbol{q}_t + \boldsymbol{u}^T \boldsymbol{r}_t + q_t \\
+
+  &=&
+    \frac{1}{2} \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T
+      \left( \bar S_{t} + Q_t \right)
+        \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \\ &&
+    \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) ^T \boldsymbol{\bar s}_{t} + \bar s_{t} +  \\&&
+
+      \frac{1}{2} \left(
+        \boldsymbol{u}^T P_t \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) \right. + \\&&
+        \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T P_t^T \boldsymbol{u} + \\&&
+        \left. \boldsymbol{u}^T R_t \boldsymbol{u} \right) + \\&&
+
+        \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T \boldsymbol{q}_t + \boldsymbol{u}^T \boldsymbol{r}_t + q_t \\
+
+  &=& \frac{1}{2} \left(
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t + \right. \\&&
+      \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+      \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+      \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t + \\&&
+      \left. \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+      \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+      \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t \right) + \\&&
+
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \boldsymbol{\bar s}_t +
+      \boldsymbol{u}^T \bar B_t^T \boldsymbol{\bar s}_t +
+      \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t +
+
+      \bar s_t + \\ &&
+
+      \frac{1}{2} \left( \boldsymbol{u}^T P_t \bar A_{t} \boldsymbol{x}_{t + 1} +
+      \boldsymbol{u}^T P_t \bar B_{t} \boldsymbol{u} +
+      \boldsymbol{u}^T P_t \boldsymbol{\bar c}_{t} \right) + \\&&
+      \frac{1}{2} \left( \boldsymbol{x}_{t+1}^T \bar A^T_t P_t^T \boldsymbol{u} +
+      \boldsymbol{u}^T \bar B^T_{t} P_t^T \boldsymbol{u} +
+      \boldsymbol{\bar c}_t^T P^T_t \boldsymbol{u} \right) + \\&&
+
+      \frac{1}{2} \boldsymbol{u}^T R_t \boldsymbol{u} + \\&&
+
+        \boldsymbol{x}^T_{t + 1} \bar A^T_t \boldsymbol{q}_t +
+        \boldsymbol{u}^T \bar B^T_t \boldsymbol{q}_t +
+      \boldsymbol{\bar c}_t^T  \boldsymbol{q}_t +
+
+        \boldsymbol{u}^T \boldsymbol{r}_t + q_t
+\end{array}$$
+
+Now, let's find the optimal $\boldsymbol{u}$.
+Do this by evaluating
+$\frac{\partial}{\partial \boldsymbol{u}} \bar v_t(\boldsymbol{x}, \boldsymbol{u}) = 0$.
+
+$$\begin{array}{rcl}
+\frac{\partial}{\partial \boldsymbol{u}} \bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u})
+  &=& \frac{1}{2} \left(
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+
+      \left(\bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1}\right)^T + \right. \\&&
+
+      2 \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+      \left( \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t \right)^T + \\&&
+      \left. \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t \right) + \\&& 
+      \boldsymbol{\bar s}_t ^T \bar B_t + \\&&
+
+      \frac{1}{2} \left( P_t \bar A_{t} \boldsymbol{x}_{t + 1}\right) ^T +
+      \frac{1}{2} \boldsymbol{x}_{t+1}^T \bar A^T_t P_t^T + \\&&
+
+      \frac{1}{2} \boldsymbol{u}^T \left( P_t \bar B_{t} + \bar B_t^T P_t^T \right) +
+      \frac{1}{2} \boldsymbol{u}^T \left( \bar B^T_{t} P_t^T + P_t \bar B_t \right) + \\&&
+      \frac{1}{2} \left( P_t \boldsymbol{\bar c}_{t} \right)^T +
+      \frac{1}{2} \boldsymbol{\bar c}^T_{t} P_t^T +
+
+      \boldsymbol{u}^T R_t + \\&&
+
+        \left(\bar B^T_t \boldsymbol{q}_t\right)^T +
+
+        \boldsymbol{r}_t^T \\
+
+  &=&
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+      \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+
+      \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t + \\&& 
+
+      \boldsymbol{\bar s}_t ^T \bar B_t + \\&&
+
+      \boldsymbol{x}_{t+1}^T \bar A^T_t P_t^T + \\&&
+
+      \boldsymbol{u}^T \left( \bar B^T_{t} P_t^T + P_t \bar B_t \right) + \\&&
+      \boldsymbol{\bar c}^T_{t} P_t^T +
+
+      \boldsymbol{u}^T R_t + \\&&
+
+      \boldsymbol{q}_t^T \bar B_t +
+      \boldsymbol{r}_t^T \\
+0 &=&
+      \boldsymbol{x}_{t + 1}^T \left( \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t + \bar A^T_t P_t^T \right) + \\&&
+
+      \boldsymbol{u}^T \left(
+          \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+          \bar B^T_{t} P_t^T + P_t \bar B_t + R_t
+      \right) + \\&&
+
+      \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+      \boldsymbol{\bar s}_t^T \bar B_t +
+      \boldsymbol{\bar c}^T_{t} P_t^T +
+      \boldsymbol{q}_t^T \bar B_t +
+      \boldsymbol{r}_t^T \\
+\end{array}$$
+
+$$\begin{array}{rcl}
+      \boldsymbol{u}^T \left(
+          \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+          \bar B^T_{t} P_t^T + P_t \bar B_t + R_t
+      \right)
+ &=&
+      - \boldsymbol{x}_{t + 1}^T \left( \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t + \bar A^T_t P_t^T \right) - \\&&
+
+
+      \left( \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+      \boldsymbol{\bar s}_t^T \bar B_t +
+      \boldsymbol{\bar c}^T_{t} P_t^T +
+      \boldsymbol{q}_t^T \bar B_t +
+      \boldsymbol{r}_t^T \right) \\
+
+\left(
+    \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+    \bar B^T_{t} P_t^T + P_t \bar B_t + R_t
+\right) \boldsymbol{u}
+   &=&
+      - \left( \bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t + P_t \bar A_t \right) \boldsymbol{x}_{t + 1} - \\&&
+
+      \left( \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t  +
+      \bar B_t^T \boldsymbol{\bar s}_t +
+      P_t \boldsymbol{\bar c}_{t} +
+      \bar B_t^T \boldsymbol{q}_t +
+      \boldsymbol{r}_t \right) \\
+\end{array}$$
+
+Some substitutions to use for simplifying:
+
+$$\begin{array}{rcl}
+\bar C_t &=& \bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t + P_t \bar A_t \\
+\bar E_t &=&
+    \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+    \bar B^T_{t} P_t^T + P_t \bar B_t + R_t \\
+\bar L_t &=& - \bar E_t^{-1} \bar C_t \\
+
+\boldsymbol{\bar e}_t &=&
+      \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t  +
+      \bar B_t^T \boldsymbol{\bar s}_t +
+      P_t \boldsymbol{\bar c}_{t} +
+      \bar B_t^T \boldsymbol{q}_t +
+      \boldsymbol{r}_t \\
+\boldsymbol{\bar l}_t &=& - \bar E_t^{-1} \boldsymbol{\bar e}_t \\
+
+\bar D_t &=& \bar A_t^T \left( \bar S_t + Q_t \right) \bar A_t \\
+\boldsymbol{\bar d}_t &=&
+      \bar A_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+      \bar A_t^T \left( \boldsymbol{\bar s}_t + \boldsymbol{q}_t \right) \\
+
+\boldsymbol{u} &=& - \bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \\
+\boldsymbol{u} &=& \bar L_t \boldsymbol{x}_{t + 1} + \boldsymbol{\bar l}_t \\
+
+\bar E_t \boldsymbol{u} &=& -\bar C_t \boldsymbol{x}_{t + 1} - \boldsymbol{\bar e}_t
+\end{array}$$
+
+Now, let's solve for the new cost function.
+
+$$\begin{array}{rcl}
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u})
+  &=& \frac{1}{2} \left(
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t + \right. \\&&
+      \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+      \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+      \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t + \\&&
+      \left. \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+      \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+      \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t \right) + \\&& 
+
+      \boldsymbol{x}_{t + 1}^T \bar A_t^T \boldsymbol{\bar s}_t +
+      \boldsymbol{u}^T \bar B_t^T \boldsymbol{\bar s}_t +
+      \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t +
+
+      \bar s_t + \\ &&
+
+      \frac{1}{2} \left( \boldsymbol{u}^T P_t \bar A_{t} \boldsymbol{x}_{t + 1} +
+      \boldsymbol{u}^T P_t \bar B_{t} \boldsymbol{u} +
+      \boldsymbol{u}^T P_t \boldsymbol{\bar c}_{t} \right) + \\&&
+      \frac{1}{2} \left( \boldsymbol{x}_{t+1}^T \bar A^T_t P_t^T \boldsymbol{u} +
+      \boldsymbol{u}^T \bar B^T_{t} P_t^T \boldsymbol{u} +
+      \boldsymbol{\bar c}_t^T P^T_t \boldsymbol{u} \right) + \\&&
+
+      \frac{1}{2} \boldsymbol{u}^T R_t \boldsymbol{u} + \\&&
+
+        \boldsymbol{x}^T_{t + 1} \bar A^T_t \boldsymbol{q}_t +
+        \boldsymbol{u}^T \bar B^T_t \boldsymbol{q}_t +
+      \boldsymbol{\bar c}_t^T \boldsymbol{q}_t +
+
+        \boldsymbol{u}^T \boldsymbol{r}_t + q_t \\
+
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u})
+  &=& \frac{1}{2} \left(
+      \boldsymbol{x}_{t + 1}^T \bar D_t \boldsymbol{x}_{t + 1} +
+      \boldsymbol{x}_{t + 1}^T \bar C_t^T \boldsymbol{u} +
+      \boldsymbol{u}^T \bar C_t \boldsymbol{x}_{t + 1} +
+      \boldsymbol{u}^T \bar E_t \boldsymbol{u} \right) + \\&&
+
+      \boldsymbol{x}_{t + 1}^T \boldsymbol{\bar d}_t +
+
+      \boldsymbol{u}^T \boldsymbol{\bar e}_t + \\&&
+
+      \frac{1}{2} \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+      \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t + \boldsymbol{\bar c}_t^T \boldsymbol{q}_t + \bar s_t + q_t \\
+
+\bar v_{t + 1}(\boldsymbol{x}_{t+1})
+  &=& \frac{1}{2} \left(
+      \boldsymbol{x}_{t + 1}^T \bar D_t \boldsymbol{x}_{t + 1} + \right. \\ &&
+      \boldsymbol{x}_{t + 1}^T \bar C_t^T \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right) + \\&&
+      \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right)^T \bar C_t \boldsymbol{x}_{t + 1} + \\&&
+      \left. \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right)^T \bar E_t \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right) \right) + \\&&
+
+      \boldsymbol{x}_{t + 1}^T \boldsymbol{\bar d}_t +
+
+      \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right)^T \boldsymbol{\bar e}_t + \\&&
+
+      \frac{1}{2} \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+      \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t + \boldsymbol{\bar c}_t^T \boldsymbol{q}_t + \bar s_t + q_t \\
+
+\bar v_{t + 1}(\boldsymbol{x}_{t+1})
+  &=& \frac{1}{2}
+      \boldsymbol{x}_{t + 1}^T \left(\bar D_t - \bar C_t^T \bar E_t^{-1} \bar C_t \right) \boldsymbol{x}_{t + 1} + \\ &&
+
+      \boldsymbol{x}_{t + 1}^T \left(\boldsymbol{\bar d}_t
+      - \bar C_t^T \bar E_t^{-1} \boldsymbol{\bar e}_t \right)\\&&
+
+      - \frac{1}{2} \boldsymbol{\bar e}_t^T \bar E_t^{-1} \boldsymbol{\bar e}_t +
+      \frac{1}{2} \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+      \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t + \boldsymbol{\bar c}_t^T \boldsymbol{q}_t + \bar s_t + q_t \\
+\end{array}$$
+
+Ok, let's now pull out the 3 variables of interest and do further simplification.
+
+$$\begin{array}{rcl}
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}) &=& \frac{1}{2} \boldsymbol{x}_{t + 1}^T \bar S_{t + 1} \boldsymbol{x}_{t + 1} + \boldsymbol{x}_{t + 1}^T \boldsymbol{\bar s}_{t + 1} + \bar s_{t+1} \\
+  \bar S_{t + 1} &=& \bar D_t - \bar C_t^T \bar E_t^{-1} \bar C_t \\
+  \boldsymbol{\bar s}_{t + 1} &=&
+       \left(\boldsymbol{\bar d}_t - \bar C_t^T \bar E_t^{-1} \boldsymbol{\bar e}_t \right)\\
+
+\bar s_{t+1} &=&
+      - \frac{1}{2} \boldsymbol{\bar e}_t^T \bar E_t^{-1} \boldsymbol{\bar e}_t +
+      \frac{1}{2} \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+      \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t + \boldsymbol{\bar c}_t^T \boldsymbol{q}_t + \bar s_t + q_t \\
+\end{array}$$
+
+\newpage
+\section{Detailed work for a few transformations}
+
+$$\begin{array}{l}
+\begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+\begin{bmatrix} Q_{t} & P_{t}^T \\ P_{t} & R_{t} \end{bmatrix}
+\begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix} \\
+
+\begin{bmatrix} \boldsymbol{x}_1 & \boldsymbol{x}_2 & \boldsymbol{u}_1 & \boldsymbol{u}_2 \end{bmatrix}
+\left[\begin{array}{cc|cc}
+    Q_{t11} & Q_{t12} & P_{t11} & P_{t21} \\
+    Q_{t21} & Q_{t22} & P_{t12} & P_{t22} \\
+    \hline
+    P_{t11} & P_{t12} & R_{t11} & R_{t12} \\
+    P_{t21} & P_{t22} & R_{t21} & R_{t22} \\
+\end{array}\right]
+\begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix}
+\\
+\begin{bmatrix}
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+    \begin{bmatrix} Q_{t11} \\ Q_{t21} \\ P_{t11} \\ P_{t21} \end{bmatrix} &
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+    \begin{bmatrix} Q_{t12} \\ Q_{t22} \\ P_{t12} \\ P_{t22} \end{bmatrix} &
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+    \begin{bmatrix} P_{t11} \\ P_{t12} \\ R_{t11} \\ R_{t21} \end{bmatrix} &
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+    \begin{bmatrix} P_{t21} \\ P_{t22} \\ R_{t12} \\ R_{t22} \end{bmatrix} &
+\end{bmatrix}
+\begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix}
+\\
+\begin{bmatrix}
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+    \begin{bmatrix} Q_{t11} \\ Q_{t21} \end{bmatrix}
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+    \begin{bmatrix} Q_{t12} \\ Q_{t22} \end{bmatrix}
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+    \begin{bmatrix} P_{t11} \\ P_{t12} \end{bmatrix}
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+    \begin{bmatrix} P_{t21} \\ P_{t22} \end{bmatrix}
+\end{bmatrix}
+\begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} + \\ \quad
+\begin{bmatrix}
+    \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+      \begin{bmatrix} P_{t11} \\ P_{t21} \end{bmatrix} &
+    \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+      \begin{bmatrix} P_{t12} \\ P_{t22} \end{bmatrix} &
+    \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+      \begin{bmatrix} R_{t11} \\ R_{t21} \end{bmatrix} &
+    \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+      \begin{bmatrix} R_{t12} \\ R_{t22} \end{bmatrix} &
+\end{bmatrix}
+\begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix}
+\\
+\begin{bmatrix} \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+  \begin{bmatrix} Q_{t11} \\ Q_{t21} \end{bmatrix} &
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+  \begin{bmatrix} Q_{t12} \\ Q_{t22} \end{bmatrix}\end{bmatrix}
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} +
+\begin{bmatrix} \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+  \begin{bmatrix} P_{t11} \\ P_{t12} \end{bmatrix} &
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+  \begin{bmatrix} P_{t21} \\ P_{t22} \end{bmatrix}\end{bmatrix}
+  \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} + \\ \quad
+\begin{bmatrix} \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+  \begin{bmatrix} P_{t11} \\ P_{t21} \end{bmatrix} &
+  \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+  \begin{bmatrix} P_{t12} \\ P_{t22} \end{bmatrix}\end{bmatrix}
+  \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} +
+\begin{bmatrix} \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+  \begin{bmatrix} R_{t11} \\ R_{t21} \end{bmatrix} &
+  \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+  \begin{bmatrix} R_{t12} \\ R_{t22} \end{bmatrix}\end{bmatrix}
+  \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix}
+\\
+\boldsymbol{x}^T Q_t \boldsymbol{x} + \boldsymbol{u}^T P_t \boldsymbol{x} + \boldsymbol{x}^T P_t^T \boldsymbol{u} + \boldsymbol{u}^T R_t \boldsymbol{u}
+\end{array}$$
+\\ \\
+$$\begin{array}{l}
+\begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+\begin{bmatrix} \boldsymbol{q}_{t} \\ \boldsymbol{r}_{t} \end{bmatrix}
+\\
+\begin{bmatrix} \boldsymbol{x}_1 & \boldsymbol{x}_2 & \boldsymbol{u}_1 & \boldsymbol{u}_2 \end{bmatrix}
+\begin{bmatrix} \boldsymbol{q}_{t1} \\ \boldsymbol{q}_{t2} \\ \boldsymbol{r}_{t1} \\ \boldsymbol{r}_{t1} \end{bmatrix}
+\\
+\boldsymbol{x}^T \boldsymbol{q}_t + \boldsymbol{u}^T \boldsymbol{r}_t
+\end{array}$$
+
+\end{document}
diff --git a/y2014/control_loops/python/extended_lqr_derivation.py b/y2014/control_loops/python/extended_lqr_derivation.py
new file mode 100755
index 0000000..248c6fc
--- /dev/null
+++ b/y2014/control_loops/python/extended_lqr_derivation.py
@@ -0,0 +1,410 @@
+#!/usr/bin/python2
+
+# This file checks our math in extended_lqr.tex.
+
+from __future__ import print_function
+from __future__ import division
+
+import sys
+import random
+
+import sympy
+
+'''
+* `x_t1` means `x_{t + 1}`. Using `'x_t + 1'` as the symbol name makes the non-
+  latex output really confusing, so not doing that.
+* `xb` means `\\boldsymbol{x}`. Written as `'xbold'` in the symbol name because
+  that's what sympy.latex recognizes.
+* `xb_tb` means `\\boldsymbol{\\bar x}_t. Written as `'xboldbar'` in the symbol
+  name so sympy.latex recognizes it.
+'''
+
+# sympy.latex
+
+# n in the 2013 paper
+number_of_states = sympy.Symbol('states', integer=True)
+# m in the 2013 paper
+number_of_inputs = sympy.Symbol('inputs', integer=True)
+number_of_outputs = sympy.Symbol('outputs', integer=True)
+
+DIMENSIONS = set([number_of_states, number_of_inputs, number_of_outputs])
+
+A_t = sympy.MatrixSymbol('A_t', number_of_states, number_of_states)
+B_t = sympy.MatrixSymbol('B_t', number_of_states, number_of_inputs)
+cb_t = sympy.MatrixSymbol('cbold_t', number_of_states, 1)
+A_tb = sympy.MatrixSymbol('Abar_t', number_of_states, number_of_states)
+B_tb = sympy.MatrixSymbol('Bbar_t', number_of_states, number_of_inputs)
+cb_tb = sympy.MatrixSymbol('cboldbar_t', number_of_states, 1)
+
+Q_t = sympy.MatrixSymbol('Q_t', number_of_states, number_of_states)
+P_t = sympy.MatrixSymbol('P_t', number_of_inputs, number_of_states)
+R_t = sympy.MatrixSymbol('R_t', number_of_inputs, number_of_inputs)
+qb_t = sympy.MatrixSymbol('qbold_t', number_of_states, 1)
+rb_t = sympy.MatrixSymbol('rbold_t', number_of_inputs, 1)
+q_t = sympy.MatrixSymbol('q_t', 1, 1)
+
+S_t1 = sympy.MatrixSymbol('S_t1', number_of_states, number_of_states)
+sb_t1 = sympy.MatrixSymbol('sbold_t1', number_of_states, 1)
+s_t1 = sympy.MatrixSymbol('s_t1', 1, 1)
+S_tb = sympy.MatrixSymbol('Sbar_t', number_of_states, number_of_states)
+sb_tb = sympy.MatrixSymbol('sboldbar_t', number_of_states, 1)
+s_tb = sympy.MatrixSymbol('sbar_t', 1, 1)
+
+xb_t = sympy.MatrixSymbol('xbold_t', number_of_states, 1)
+ub_t = sympy.MatrixSymbol('ubold_t', number_of_inputs, 1)
+xb_t1 = sympy.MatrixSymbol('xbold_t1', number_of_states, 1)
+ub_t1 = sympy.MatrixSymbol('ubold_t1', number_of_inputs, 1)
+
+half = sympy.Integer(1) / sympy.Integer(2)
+xb = sympy.MatrixSymbol('xbold', number_of_states, 1)
+ub = sympy.MatrixSymbol('ubold', number_of_inputs, 1)
+
+CONSTANTS = set([
+    A_t, B_t, cb_t,
+    S_t1, sb_t1, s_t1,
+    A_tb, B_tb, cb_tb,
+    S_tb, sb_tb, s_tb,
+    P_t, Q_t, R_t, qb_t, rb_t, q_t,
+    ])
+
+SYMMETRIC_CONSTANTS = set([
+    S_t1, S_tb,
+    Q_t, R_t,
+    ])
+
+def verify_equivalent(a, b, inverses={}):
+  def get_matrices(m):
+    matrices = m.atoms(sympy.MatrixSymbol)
+    new_matrices = set()
+    for matrix in matrices:
+      if matrix in inverses:
+        new_matrices.update(inverses[matrix].atoms(sympy.MatrixSymbol))
+    matrices.update(new_matrices)
+  a_matrices, b_matrices = get_matrices(a), get_matrices(b)
+  if a_matrices != b_matrices:
+    raise RuntimeError('matrices different: %s vs %s' % (a_matrices,
+                                                         b_matrices))
+  a_symbols, b_symbols = a.atoms(sympy.Symbol), b.atoms(sympy.Symbol)
+  if a_symbols != b_symbols:
+    raise RuntimeError('symbols different: %s vs %s' % (a_symbols, b_symbols))
+  if not a_symbols < DIMENSIONS:
+    raise RuntimeError('not sure what to do with %s' % (a_symbols - DIMENSIONS))
+
+  if a.shape != b.shape:
+    raise RuntimeError('Different shapes: %s and %s' % (a.shape, b.shape))
+
+  for _ in range(10):
+    subs_symbols = {s: random.randint(1, 5) for s in a_symbols}
+    for _ in range(10):
+      diff = a - b
+      subs_matrices = {}
+      def get_replacement(*args):
+        try:
+          m = sympy.MatrixSymbol(*args)
+          if m not in subs_matrices:
+            if m in inverses:
+              i = inverses[m].replace(sympy.MatrixSymbol, get_replacement, simultaneous=False)
+              i_evaled = sympy.ImmutableMatrix(i.rows, i.cols,
+                                               lambda x,y: i[x, y].evalf())
+              subs_matrices[m] = i_evaled.I
+            else:
+              rows = m.rows.subs(subs_symbols)
+              cols = m.cols.subs(subs_symbols)
+              new_m = sympy.ImmutableMatrix(rows, cols,
+                                            lambda i,j: random.uniform(-5, 5))
+              if m in SYMMETRIC_CONSTANTS:
+                if rows != cols:
+                  raise RuntimeError('Non-square symmetric matrix %s' % m)
+                def calculate_cell(i, j):
+                  if i > j:
+                    return new_m[i, j]
+                  else:
+                    return new_m[j, i]
+                new_m = sympy.ImmutableMatrix(rows, cols, calculate_cell)
+              subs_matrices[m] = new_m
+          return subs_matrices[m]
+        except AttributeError as e:
+          # Stupid sympy silently eats AttributeErrors and treats them as
+          # "no replacement"...
+          raise RuntimeError(e)
+      # subs fails when it tries doing matrix multiplies between fixed-size ones
+      # and the rest of the equation which still has the symbolic-sized ones.
+      # subs(simultaneous=True) wants to put dummies in for everything first,
+      # and Dummy().transpose() is broken.
+      # replace() has the same issue as subs with simultaneous being True.
+      # lambdify() has no idea what to do with the transposes if you replace all
+      # the matrices with ones of random sizes full of dummies.
+      diff = diff.replace(sympy.MatrixSymbol, get_replacement,
+                          simultaneous=False)
+      for row in range(diff.rows):
+        for col in range(diff.cols):
+          result = diff[row, col].evalf()
+          if abs(result) > 1e-7:
+            raise RuntimeError('difference at (%s, %s) is %s' % (row, col,
+                                                                 result))
+
+def verify_arguments(f, *args):
+  matrix_atoms = f.atoms(sympy.MatrixSymbol) - CONSTANTS
+  if matrix_atoms != set(args):
+    print('Arguments expected to be %s, but are %s, in:\n%s' % (
+        sorted(args), sorted(list(matrix_atoms)), f), file=sys.stderr)
+    raise RuntimeError
+
+def make_c_t():
+  x_and_u = sympy.BlockMatrix(((xb,), (ub,)))
+  c_t = (half * x_and_u.transpose() *
+         sympy.BlockMatrix(((Q_t, P_t.T), (P_t, R_t))) * x_and_u +
+         x_and_u.transpose() * sympy.BlockMatrix(((qb_t,), (rb_t,))) +
+         q_t)
+  verify_arguments(c_t, xb, ub)
+  return c_t
+
+def check_backwards_cost():
+  g_t = A_t * xb_t + B_t * ub_t + cb_t
+  verify_arguments(g_t, xb_t, ub_t)
+  v_t1 = half * xb.transpose() * S_t1 * xb + xb.transpose() * sb_t1 + s_t1
+  verify_arguments(v_t1, xb)
+  v_t = (v_t1.subs(xb, g_t) + make_c_t()).subs({xb_t: xb, ub_t: ub})
+  verify_arguments(v_t, xb, ub)
+
+  v_t_for_cost = (
+      half * (
+          xb.transpose() * (A_t.transpose() * S_t1 * A_t + Q_t) * xb +
+          ub.transpose() * (B_t.transpose() * S_t1 * A_t + P_t) * xb +
+          xb.transpose() * (A_t.transpose() * S_t1 * B_t + P_t.T) * ub +
+          ub.transpose() * (B_t.transpose() * S_t1 * B_t + R_t) * ub) +
+      xb.transpose() * (A_t.transpose() * sb_t1 + qb_t) +
+      ub.transpose() * (B_t.transpose() * sb_t1 + rb_t) +
+      cb_t.transpose() * sb_t1 +
+      s_t1 + q_t +
+      half * (cb_t.transpose() * S_t1 * cb_t +
+    xb.transpose() * A_t.transpose() * S_t1 * cb_t +
+    ub.transpose() * B_t.transpose() * S_t1 * cb_t +
+    cb_t.transpose() * S_t1 * B_t * ub +
+              cb_t.transpose() * S_t1 * A_t * xb))
+  verify_equivalent(v_t, v_t_for_cost)
+
+  v_t_now = (
+      half * (xb.T * (A_t.T * S_t1 * A_t + Q_t) * xb +
+              ub.T * (B_t.T * S_t1 * A_t + P_t) * xb +
+              xb.T * (A_t.T * S_t1 * B_t + P_t.T) * ub +
+              ub.T * (B_t.T * S_t1 * B_t + R_t) * ub) +
+      xb.T * (A_t.T * sb_t1 + qb_t) +
+      ub.T * (B_t.T * sb_t1 + rb_t) +
+      cb_t.T * sb_t1 + s_t1 + q_t +
+      half * (cb_t.T * S_t1 * cb_t +
+              xb.T * A_t.T * S_t1 * cb_t +
+              ub.T * B_t.T * S_t1 * cb_t +
+              cb_t.T * S_t1 * B_t * ub +
+              cb_t.T * S_t1 * A_t * xb))
+
+  v_t_now = (
+      half * (xb.T * (A_t.T * S_t1 * A_t + Q_t) * xb +
+              ub.T * (B_t.T * S_t1 * A_t + P_t) * xb +
+              xb.T * (A_t.T * S_t1 * B_t + P_t.T) * ub +
+              ub.T * (B_t.T * S_t1 * B_t + R_t) * ub) +
+      xb.T * (A_t.T * sb_t1 + qb_t + half * A_t.T * S_t1 * cb_t) +
+      ub.T * (B_t.T * sb_t1 + rb_t + half * B_t.T * S_t1 * cb_t) +
+      half * cb_t.T * S_t1 * (A_t * xb + B_t * ub + cb_t) +
+      cb_t.T * sb_t1 + s_t1 + q_t)
+
+  v_t_now = (
+      half * (xb.T * (A_t.T * S_t1 * A_t + Q_t) * xb +
+              ub.T * (B_t.T * S_t1 * A_t + P_t) * xb +
+              xb.T * (A_t.T * S_t1 * B_t + P_t.T) * ub +
+              ub.T * (B_t.T * S_t1 * B_t + R_t) * ub) +
+      xb.T * (A_t.T * sb_t1 + qb_t + A_t.T * S_t1 * cb_t) +
+      ub.T * (B_t.T * sb_t1 + rb_t + B_t.T * S_t1 * cb_t) +
+      half * cb_t.T * S_t1 * cb_t +
+      cb_t.T * sb_t1 + s_t1 + q_t)
+
+  C_t = B_t.T * S_t1 * A_t + P_t
+  E_t = B_t.T * S_t1 * B_t + R_t
+  E_t_I = sympy.MatrixSymbol('E_t^-1', E_t.cols, E_t.rows)
+  L_t = -E_t_I * C_t
+  eb_t = B_t.T * S_t1 * cb_t + B_t.T * sb_t1 + rb_t
+  lb_t = -E_t_I * eb_t
+  D_t = A_t.T * S_t1 * A_t + Q_t
+  db_t = A_t.T * S_t1 * cb_t + A_t.T * sb_t1 + qb_t
+
+  v_t_now = (
+      half * (xb.T * D_t * xb + ub.T * C_t * xb +
+              xb.T * C_t.T * ub + ub.T * E_t * ub) +
+      xb.T * db_t + ub.T * eb_t +
+      half * cb_t.T * S_t1 * cb_t +
+      cb_t.T * sb_t1 + s_t1 + q_t)
+
+  v_t_final = (
+      half * xb.T * (D_t + L_t.T * C_t + C_t.T * L_t + L_t.T * E_t * L_t) * xb +
+      xb.T * (C_t.T * lb_t + L_t.T * E_t * lb_t + db_t + L_t.T * eb_t) +
+      half * lb_t.T * E_t * lb_t +
+      lb_t.T * eb_t +
+      cb_t.T * sb_t1 + s_t1 + q_t + half * cb_t.T * S_t1 * cb_t
+      )
+  verify_arguments(v_t_final, xb, E_t_I)
+  verify_equivalent(v_t.subs(ub, L_t * xb + lb_t), v_t_final, {E_t_I: E_t})
+
+  def v_t_from_s(this_S_t, this_sb_t, this_s_t):
+    return half * xb.T * this_S_t * xb + xb.T * this_sb_t + this_s_t
+
+  S_t_new_first = D_t + L_t.T * C_t + C_t.T * L_t + L_t.T * E_t * L_t
+  sb_t_new_first = db_t - C_t.T * E_t_I * eb_t
+  s_t_new_first = (half * lb_t.T * E_t * lb_t +
+                   lb_t.T * eb_t +
+                   cb_t.T * sb_t1 +
+                   s_t1 + q_t +
+                   half * cb_t.T * S_t1 * cb_t)
+  verify_equivalent(v_t_from_s(S_t_new_first, sb_t_new_first, s_t_new_first),
+                    v_t_final, {E_t_I: E_t})
+
+  S_t_new_end = D_t - C_t.T * E_t_I * C_t
+  sb_t_new_end = db_t - C_t.T * E_t_I * eb_t
+  s_t_new_end = (q_t - half * eb_t.T * E_t_I * eb_t +
+                 half * cb_t.T * S_t1 * cb_t + cb_t.T * sb_t1 + s_t1)
+  verify_equivalent(v_t_from_s(S_t_new_end, sb_t_new_end, s_t_new_end),
+                    v_t_final, {E_t_I: E_t})
+
+def check_forwards_cost():
+  v_tb = half * xb.T * S_tb * xb + xb.T * sb_tb + s_tb
+  verify_arguments(v_tb, xb)
+  g_tb = A_tb * xb_t1 + B_tb * ub + cb_tb
+  verify_arguments(g_tb, xb_t1, ub)
+  c_t1b = make_c_t().subs(xb, g_tb)
+  verify_arguments(c_t1b, xb_t1, ub)
+  v_t1b = v_tb.subs(xb, g_tb) + c_t1b
+  verify_arguments(v_t1b, xb_t1, ub)
+
+  v_t1b_now = (
+      half * g_tb.T * S_tb * g_tb +
+      g_tb.T * sb_tb + s_tb +
+      half * (g_tb.T * Q_t * g_tb +
+              ub.T * P_t * g_tb +
+              g_tb.T * P_t.T * ub +
+              ub.T * R_t * ub) +
+      g_tb.T * qb_t + ub.T * rb_t + q_t)
+
+  v_t1b_for_cost = (
+      half * (xb_t1.T * A_tb.T * (S_tb + Q_t) * A_tb * xb_t1 +
+              xb_t1.T * A_tb.T * (S_tb + Q_t) * B_tb * ub +
+              xb_t1.T * A_tb.T * (S_tb + Q_t) * cb_tb +
+              ub.T * B_tb.T * (S_tb + Q_t) * A_tb * xb_t1 +
+              ub.T * B_tb.T * (S_tb + Q_t) * B_tb * ub +
+              ub.T * B_tb.T * (S_tb + Q_t) * cb_tb +
+              cb_tb.T * (S_tb + Q_t) * A_tb * xb_t1 +
+              cb_tb.T * (S_tb + Q_t) * B_tb * ub +
+              cb_tb.T * (S_tb + Q_t) * cb_tb) +
+      xb_t1.T * A_tb.T * sb_tb +
+      ub.T * B_tb.T * sb_tb +
+      cb_tb.T * sb_tb +
+      s_tb +
+      half * (ub.T * P_t * A_tb * xb_t1 +
+              ub.T * P_t * B_tb * ub +
+              ub.T * P_t * cb_tb) +
+      half * (xb_t1.T * A_tb.T * P_t.T * ub +
+              ub.T * B_tb.T * P_t.T * ub +
+              cb_tb.T * P_t.T * ub) +
+      half * ub.T * R_t * ub +
+      xb_t1.T * A_tb.T * qb_t + ub.T * B_tb.T * qb_t + cb_tb.T * qb_t +
+      ub.T * rb_t + q_t)
+  verify_equivalent(v_t1b, v_t1b_for_cost)
+
+  S_and_Q = S_tb + Q_t
+
+  v_t1b_now = (
+      half * (xb_t1.T * A_tb.T * S_and_Q * A_tb * xb_t1 +
+              xb_t1.T * A_tb.T * S_and_Q * B_tb * ub +
+              xb_t1.T * A_tb.T * S_and_Q * cb_tb +
+              ub.T * B_tb.T * S_and_Q * A_tb * xb_t1 +
+              ub.T * B_tb.T * S_and_Q * B_tb * ub +
+              ub.T * B_tb.T * S_and_Q * cb_tb +
+              cb_tb.T * S_and_Q * A_tb * xb_t1 +
+              cb_tb.T * S_and_Q * B_tb * ub +
+              cb_tb.T * S_and_Q * cb_tb) +
+      xb_t1.T * A_tb.T * sb_tb +
+      ub.T * B_tb.T * sb_tb +
+      cb_tb.T * sb_tb +
+      s_tb +
+      half * (ub.T * P_t * A_tb * xb_t1 +
+              ub.T * P_t * B_tb * ub +
+              ub.T * P_t * cb_tb) +
+      half * (xb_t1.T * A_tb.T * P_t.T * ub +
+              ub.T * B_tb.T * P_t.T * ub +
+              cb_tb.T * P_t.T * ub) +
+      half * ub.T * R_t * ub +
+      xb_t1.T * A_tb.T * qb_t +
+      ub.T * B_tb.T * qb_t +
+      cb_tb.T * qb_t +
+      ub.T * rb_t +
+      q_t)
+
+  C_tb = B_tb.T * S_and_Q * A_tb + P_t * A_tb
+  E_tb = B_tb.T * S_and_Q * B_tb + B_tb.T * P_t.T + P_t * B_tb + R_t
+  E_tb_I = sympy.MatrixSymbol('Ebar_t^-1', E_tb.cols, E_tb.rows)
+  L_tb = -E_tb_I * C_tb
+  eb_tb = B_tb.T * S_and_Q * cb_tb + B_tb.T * sb_tb + P_t * cb_tb + B_tb.T * qb_t + rb_t
+  lb_tb = -E_tb_I * eb_tb
+  D_tb = A_tb.T * S_and_Q * A_tb
+  db_tb = A_tb.T * S_and_Q * cb_tb + A_tb.T * (sb_tb + qb_t)
+
+  v_t1b_now = (
+      half * (xb_t1.T * D_tb * xb_t1 +
+              xb_t1.T * C_tb.T * ub +
+              ub.T * C_tb * xb_t1 +
+              ub.T * E_tb * ub) +
+      xb_t1.T * db_tb +
+      ub.T * eb_tb +
+      half * cb_tb.T * S_and_Q * cb_tb +
+      cb_tb.T * sb_tb +
+      cb_tb.T * qb_t +
+      s_tb + q_t)
+
+  v_t1b_final = (
+      half * xb_t1.T * (D_tb - C_tb.T * E_tb_I * C_tb) * xb_t1 +
+      xb_t1.T * (db_tb - C_tb.T * E_tb_I * eb_tb) +
+      -half * eb_tb.T * E_tb_I * eb_tb +
+      half * cb_tb.T * S_and_Q * cb_tb +
+      cb_tb.T * sb_tb +
+      cb_tb.T * qb_t +
+      s_tb + q_t)
+  verify_arguments(v_t1b_final, xb_t1, E_tb_I)
+  verify_equivalent(v_t1b.subs(ub, -E_tb_I * C_tb * xb_t1 - E_tb_I * eb_tb),
+                    v_t1b_final, {E_tb_I: E_tb})
+
+def check_forwards_u():
+  S_and_Q = S_tb + Q_t
+
+  diff_start = (
+      half * (xb_t1.T * A_tb.T * S_and_Q * B_tb +
+              (B_tb.T * S_and_Q * A_tb * xb_t1).T +
+              2 * ub.T * B_tb.T * S_and_Q * B_tb +
+              (B_tb.T * S_and_Q * cb_tb).T +
+              cb_tb.T * S_and_Q * B_tb) +
+      sb_tb.T * B_tb +
+      half * (P_t * A_tb * xb_t1).T +
+      half * xb_t1.T * A_tb.T * P_t.T +
+      half * ub.T * (P_t * B_tb + B_tb.T * P_t.T) +
+      half * ub.T * (B_tb.T * P_t.T + P_t * B_tb) +
+      half * (P_t * cb_tb).T +
+      half * cb_tb.T * P_t.T +
+      ub.T * R_t +
+      (B_tb.T * qb_t).T + rb_t.T)
+  verify_arguments(diff_start, xb_t1, ub)
+
+  diff_end = (
+      xb_t1.T * (A_tb.T * S_and_Q * B_tb + A_tb.T * P_t.T) +
+      ub.T * (B_tb.T * S_and_Q * B_tb + B_tb.T * P_t.T + P_t * B_tb + R_t) +
+      cb_tb.T * S_and_Q * B_tb +
+      sb_tb.T * B_tb +
+      cb_tb.T * P_t.T +
+      qb_t.T * B_tb +
+      rb_t.T)
+  verify_equivalent(diff_start, diff_end)
+
+def main():
+  sympy.init_printing(use_unicode=True)
+  check_backwards_cost()
+  check_forwards_cost()
+  check_forwards_u()
+
+if __name__ == '__main__':
+  main()
diff --git a/y2014/wpilib/wpilib_interface.cc b/y2014/wpilib/wpilib_interface.cc
index 5195ab6..a53d54b 100644
--- a/y2014/wpilib/wpilib_interface.cc
+++ b/y2014/wpilib/wpilib_interface.cc
@@ -4,6 +4,7 @@
 #include <inttypes.h>
 
 #include <thread>
+#include <chrono>
 #include <mutex>
 #include <functional>
 
@@ -260,8 +261,8 @@
     bottom_reader_.Start();
     dma_synchronizer_->Start();
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                        ::aos::time::Time::InMS(4));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                        ::std::chrono::milliseconds(4));
 
     ::aos::SetCurrentThreadRealtimePriority(40);
     while (run_) {
@@ -504,8 +505,8 @@
     ::aos::SetCurrentThreadName("Solenoids");
     ::aos::SetCurrentThreadRealtimePriority(27);
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
-                                        ::aos::time::Time::InMS(1));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+                                        ::std::chrono::milliseconds(1));
 
     while (run_) {
       {
diff --git a/y2014_bot3/BUILD b/y2014_bot3/BUILD
index 3ec0bb5..1c07423 100644
--- a/y2014_bot3/BUILD
+++ b/y2014_bot3/BUILD
@@ -16,21 +16,22 @@
     '//frc971/queues:gyro',
     '//y2014_bot3/autonomous:auto_queue',
     '//y2014_bot3/control_loops/rollers:rollers_queue',
-    '//y2014_bot3/control_loops/drivetrain:drivetrain_queue',
+    '//frc971/control_loops/drivetrain:drivetrain_queue',
   ],
 )
 
 aos_downloader(
-  name = 'download',
+  name = 'download_stripped',
   start_srcs = [
-    '//aos:prime_start_binaries',
-    '//y2014_bot3/control_loops/drivetrain:drivetrain',
-    '//y2014_bot3/control_loops/rollers:rollers',
-    '//y2014_bot3/autonomous:auto',
-    ':joystick_reader',
-    '//y2014_bot3/wpilib:wpilib_interface',
+    ':joystick_reader.stripped',
+    '//aos:prime_start_binaries_stripped',
+    '//y2014_bot3/autonomous:auto.stripped',
+    '//y2014_bot3/control_loops/drivetrain:drivetrain.stripped',
+    '//y2014_bot3/control_loops/rollers:rollers.stripped',
+    '//y2014_bot3/wpilib:wpilib_interface.stripped',
+
   ],
   srcs = [
-    '//aos:prime_binaries',
+    '//aos:prime_binaries_stripped',
   ],
 )
diff --git a/y2014_bot3/autonomous/BUILD b/y2014_bot3/autonomous/BUILD
index f90ce74..bfd7f34 100644
--- a/y2014_bot3/autonomous/BUILD
+++ b/y2014_bot3/autonomous/BUILD
@@ -20,8 +20,7 @@
   deps = [
     ':auto_queue',
     '//aos/common/controls:control_loop',
-    '//y2014_bot3/control_loops/drivetrain:drivetrain_queue',
-    '//y2014_bot3/control_loops/drivetrain:drivetrain_lib',
+    '//frc971/control_loops/drivetrain:drivetrain_queue',
     '//y2014_bot3/control_loops/rollers:rollers_queue',
     '//aos/common:time',
     '//aos/common/util:phased_loop',
diff --git a/y2014_bot3/autonomous/auto.cc b/y2014_bot3/autonomous/auto.cc
index 3724cbe..80f2b09 100644
--- a/y2014_bot3/autonomous/auto.cc
+++ b/y2014_bot3/autonomous/auto.cc
@@ -8,13 +8,12 @@
 #include "aos/common/logging/logging.h"
 #include "aos/common/logging/queue_logging.h"
 
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
 #include "y2014_bot3/autonomous/auto.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
 #include "y2014_bot3/control_loops/rollers/rollers.q.h"
 
 using ::aos::time::Time;
-using ::y2014_bot3::control_loops::drivetrain_queue;
+using ::frc971::control_loops::drivetrain_queue;
 using ::y2014_bot3::control_loops::rollers_queue;
 
 namespace y2014_bot3 {
@@ -35,7 +34,7 @@
 
 void ResetDrivetrain() {
   LOG(INFO, "resetting the drivetrain\n");
-  control_loops::drivetrain_queue.goal.MakeWithBuilder()
+  ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
       .control_loop_driving(false)
       .steering(0.0)
       .throttle(0.0)
@@ -47,11 +46,11 @@
 }
 
 void InitializeEncoders() {
-  control_loops::drivetrain_queue.status.FetchAnother();
+  ::frc971::control_loops::drivetrain_queue.status.FetchAnother();
   left_initial_position =
-      control_loops::drivetrain_queue.status->estimated_left_position;
+      ::frc971::control_loops::drivetrain_queue.status->estimated_left_position;
   right_initial_position =
-      control_loops::drivetrain_queue.status->estimated_right_position;
+      ::frc971::control_loops::drivetrain_queue.status->estimated_right_position;
 }
 
 void HandleAuto() {
@@ -63,7 +62,7 @@
   InitializeEncoders();
 
   LOG(INFO, "Driving\n");
-  control_loops::drivetrain_queue.goal.MakeWithBuilder()
+  ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
       .control_loop_driving(false)
       .highgear(false)
       .quickturn(false)
@@ -76,7 +75,7 @@
       .Send();
   time::SleepFor(time::Time::InSeconds(2.0));
 
-  control_loops::drivetrain_queue.goal.MakeWithBuilder()
+  ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
       .control_loop_driving(false)
       .highgear(false)
       .quickturn(false)
diff --git a/y2014_bot3/control_loops/drivetrain/BUILD b/y2014_bot3/control_loops/drivetrain/BUILD
index 32afd4b..6bd7e33 100644
--- a/y2014_bot3/control_loops/drivetrain/BUILD
+++ b/y2014_bot3/control_loops/drivetrain/BUILD
@@ -2,45 +2,6 @@
 
 load('/aos/build/queues', 'queue_library')
 
-cc_binary(
-  name = 'replay_drivetrain',
-  srcs = [
-    'replay_drivetrain.cc',
-  ],
-  deps = [
-    ':drivetrain_queue',
-    '//aos/common/controls:replay_control_loop',
-    '//aos/linux_code:init',
-  ],
-)
-
-queue_library(
-  name = 'drivetrain_queue',
-  srcs = [
-    'drivetrain.q',
-  ],
-  deps = [
-    '//aos/common/controls:control_loop_queues',
-  ],
-)
-
-cc_library(
-  name = 'polydrivetrain_plants',
-  srcs = [
-    'polydrivetrain_dog_motor_plant.cc',
-    'drivetrain_dog_motor_plant.cc',
-    'polydrivetrain_cim_plant.cc',
-  ],
-  hdrs = [
-    'polydrivetrain_dog_motor_plant.h',
-    'drivetrain_dog_motor_plant.h',
-    'polydrivetrain_cim_plant.h',
-  ],
-  deps = [
-    '//frc971/control_loops:state_feedback_loop',
-  ],
-)
-
 genrule(
   name = 'genrule_drivetrain',
   visibility = ['//visibility:private'],
@@ -51,47 +12,55 @@
   outs = [
     'drivetrain_dog_motor_plant.h',
     'drivetrain_dog_motor_plant.cc',
+    'kalman_drivetrain_motor_plant.h',
+    'kalman_drivetrain_motor_plant.cc',
+  ],
+)
+
+genrule(
+  name = 'genrule_polydrivetrain',
+  visibility = ['//visibility:private'],
+  cmd = '$(location //y2014_bot3/control_loops/python:polydrivetrain) $(OUTS)',
+  tools = [
+    '//y2014_bot3/control_loops/python:polydrivetrain',
+  ],
+  outs = [
+    'polydrivetrain_dog_motor_plant.h',
+    'polydrivetrain_dog_motor_plant.cc',
+    'polydrivetrain_cim_plant.h',
+    'polydrivetrain_cim_plant.cc',
   ],
 )
 
 cc_library(
-  name = 'drivetrain_lib',
-  hdrs = [
-    'drivetrain.h',
-  ],
+  name = 'polydrivetrain_plants',
   srcs = [
-    'drivetrain.cc',
+    'polydrivetrain_dog_motor_plant.cc',
+    'drivetrain_dog_motor_plant.cc',
+    'kalman_drivetrain_motor_plant.cc',
+  ],
+  hdrs = [
+    'polydrivetrain_dog_motor_plant.h',
+    'drivetrain_dog_motor_plant.h',
+    'kalman_drivetrain_motor_plant.h',
   ],
   deps = [
-    ':polydrivetrain_plants',
-    ':drivetrain_queue',
-    '//aos/common/controls:control_loop',
-    '//aos/common/controls:polytope',
     '//frc971/control_loops:state_feedback_loop',
-    '//frc971/control_loops:coerce_goal',
-    '//frc971/queues:gyro',
-    '//aos/common/logging:queue_logging',
-    '//aos/common/logging:matrix_logging',
-    '//aos/common:math',
-    '//aos/common/util:log_interval',
-    '//frc971:shifter_hall_effect',
   ],
 )
 
-cc_test(
-  name = 'drivetrain_lib_test',
+cc_library(
+  name = 'drivetrain_base',
   srcs = [
-    'drivetrain_lib_test.cc',
+    'drivetrain_base.cc',
+  ],
+  hdrs = [
+    'drivetrain_base.h',
   ],
   deps = [
-    '//aos/testing:googletest',
-    ':drivetrain_queue',
-    ':drivetrain_lib',
-    '//aos/common/controls:control_loop_test',
-    '//frc971/control_loops:state_feedback_loop',
-    '//frc971/queues:gyro',
-    '//aos/common:queues',
-    '//aos/common/network:team_number',
+    ':polydrivetrain_plants',
+    '//frc971/control_loops/drivetrain:drivetrain_config',
+    '//frc971:shifter_hall_effect',
   ],
 )
 
@@ -101,8 +70,8 @@
     'drivetrain_main.cc',
   ],
   deps = [
-    ':drivetrain_lib',
-    ':drivetrain_queue',
+    ':drivetrain_base',
     '//aos/linux_code:init',
+    '//frc971/control_loops/drivetrain:drivetrain_lib',
   ],
 )
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain.cc b/y2014_bot3/control_loops/drivetrain/drivetrain.cc
deleted file mode 100644
index 125dd24..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain.cc
+++ /dev/null
@@ -1,571 +0,0 @@
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
-
-#include <stdio.h>
-#include <sched.h>
-#include <cmath>
-#include <memory>
-#include "Eigen/Dense"
-
-#include "aos/common/logging/logging.h"
-#include "aos/common/controls/polytope.h"
-#include "aos/common/commonmath.h"
-#include "aos/common/logging/queue_logging.h"
-#include "aos/common/logging/matrix_logging.h"
-
-#include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/coerce_goal.h"
-#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-#include "frc971/queues/gyro.q.h"
-#include "frc971/shifter_hall_effect.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
-
-using ::frc971::sensors::gyro_reading;
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-class DrivetrainMotorsSS {
- public:
-  class LimitedDrivetrainLoop : public StateFeedbackLoop<4, 2, 2> {
-   public:
-    LimitedDrivetrainLoop(StateFeedbackLoop<4, 2, 2> &&loop)
-        : StateFeedbackLoop<4, 2, 2>(::std::move(loop)),
-          U_Poly_((Eigen::Matrix<double, 4, 2>() << 1, 0, -1, 0, 0, 1, 0, -1)
-                      .finished(),
-                  (Eigen::Matrix<double, 4, 1>() << 12.0, 12.0, 12.0, 12.0)
-                      .finished()) {
-      ::aos::controls::HPolytope<0>::Init();
-      T << 1, -1, 1, 1;
-      T_inverse = T.inverse();
-    }
-
-    bool output_was_capped() const { return output_was_capped_; }
-
-   private:
-    virtual void CapU() {
-      const Eigen::Matrix<double, 4, 1> error = R() - X_hat();
-
-      if (::std::abs(U(0, 0)) > 12.0 || ::std::abs(U(1, 0)) > 12.0) {
-        mutable_U() =
-            U() * 12.0 / ::std::max(::std::abs(U(0, 0)), ::std::abs(U(1, 0)));
-        LOG_MATRIX(DEBUG, "U is now", U());
-        // TODO(Austin): Figure out why the polytope stuff wasn't working and
-        // remove this hack.
-        output_was_capped_ = true;
-        return;
-
-        LOG_MATRIX(DEBUG, "U at start", U());
-        LOG_MATRIX(DEBUG, "R at start", R());
-        LOG_MATRIX(DEBUG, "Xhat at start", X_hat());
-
-        Eigen::Matrix<double, 2, 2> position_K;
-        position_K << K(0, 0), K(0, 2), K(1, 0), K(1, 2);
-        Eigen::Matrix<double, 2, 2> velocity_K;
-        velocity_K << K(0, 1), K(0, 3), K(1, 1), K(1, 3);
-
-        Eigen::Matrix<double, 2, 1> position_error;
-        position_error << error(0, 0), error(2, 0);
-        const auto drive_error = T_inverse * position_error;
-        Eigen::Matrix<double, 2, 1> velocity_error;
-        velocity_error << error(1, 0), error(3, 0);
-        LOG_MATRIX(DEBUG, "error", error);
-
-        const auto &poly = U_Poly_;
-        const Eigen::Matrix<double, 4, 2> pos_poly_H =
-            poly.H() * position_K * T;
-        const Eigen::Matrix<double, 4, 1> pos_poly_k =
-            poly.k() - poly.H() * velocity_K * velocity_error;
-        const ::aos::controls::HPolytope<2> pos_poly(pos_poly_H, pos_poly_k);
-
-        Eigen::Matrix<double, 2, 1> adjusted_pos_error;
-        {
-          const auto &P = drive_error;
-
-          Eigen::Matrix<double, 1, 2> L45;
-          L45 << ::aos::sign(P(1, 0)), -::aos::sign(P(0, 0));
-          const double w45 = 0;
-
-          Eigen::Matrix<double, 1, 2> LH;
-          if (::std::abs(P(0, 0)) > ::std::abs(P(1, 0))) {
-            LH << 0, 1;
-          } else {
-            LH << 1, 0;
-          }
-          const double wh = LH.dot(P);
-
-          Eigen::Matrix<double, 2, 2> standard;
-          standard << L45, LH;
-          Eigen::Matrix<double, 2, 1> W;
-          W << w45, wh;
-          const Eigen::Matrix<double, 2, 1> intersection =
-              standard.inverse() * W;
-
-          bool is_inside_h;
-          const auto adjusted_pos_error_h = frc971::control_loops::DoCoerceGoal(
-              pos_poly, LH, wh, drive_error, &is_inside_h);
-          const auto adjusted_pos_error_45 =
-              frc971::control_loops::DoCoerceGoal(pos_poly, L45, w45,
-                                                  intersection, nullptr);
-          if (pos_poly.IsInside(intersection)) {
-            adjusted_pos_error = adjusted_pos_error_h;
-          } else {
-            if (is_inside_h) {
-              if (adjusted_pos_error_h.norm() > adjusted_pos_error_45.norm()) {
-                adjusted_pos_error = adjusted_pos_error_h;
-              } else {
-                adjusted_pos_error = adjusted_pos_error_45;
-              }
-            } else {
-              adjusted_pos_error = adjusted_pos_error_45;
-            }
-          }
-        }
-
-        LOG_MATRIX(DEBUG, "adjusted_pos_error", adjusted_pos_error);
-        mutable_U() =
-            velocity_K * velocity_error + position_K * T * adjusted_pos_error;
-        LOG_MATRIX(DEBUG, "U is now", U());
-      } else {
-        output_was_capped_ = false;
-      }
-    }
-
-    const ::aos::controls::HPolytope<2> U_Poly_;
-    Eigen::Matrix<double, 2, 2> T, T_inverse;
-    bool output_was_capped_ = false;
-  };
-
-  DrivetrainMotorsSS()
-      : loop_(new LimitedDrivetrainLoop(
-            ::y2014_bot3::control_loops::drivetrain::MakeDrivetrainLoop())),
-        filtered_offset_(0.0),
-        gyro_(0.0),
-        left_goal_(0.0),
-        right_goal_(0.0),
-        raw_left_(0.0),
-        raw_right_(0.0) {
-    // Low gear on both.
-    loop_->set_controller_index(0);
-  }
-
-  void SetGoal(double left, double left_velocity, double right,
-               double right_velocity) {
-    left_goal_ = left;
-    right_goal_ = right;
-    loop_->mutable_R() << left, left_velocity, right, right_velocity;
-  }
-  void SetRawPosition(double left, double right) {
-    raw_right_ = right;
-    raw_left_ = left;
-    Eigen::Matrix<double, 2, 1> Y;
-    Y << left + filtered_offset_, right - filtered_offset_;
-    loop_->Correct(Y);
-  }
-  void SetPosition(double left, double right, double gyro) {
-    // Decay the offset quickly because this gyro is great.
-    const double offset = (right - left - gyro * kDrivetrainTurnWidth) / 2.0;
-    filtered_offset_ = 0.25 * offset + 0.75 * filtered_offset_;
-    gyro_ = gyro;
-    SetRawPosition(left, right);
-  }
-
-  void SetExternalMotors(double left_voltage, double right_voltage) {
-    loop_->mutable_U() << left_voltage, right_voltage;
-  }
-
-  void Update(bool stop_motors, bool enable_control_loop) {
-    if (enable_control_loop) {
-      loop_->Update(stop_motors);
-    } else {
-      if (stop_motors) {
-        loop_->mutable_U().setZero();
-        loop_->mutable_U_uncapped().setZero();
-      }
-      loop_->UpdateObserver(loop_->U());
-    }
-    ::Eigen::Matrix<double, 4, 1> E = loop_->R() - loop_->X_hat();
-    LOG_MATRIX(DEBUG, "E", E);
-  }
-
-  double GetEstimatedRobotSpeed() const {
-    // lets just call the average of left and right velocities close enough
-    return (loop_->X_hat(1, 0) + loop_->X_hat(3, 0)) / 2;
-  }
-
-  double GetEstimatedLeftEncoder() const { return loop_->X_hat(0, 0); }
-
-  double GetEstimatedRightEncoder() const { return loop_->X_hat(2, 0); }
-
-  bool OutputWasCapped() const { return loop_->output_was_capped(); }
-
-  void SendMotors(DrivetrainQueue::Output *output) const {
-    if (output) {
-      output->left_voltage = loop_->U(0, 0);
-      output->right_voltage = loop_->U(1, 0);
-      output->left_high = false;
-      output->right_high = false;
-    }
-  }
-
-  const LimitedDrivetrainLoop &loop() const { return *loop_; }
-
- private:
-  ::std::unique_ptr<LimitedDrivetrainLoop> loop_;
-
-  double filtered_offset_;
-  double gyro_;
-  double left_goal_;
-  double right_goal_;
-  double raw_left_;
-  double raw_right_;
-};
-
-class PolyDrivetrain {
- public:
-  enum Gear { HIGH, LOW };
-  // Stall Torque in N m
-  static constexpr double kStallTorque = 2.42;
-  // Stall Current in Amps
-  static constexpr double kStallCurrent = 133.0;
-  // Free Speed in RPM. Used number from last year.
-  static constexpr double kFreeSpeed = 4650.0;
-  // Free Current in Amps
-  static constexpr double kFreeCurrent = 2.7;
-  // Moment of inertia of the drivetrain in kg m^2
-  // Just borrowed from last year.
-  static constexpr double J = 10;
-  // Mass of the robot, in kg.
-  static constexpr double m = 68;
-  // Radius of the robot, in meters (from last year).
-  static constexpr double rb = 0.66675 / 2.0;
-  static constexpr double kWheelRadius = 0.04445;
-  // Resistance of the motor, divided by the number of motors.
-  static constexpr double kR =
-      (12.0 / kStallCurrent / 4 + 0.03) / (0.93 * 0.93);
-  // Motor velocity constant
-  static constexpr double Kv =
-      ((kFreeSpeed / 60.0 * 2.0 * M_PI) / (12.0 - kR * kFreeCurrent));
-  // Torque constant
-  static constexpr double Kt = kStallTorque / kStallCurrent;
-
-  PolyDrivetrain()
-      : U_Poly_((Eigen::Matrix<double, 4, 2>() << /*[[*/ 1, 0 /*]*/,
-                 /*[*/ -1, 0 /*]*/,
-                 /*[*/ 0, 1 /*]*/,
-                 /*[*/ 0, -1 /*]]*/).finished(),
-                (Eigen::Matrix<double, 4, 1>() << /*[[*/ 12 /*]*/,
-                 /*[*/ 12 /*]*/,
-                 /*[*/ 12 /*]*/,
-                 /*[*/ 12 /*]]*/).finished()),
-        loop_(new StateFeedbackLoop<2, 2, 2>(
-            ::y2014_bot3::control_loops::MakeVelocityDrivetrainLoop())),
-        ttrust_(1.1),
-        wheel_(0.0),
-        throttle_(0.0),
-        quickturn_(false),
-        stale_count_(0),
-        position_time_delta_(0.01),
-        left_gear_(LOW),
-        right_gear_(LOW),
-        counter_(0) {
-    last_position_.Zero();
-    position_.Zero();
-  }
-
-  static double MotorSpeed(bool high_gear, double velocity) {
-    if (high_gear) {
-      return velocity / kDrivetrainHighGearRatio / kWheelRadius;
-    } else {
-      return velocity / kDrivetrainLowGearRatio / kWheelRadius;
-    }
-  }
-
-  void SetGoal(double wheel, double throttle, bool quickturn, bool highgear) {
-    const double kWheelNonLinearity = 0.5;
-    // Apply a sin function that's scaled to make it feel better.
-    const double angular_range = M_PI_2 * kWheelNonLinearity;
-
-    quickturn_ = quickturn;
-    wheel_ = sin(angular_range * wheel) / sin(angular_range);
-    wheel_ = sin(angular_range * wheel_) / sin(angular_range);
-    if (!quickturn_) {
-      wheel_ *= 1.5;
-    }
-
-    static const double kThrottleDeadband = 0.05;
-    if (::std::abs(throttle) < kThrottleDeadband) {
-      throttle_ = 0;
-    } else {
-      throttle_ = copysign((::std::abs(throttle) - kThrottleDeadband) /
-                               (1.0 - kThrottleDeadband),
-                           throttle);
-    }
-
-    Gear requested_gear = highgear ? HIGH : LOW;
-    left_gear_ = right_gear_ = requested_gear;
-  }
-
-  void SetPosition(const DrivetrainQueue::Position *position) {
-    if (position == NULL) {
-      ++stale_count_;
-    } else {
-      last_position_ = position_;
-      position_ = *position;
-      position_time_delta_ = (stale_count_ + 1) * 0.01;
-      stale_count_ = 0;
-    }
-  }
-
-  double FilterVelocity(double throttle) {
-    const Eigen::Matrix<double, 2, 2> FF =
-        loop_->B().inverse() *
-        (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
-
-    constexpr int kHighGearController = 3;
-    const Eigen::Matrix<double, 2, 2> FF_high =
-        loop_->controller(kHighGearController).plant.B().inverse() *
-        (Eigen::Matrix<double, 2, 2>::Identity() -
-         loop_->controller(kHighGearController).plant.A());
-
-    ::Eigen::Matrix<double, 1, 2> FF_sum = FF.colwise().sum();
-    int min_FF_sum_index;
-    const double min_FF_sum = FF_sum.minCoeff(&min_FF_sum_index);
-    const double min_K_sum = loop_->K().col(min_FF_sum_index).sum();
-    const double high_min_FF_sum = FF_high.col(0).sum();
-
-    const double adjusted_ff_voltage = ::aos::Clip(
-        throttle * 12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0);
-    return (adjusted_ff_voltage +
-            ttrust_ * min_K_sum * (loop_->X_hat(0, 0) + loop_->X_hat(1, 0)) /
-                2.0) /
-           (ttrust_ * min_K_sum + min_FF_sum);
-  }
-
-  double MaxVelocity() {
-    const Eigen::Matrix<double, 2, 2> FF =
-        loop_->B().inverse() *
-        (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
-
-    constexpr int kHighGearController = 3;
-    const Eigen::Matrix<double, 2, 2> FF_high =
-        loop_->controller(kHighGearController).plant.B().inverse() *
-        (Eigen::Matrix<double, 2, 2>::Identity() -
-         loop_->controller(kHighGearController).plant.A());
-
-    ::Eigen::Matrix<double, 1, 2> FF_sum = FF.colwise().sum();
-    int min_FF_sum_index;
-    const double min_FF_sum = FF_sum.minCoeff(&min_FF_sum_index);
-    // const double min_K_sum = loop_->K().col(min_FF_sum_index).sum();
-    const double high_min_FF_sum = FF_high.col(0).sum();
-
-    const double adjusted_ff_voltage =
-        ::aos::Clip(12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0);
-    return adjusted_ff_voltage / min_FF_sum;
-  }
-
-  void Update() {
-    // TODO(austin): Observer for the current velocity instead of difference
-    // calculations.
-    ++counter_;
-
-    const double current_left_velocity =
-        (position_.left_encoder - last_position_.left_encoder) /
-        position_time_delta_;
-    const double current_right_velocity =
-        (position_.right_encoder - last_position_.right_encoder) /
-        position_time_delta_;
-    const double left_motor_speed = MotorSpeed(left_gear_ == HIGH,
-        current_left_velocity);
-    const double right_motor_speed = MotorSpeed(right_gear_ == HIGH,
-        current_right_velocity);
-
-    {
-      CIMLogging logging;
-
-      // Reset the CIM model to the current conditions to be ready for when we
-      // shift.
-      logging.left_in_gear = true;
-      logging.left_motor_speed = left_motor_speed;
-      logging.left_velocity = current_left_velocity;
-
-      logging.right_in_gear = true;
-      logging.right_motor_speed = right_motor_speed;
-      logging.right_velocity = current_right_velocity;
-
-      LOG_STRUCT(DEBUG, "currently", logging);
-    }
-
-    {
-      // FF * X = U (steady state)
-      const Eigen::Matrix<double, 2, 2> FF =
-          loop_->B().inverse() *
-          (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
-
-      // Invert the plant to figure out how the velocity filter would have to
-      // work
-      // out in order to filter out the forwards negative inertia.
-      // This math assumes that the left and right power and velocity are
-      // equals,
-      // and that the plant is the same on the left and right.
-      const double fvel = FilterVelocity(throttle_);
-
-      const double sign_svel = wheel_ * ((fvel > 0.0) ? 1.0 : -1.0);
-      double steering_velocity;
-      if (quickturn_) {
-        steering_velocity = wheel_ * MaxVelocity();
-      } else {
-        steering_velocity = ::std::abs(fvel) * wheel_;
-      }
-      const double left_velocity = fvel - steering_velocity;
-      const double right_velocity = fvel + steering_velocity;
-      LOG(DEBUG, "l=%f r=%f\n", left_velocity, right_velocity);
-
-      // Integrate velocity to get the position.
-      // This position is used to get integral control.
-      loop_->mutable_R() << left_velocity, right_velocity;
-
-      if (!quickturn_) {
-        // K * R = w
-        Eigen::Matrix<double, 1, 2> equality_k;
-        equality_k << 1 + sign_svel, -(1 - sign_svel);
-        const double equality_w = 0.0;
-
-        // Construct a constraint on R by manipulating the constraint on U
-        ::aos::controls::HPolytope<2> R_poly = ::aos::controls::HPolytope<2>(
-            U_Poly_.H() * (loop_->K() + FF),
-            U_Poly_.k() + U_Poly_.H() * loop_->K() * loop_->X_hat());
-
-        // Limit R back inside the box.
-        loop_->mutable_R() = frc971::control_loops::CoerceGoal(
-            R_poly, equality_k, equality_w, loop_->R());
-      }
-
-      const Eigen::Matrix<double, 2, 1> FF_volts = FF * loop_->R();
-      const Eigen::Matrix<double, 2, 1> U_ideal =
-          loop_->K() * (loop_->R() - loop_->X_hat()) + FF_volts;
-
-      for (int i = 0; i < 2; i++) {
-        loop_->mutable_U()[i] = ::aos::Clip(U_ideal[i], -12, 12);
-      }
-
-      // TODO(austin): Model this better.
-      // TODO(austin): Feedback?
-      loop_->mutable_X_hat() =
-          loop_->A() * loop_->X_hat() + loop_->B() * loop_->U();
-    }
-  }
-
-  void SendMotors(DrivetrainQueue::Output *output) {
-    if (output != NULL) {
-      output->left_voltage = loop_->U(0, 0);
-      output->right_voltage = loop_->U(1, 0);
-      output->left_high = left_gear_ == HIGH;
-      output->right_high = right_gear_ == HIGH;
-    }
-  }
-
- private:
-  const ::aos::controls::HPolytope<2> U_Poly_;
-
-  ::std::unique_ptr<StateFeedbackLoop<2, 2, 2>> loop_;
-
-  const double ttrust_;
-  double wheel_;
-  double throttle_;
-  bool quickturn_;
-  int stale_count_;
-  double position_time_delta_;
-  Gear left_gear_;
-  Gear right_gear_;
-  DrivetrainQueue::Position last_position_;
-  DrivetrainQueue::Position position_;
-  int counter_;
-};
-
-constexpr double PolyDrivetrain::kStallTorque;
-constexpr double PolyDrivetrain::kStallCurrent;
-constexpr double PolyDrivetrain::kFreeSpeed;
-constexpr double PolyDrivetrain::kFreeCurrent;
-constexpr double PolyDrivetrain::J;
-constexpr double PolyDrivetrain::m;
-constexpr double PolyDrivetrain::rb;
-constexpr double PolyDrivetrain::kWheelRadius;
-constexpr double PolyDrivetrain::kR;
-constexpr double PolyDrivetrain::Kv;
-constexpr double PolyDrivetrain::Kt;
-
-void DrivetrainLoop::RunIteration(const DrivetrainQueue::Goal *goal,
-                                  const DrivetrainQueue::Position *position,
-                                  DrivetrainQueue::Output *output,
-                                  DrivetrainQueue::Status *status) {
-  // TODO(aschuh): These should be members of the class.
-  static DrivetrainMotorsSS dt_closedloop;
-  static PolyDrivetrain dt_openloop;
-
-  bool bad_pos = false;
-  if (position == nullptr) {
-    LOG_INTERVAL(no_position_);
-    bad_pos = true;
-  }
-  no_position_.Print();
-
-  bool control_loop_driving = false;
-  if (goal) {
-    double wheel = goal->steering;
-    double throttle = goal->throttle;
-    bool quickturn = goal->quickturn;
-    bool highgear = goal->highgear;
-
-    control_loop_driving = goal->control_loop_driving;
-    double left_goal = goal->left_goal;
-    double right_goal = goal->right_goal;
-
-    dt_closedloop.SetGoal(left_goal, goal->left_velocity_goal, right_goal,
-                          goal->right_velocity_goal);
-    dt_openloop.SetGoal(wheel, throttle, quickturn, highgear);
-  }
-
-  if (!bad_pos) {
-    const double left_encoder = position->left_encoder;
-    const double right_encoder = position->right_encoder;
-    if (gyro_reading.FetchLatest()) {
-      LOG_STRUCT(DEBUG, "using", *gyro_reading.get());
-      dt_closedloop.SetPosition(left_encoder, right_encoder,
-                                gyro_reading->angle);
-    } else {
-      dt_closedloop.SetRawPosition(left_encoder, right_encoder);
-    }
-  }
-  dt_openloop.SetPosition(position);
-  dt_openloop.Update();
-
-  if (control_loop_driving) {
-    dt_closedloop.Update(output == NULL, true);
-    dt_closedloop.SendMotors(output);
-  } else {
-    dt_openloop.SendMotors(output);
-    if (output) {
-      dt_closedloop.SetExternalMotors(output->left_voltage,
-                                      output->right_voltage);
-    }
-    dt_closedloop.Update(output == NULL, false);
-  }
-
-  // set the output status of the control loop state
-  if (status) {
-    status->robot_speed = dt_closedloop.GetEstimatedRobotSpeed();
-    status->estimated_left_position = dt_closedloop.GetEstimatedLeftEncoder();
-    status->estimated_right_position = dt_closedloop.GetEstimatedRightEncoder();
-
-    status->estimated_left_velocity = dt_closedloop.loop().X_hat(1, 0);
-    status->estimated_right_velocity = dt_closedloop.loop().X_hat(3, 0);
-    status->output_was_capped = dt_closedloop.OutputWasCapped();
-    status->uncapped_left_voltage = dt_closedloop.loop().U_uncapped(0, 0);
-    status->uncapped_right_voltage = dt_closedloop.loop().U_uncapped(1, 0);
-  }
-}
-
-}  // namespace control_loops
-}  // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain.h b/y2014_bot3/control_loops/drivetrain/drivetrain.h
deleted file mode 100644
index dfb7269..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain.h
+++ /dev/null
@@ -1,58 +0,0 @@
-#ifndef Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_H_
-#define Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_H_
-
-#include "Eigen/Dense"
-
-#include "aos/common/controls/polytope.h"
-#include "aos/common/controls/control_loop.h"
-#include "aos/common/controls/polytope.h"
-#include "aos/common/util/log_interval.h"
-
-#include "frc971/shifter_hall_effect.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-// Constants
-// TODO(comran): Get actual constants.
-constexpr double kDrivetrainTurnWidth = 0.63;
-constexpr double kDrivetrainEncoderRatio = 18.0 / 44.0;
-constexpr double kDrivetrainHighGearRatio =
-    kDrivetrainEncoderRatio * 18.0 / 60.0;
-constexpr double kDrivetrainLowGearRatio = kDrivetrainHighGearRatio;
-const ::frc971::constants::ShifterHallEffect kDrivetrainRightShifter{
-    555, 657, 660, 560, 0.2, 0.7};
-const ::frc971::constants::ShifterHallEffect kDrivetrainLeftShifter{
-    555, 660, 644, 552, 0.2, 0.7};
-// End constants
-
-class DrivetrainLoop
-    : public aos::controls::ControlLoop<control_loops::DrivetrainQueue> {
- public:
-  // Constructs a control loop which can take a Drivetrain or defaults to the
-  // drivetrain at y2014_bot3::control_loops::drivetrain
-  explicit DrivetrainLoop(control_loops::DrivetrainQueue *my_drivetrain =
-                              &control_loops::drivetrain_queue)
-      : aos::controls::ControlLoop<control_loops::DrivetrainQueue>(
-            my_drivetrain) {
-    ::aos::controls::HPolytope<0>::Init();
-  }
-
- protected:
-  // Executes one cycle of the control loop.
-  virtual void RunIteration(
-      const control_loops::DrivetrainQueue::Goal *goal,
-      const control_loops::DrivetrainQueue::Position *position,
-      control_loops::DrivetrainQueue::Output *output,
-      control_loops::DrivetrainQueue::Status *status);
-
-  typedef ::aos::util::SimpleLogInterval SimpleLogInterval;
-  SimpleLogInterval no_position_ = SimpleLogInterval(
-      ::aos::time::Time::InSeconds(0.25), WARNING, "no position");
-};
-
-}  // namespace control_loops
-}  // namespace y2014_bot3
-
-#endif  // Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain.q b/y2014_bot3/control_loops/drivetrain/drivetrain.q
deleted file mode 100644
index 1b97f81..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain.q
+++ /dev/null
@@ -1,104 +0,0 @@
-package y2014_bot3.control_loops;
-
-import "aos/common/controls/control_loops.q";
-
-// For logging information about the state of the shifters.
-struct CIMLogging {
-  // Whether the code thinks the left side is currently in gear.
-  bool left_in_gear;
-  // Whether the code thinks the right side is currently in gear.
-  bool right_in_gear;
-  // The velocity in rad/s (positive forward) the code thinks the left motor
-  // is currently spinning at.
-  double left_motor_speed;
-  // The velocity in rad/s (positive forward) the code thinks the right motor
-  // is currently spinning at.
-  double right_motor_speed;
-  // The velocity estimate for the left side of the robot in m/s (positive
-  // forward) used for shifting.
-  double left_velocity;
-  // The velocity estimate for the right side of the robot in m/s (positive
-  // forward) used for shifting.
-  double right_velocity;
-};
-
-queue_group DrivetrainQueue {
-  implements aos.control_loops.ControlLoop;
-
-  message Goal {
-    // Position of the steering wheel (positive = turning left when going
-    // forwards).
-    double steering;
-    // Position of the throttle (positive forwards).
-    double throttle;
-    // True to shift into high, false to shift into low.
-    bool highgear;
-    // True to activate quickturn.
-    bool quickturn;
-    // True to have the closed-loop controller take over.
-    bool control_loop_driving;
-    // Position goal for the left side in meters when the closed-loop controller
-    // is active.
-    double left_goal;
-    // Velocity goal for the left side in m/s when the closed-loop controller
-    // is active.
-    double left_velocity_goal;
-    // Position goal for the right side in meters when the closed-loop
-    // controller is active.
-    double right_goal;
-    // Velocity goal for the right side in m/s when the closed-loop controller
-    // is active.
-    double right_velocity_goal;
-  };
-
-  message Position {
-    // Relative position of the left side in meters.
-    double left_encoder;
-    // Relative position of the right side in meters.
-    double right_encoder;
-    // The speed in m/s of the left side from the most recent encoder pulse,
-    // or 0 if there was no edge within the last 5ms.
-    double left_speed;
-    // The speed in m/s of the right side from the most recent encoder pulse,
-    // or 0 if there was no edge within the last 5ms.
-    double right_speed;
-  };
-
-  message Output {
-    // Voltage to send to the left motor(s).
-    double left_voltage;
-    // Voltage to send to the right motor(s).
-    double right_voltage;
-    // True to set the left shifter piston for high gear.
-    bool left_high;
-    // True to set the right shifter piston for high gear.
-    bool right_high;
-  };
-
-  message Status {
-    // Estimated speed of the center of the robot in m/s (positive forwards).
-    double robot_speed;
-    // Estimated relative position of the left side in meters.
-    double estimated_left_position;
-    // Estimated relative position of the right side in meters.
-    double estimated_right_position;
-    // Estimated velocity of the left side in m/s.
-    double estimated_left_velocity;
-    // Estimated velocity of the right side in m/s.
-    double estimated_right_velocity;
-
-    // The voltage we wanted to send to the left side last cycle.
-    double uncapped_left_voltage;
-    // The voltage we wanted to send to the right side last cycle.
-    double uncapped_right_voltage;
-    // True if the output voltage was capped last cycle.
-    bool output_was_capped;
-  };
-
-  queue Goal goal;
-  queue Position position;
-  queue Output output;
-  queue Status status;
-};
-
-queue_group DrivetrainQueue drivetrain_queue;
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_base.cc b/y2014_bot3/control_loops/drivetrain/drivetrain_base.cc
new file mode 100644
index 0000000..bca3f24
--- /dev/null
+++ b/y2014_bot3/control_loops/drivetrain/drivetrain_base.cc
@@ -0,0 +1,47 @@
+#include "y2014_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "y2014_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+#include "y2014_bot3/control_loops/drivetrain/kalman_drivetrain_motor_plant.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainConfig;
+
+namespace y2014_bot3 {
+namespace control_loops {
+namespace drivetrain {
+
+using ::frc971::constants::ShifterHallEffect;
+
+const ShifterHallEffect kThreeStateDriveShifter{0.0, 0.0, 0.0, 0.0, 0.25, 0.75};
+
+const DrivetrainConfig &GetDrivetrainConfig() {
+  static DrivetrainConfig kDrivetrainConfig{
+      ::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
+      ::frc971::control_loops::drivetrain::LoopType::OPEN_LOOP,
+
+      ::y2014_bot3::control_loops::drivetrain::MakeDrivetrainLoop,
+      ::y2014_bot3::control_loops::drivetrain::MakeVelocityDrivetrainLoop,
+      ::y2014_bot3::control_loops::drivetrain::MakeKFDrivetrainLoop,
+
+      drivetrain::kDt,
+      drivetrain::kRobotRadius,
+      drivetrain::kWheelRadius,
+      drivetrain::kV,
+
+      drivetrain::kHighGearRatio,
+      drivetrain::kLowGearRatio,
+
+      // No shifter sensors, so we could put anything for the things below.
+      kThreeStateDriveShifter,
+      kThreeStateDriveShifter,
+      false};
+
+  return kDrivetrainConfig;
+};
+
+}  // namespace drivetrain
+}  // namespace control_loops
+}  // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_base.h b/y2014_bot3/control_loops/drivetrain/drivetrain_base.h
new file mode 100644
index 0000000..d2e54f9
--- /dev/null
+++ b/y2014_bot3/control_loops/drivetrain/drivetrain_base.h
@@ -0,0 +1,20 @@
+#ifndef Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+#define Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+namespace y2014_bot3 {
+namespace control_loops {
+namespace drivetrain {
+
+const double kDrivetrainEncoderRatio =
+    (17.0 / 50.0) /*output reduction*/ * (24.0 / 64.0) /*encoder gears*/;
+
+const ::frc971::control_loops::drivetrain::DrivetrainConfig &
+GetDrivetrainConfig();
+
+}  // namespace drivetrain
+}  // namespace control_loops
+}  // namespace y2014_bot3
+
+#endif  // Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_constants.h b/y2014_bot3/control_loops/drivetrain/drivetrain_constants.h
deleted file mode 100644
index 28848b0..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain_constants.h
+++ /dev/null
@@ -1,26 +0,0 @@
-#ifndef BOT3_CONTROL_LOOPS_DRIVETRAIN_CONSTANTS_H_
-#define BOT3_CONTROL_LOOPS_DRIVETRAIN_CONSTANTS_H_
-
-#include "bot3/shifter_hall_effect.h"
-
-namespace bot3 {
-namespace control_loops {
-
-constexpr constants::ShifterHallEffect kBot3LeftDriveShifter =
-    {426, 171, 0.6, 0.47};
-constexpr constants::ShifterHallEffect kBot3RightDriveShifter =
-    {424, 172, 0.62, 0.55};
-
-constexpr double kBot3TurnWidth = 0.5;
-constexpr double kBot3DrivetrainDoneDistance = 0.02;
-
-constexpr double kBot3LowGearRatio = 14.0 / 60.0 * 17.0 / 50.0;
-constexpr double kBot3HighGearRatio = 30.0 / 44.0 * 17.0 / 50.0;
-
-// If this is true, we don't use the analog hall effects for shifting.
-constexpr bool kBot3SimpleShifting = true;
-
-}  // control_loops
-}  // bot3
-
-#endif
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_lib_test.cc b/y2014_bot3/control_loops/drivetrain/drivetrain_lib_test.cc
deleted file mode 100644
index 3953951..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain_lib_test.cc
+++ /dev/null
@@ -1,295 +0,0 @@
-#include <unistd.h>
-
-#include <memory>
-
-#include "gtest/gtest.h"
-#include "aos/common/network/team_number.h"
-#include "aos/common/controls/polytope.h"
-#include "aos/common/controls/control_loop_test.h"
-
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
-#include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/coerce_goal.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-#include "frc971/queues/gyro.q.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-namespace testing {
-
-class Environment : public ::testing::Environment {
- public:
-  virtual ~Environment() {}
-  // how to set up the environment.
-  virtual void SetUp() {
-    aos::controls::HPolytope<0>::Init();
-  }
-};
-::testing::Environment* const holder_env =
-  ::testing::AddGlobalTestEnvironment(new Environment);
-
-class TeamNumberEnvironment : public ::testing::Environment {
- public:
-  // Override this to define how to set up the environment.
-  virtual void SetUp() { aos::network::OverrideTeamNumber(971); }
-};
-
-::testing::Environment* const team_number_env =
-    ::testing::AddGlobalTestEnvironment(new TeamNumberEnvironment);
-
-// Class which simulates the drivetrain and sends out queue messages containing
-// the position.
-class DrivetrainSimulation {
- public:
-  // Constructs a motor simulation.
-  // TODO(aschuh) Do we want to test the clutch one too?
-  DrivetrainSimulation()
-      : drivetrain_plant_(
-            new StateFeedbackPlant<4, 2, 2>(drivetrain::MakeDrivetrainPlant())),
-        my_drivetrain_queue_(".y2014_bot3.control_loops.drivetrain",
-                       0x8a8dde77, ".y2014_bot3.control_loops.drivetrain.goal",
-                       ".y2014_bot3.control_loops.drivetrain.position",
-                       ".y2014_bot3.control_loops.drivetrain.output",
-                       ".y2014_bot3.control_loops.drivetrain.status") {
-    Reinitialize();
-  }
-
-  // Resets the plant.
-  void Reinitialize() {
-    drivetrain_plant_->mutable_X(0, 0) = 0.0;
-    drivetrain_plant_->mutable_X(1, 0) = 0.0;
-    drivetrain_plant_->mutable_Y() =
-        drivetrain_plant_->C() * drivetrain_plant_->X();
-    last_left_position_ = drivetrain_plant_->Y(0, 0);
-    last_right_position_ = drivetrain_plant_->Y(1, 0);
-  }
-
-  // Returns the position of the drivetrain.
-  double GetLeftPosition() const { return drivetrain_plant_->Y(0, 0); }
-  double GetRightPosition() const { return drivetrain_plant_->Y(1, 0); }
-
-  // Sends out the position queue messages.
-  void SendPositionMessage() {
-    const double left_encoder = GetLeftPosition();
-    const double right_encoder = GetRightPosition();
-
-    ::aos::ScopedMessagePtr<control_loops::DrivetrainQueue::Position> position =
-        my_drivetrain_queue_.position.MakeMessage();
-    position->left_encoder = left_encoder;
-    position->right_encoder = right_encoder;
-    position.Send();
-  }
-
-  // Simulates the drivetrain moving for one timestep.
-  void Simulate() {
-    last_left_position_ = drivetrain_plant_->Y(0, 0);
-    last_right_position_ = drivetrain_plant_->Y(1, 0);
-    EXPECT_TRUE(my_drivetrain_queue_.output.FetchLatest());
-    drivetrain_plant_->mutable_U() << my_drivetrain_queue_.output->left_voltage,
-        my_drivetrain_queue_.output->right_voltage;
-    drivetrain_plant_->Update();
-  }
-
-  ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> drivetrain_plant_;
- private:
-  DrivetrainQueue my_drivetrain_queue_;
-  double last_left_position_;
-  double last_right_position_;
-};
-
-class DrivetrainTest : public ::aos::testing::ControlLoopTest {
- protected:
-  // Create a new instance of the test queue so that it invalidates the queue
-  // that it points to.  Otherwise, we will have a pointer to shared memory that
-  // is no longer valid.
-  DrivetrainQueue my_drivetrain_queue_;
-
-  // Create a loop and simulation plant.
-  DrivetrainLoop drivetrain_motor_;
-  DrivetrainSimulation drivetrain_motor_plant_;
-
-  DrivetrainTest() : my_drivetrain_queue_(".y2014_bot3.control_loops.drivetrain",
-                               0x8a8dde77,
-                               ".y2014_bot3.control_loops.drivetrain.goal",
-                               ".y2014_bot3.control_loops.drivetrain.position",
-                               ".y2014_bot3.control_loops.drivetrain.output",
-                               ".y2014_bot3.control_loops.drivetrain.status"),
-                drivetrain_motor_(&my_drivetrain_queue_),
-                drivetrain_motor_plant_() {
-    ::frc971::sensors::gyro_reading.Clear();
-  }
-
-  void VerifyNearGoal() {
-    my_drivetrain_queue_.goal.FetchLatest();
-    my_drivetrain_queue_.position.FetchLatest();
-    EXPECT_NEAR(my_drivetrain_queue_.goal->left_goal,
-                drivetrain_motor_plant_.GetLeftPosition(),
-                1e-2);
-    EXPECT_NEAR(my_drivetrain_queue_.goal->right_goal,
-                drivetrain_motor_plant_.GetRightPosition(),
-                1e-2);
-  }
-
-  virtual ~DrivetrainTest() {
-    ::frc971::sensors::gyro_reading.Clear();
-  }
-};
-
-// Tests that the drivetrain converges on a goal.
-TEST_F(DrivetrainTest, ConvergesCorrectly) {
-  my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
-      .left_goal(-1.0)
-      .right_goal(1.0).Send();
-  for (int i = 0; i < 200; ++i) {
-    drivetrain_motor_plant_.SendPositionMessage();
-    drivetrain_motor_.Iterate();
-    drivetrain_motor_plant_.Simulate();
-    SimulateTimestep(true);
-  }
-  VerifyNearGoal();
-}
-
-// Tests that it survives disabling.
-TEST_F(DrivetrainTest, SurvivesDisabling) {
-  my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
-      .left_goal(-1.0)
-      .right_goal(1.0).Send();
-  for (int i = 0; i < 500; ++i) {
-    drivetrain_motor_plant_.SendPositionMessage();
-    drivetrain_motor_.Iterate();
-    drivetrain_motor_plant_.Simulate();
-    if (i > 20 && i < 200) {
-      SimulateTimestep(false);
-    } else {
-      SimulateTimestep(true);
-    }
-  }
-  VerifyNearGoal();
-}
-
-// Tests that never having a goal doesn't break.
-TEST_F(DrivetrainTest, NoGoalStart) {
-  for (int i = 0; i < 20; ++i) {
-    drivetrain_motor_plant_.SendPositionMessage();
-    drivetrain_motor_.Iterate();
-    drivetrain_motor_plant_.Simulate();
-  }
-}
-
-// Tests that never having a goal, but having driver's station messages, doesn't
-// break.
-TEST_F(DrivetrainTest, NoGoalWithRobotState) {
-  for (int i = 0; i < 20; ++i) {
-    drivetrain_motor_plant_.SendPositionMessage();
-    drivetrain_motor_.Iterate();
-    drivetrain_motor_plant_.Simulate();
-    SimulateTimestep(true);
-  }
-}
-
-::aos::controls::HPolytope<2> MakeBox(double x1_min, double x1_max,
-                                      double x2_min, double x2_max) {
-  Eigen::Matrix<double, 4, 2> box_H;
-  box_H << /*[[*/ 1.0, 0.0 /*]*/,
-            /*[*/-1.0, 0.0 /*]*/,
-            /*[*/ 0.0, 1.0 /*]*/,
-            /*[*/ 0.0,-1.0 /*]]*/;
-  Eigen::Matrix<double, 4, 1> box_k;
-  box_k << /*[[*/ x1_max /*]*/,
-            /*[*/-x1_min /*]*/,
-            /*[*/ x2_max /*]*/,
-            /*[*/-x2_min /*]]*/;
-  ::aos::controls::HPolytope<2> t_poly(box_H, box_k);
-  return t_poly;
-}
-
-class CoerceGoalTest : public ::testing::Test {
- public:
-  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
-};
-
-// WHOOOHH!
-TEST_F(CoerceGoalTest, Inside) {
-  ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
-
-  Eigen::Matrix<double, 1, 2> K;
-  K << /*[[*/ 1, -1 /*]]*/;
-
-  Eigen::Matrix<double, 2, 1> R;
-  R << /*[[*/ 1.5, 1.5 /*]]*/;
-
-  Eigen::Matrix<double, 2, 1> output =
-      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
-  EXPECT_EQ(R(0, 0), output(0, 0));
-  EXPECT_EQ(R(1, 0), output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, Outside_Inside_Intersect) {
-  ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
-
-  Eigen::Matrix<double, 1, 2> K;
-  K << 1, -1;
-
-  Eigen::Matrix<double, 2, 1> R;
-  R << 5, 5;
-
-  Eigen::Matrix<double, 2, 1> output =
-      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
-  EXPECT_EQ(2.0, output(0, 0));
-  EXPECT_EQ(2.0, output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, Outside_Inside_no_Intersect) {
-  ::aos::controls::HPolytope<2> box = MakeBox(3, 4, 1, 2);
-
-  Eigen::Matrix<double, 1, 2> K;
-  K << 1, -1;
-
-  Eigen::Matrix<double, 2, 1> R;
-  R << 5, 5;
-
-  Eigen::Matrix<double, 2, 1> output =
-      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
-  EXPECT_EQ(3.0, output(0, 0));
-  EXPECT_EQ(2.0, output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, Middle_Of_Edge) {
-  ::aos::controls::HPolytope<2> box = MakeBox(0, 4, 1, 2);
-
-  Eigen::Matrix<double, 1, 2> K;
-  K << -1, 1;
-
-  Eigen::Matrix<double, 2, 1> R;
-  R << 5, 5;
-
-  Eigen::Matrix<double, 2, 1> output =
-      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
-  EXPECT_EQ(2.0, output(0, 0));
-  EXPECT_EQ(2.0, output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, PerpendicularLine) {
-  ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
-
-  Eigen::Matrix<double, 1, 2> K;
-  K << 1, 1;
-
-  Eigen::Matrix<double, 2, 1> R;
-  R << 5, 5;
-
-  Eigen::Matrix<double, 2, 1> output =
-      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
-  EXPECT_EQ(1.0, output(0, 0));
-  EXPECT_EQ(1.0, output(1, 0));
-}
-
-}  // namespace testing
-}  // namespace control_loops
-}  // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_main.cc b/y2014_bot3/control_loops/drivetrain/drivetrain_main.cc
index 588bc89..a0f0a83 100644
--- a/y2014_bot3/control_loops/drivetrain/drivetrain_main.cc
+++ b/y2014_bot3/control_loops/drivetrain/drivetrain_main.cc
@@ -1,10 +1,14 @@
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
-
 #include "aos/linux_code/init.h"
 
+#include "frc971/control_loops/drivetrain/drivetrain.h"
+#include "y2014_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainLoop;
+
 int main() {
   ::aos::Init();
-  y2014_bot3::control_loops::DrivetrainLoop drivetrain;
+  DrivetrainLoop drivetrain(
+      ::y2014_bot3::control_loops::drivetrain::GetDrivetrainConfig());
   drivetrain.Run();
   ::aos::Cleanup();
   return 0;
diff --git a/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.cc b/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.cc
deleted file mode 100644
index 75bae13..0000000
--- a/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<1, 1, 1> MakeCIMPlantCoefficients() {
-  Eigen::Matrix<double, 1, 1> A;
-  A << 0.783924473544;
-  Eigen::Matrix<double, 1, 1> B;
-  B << 8.94979586973;
-  Eigen::Matrix<double, 1, 1> C;
-  C << 1;
-  Eigen::Matrix<double, 1, 1> D;
-  D << 0;
-  Eigen::Matrix<double, 1, 1> U_max;
-  U_max << 12.0;
-  Eigen::Matrix<double, 1, 1> U_min;
-  U_min << -12.0;
-  return StateFeedbackPlantCoefficients<1, 1, 1>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<1, 1, 1> MakeCIMController() {
-  Eigen::Matrix<double, 1, 1> L;
-  L << 0.773924473544;
-  Eigen::Matrix<double, 1, 1> K;
-  K << 0.086473980503;
-  Eigen::Matrix<double, 1, 1> A_inv;
-  A_inv << 1.2756330919;
-  return StateFeedbackController<1, 1, 1>(L, K, A_inv, MakeCIMPlantCoefficients());
-}
-
-StateFeedbackPlant<1, 1, 1> MakeCIMPlant() {
-  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>> plants(1);
-  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>(new StateFeedbackPlantCoefficients<1, 1, 1>(MakeCIMPlantCoefficients()));
-  return StateFeedbackPlant<1, 1, 1>(&plants);
-}
-
-StateFeedbackLoop<1, 1, 1> MakeCIMLoop() {
-  ::std::vector< ::std::unique_ptr<StateFeedbackController<1, 1, 1>>> controllers(1);
-  controllers[0] = ::std::unique_ptr<StateFeedbackController<1, 1, 1>>(new StateFeedbackController<1, 1, 1>(MakeCIMController()));
-  return StateFeedbackLoop<1, 1, 1>(&controllers);
-}
-
-}  // namespace control_loops
-}  // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h b/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h
deleted file mode 100644
index 0def071..0000000
--- a/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h
+++ /dev/null
@@ -1,20 +0,0 @@
-#ifndef Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
-#define Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<1, 1, 1> MakeCIMPlantCoefficients();
-
-StateFeedbackController<1, 1, 1> MakeCIMController();
-
-StateFeedbackPlant<1, 1, 1> MakeCIMPlant();
-
-StateFeedbackLoop<1, 1, 1> MakeCIMLoop();
-
-}  // namespace control_loops
-}  // namespace y2014_bot3
-
-#endif  // Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
diff --git a/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc b/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
deleted file mode 100644
index 8fc4049..0000000
--- a/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
+++ /dev/null
@@ -1,133 +0,0 @@
-#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowLowPlantCoefficients() {
-  Eigen::Matrix<double, 2, 2> A;
-  A << 0.953388055571, 0.0100729449137, 0.0100729449137, 0.953388055571;
-  Eigen::Matrix<double, 2, 2> B;
-  B << 0.0119133285199, -0.00257449680311, -0.00257449680311, 0.0119133285199;
-  Eigen::Matrix<double, 2, 2> C;
-  C << 1.0, 0.0, 0.0, 1.0;
-  Eigen::Matrix<double, 2, 2> D;
-  D << 0.0, 0.0, 0.0, 0.0;
-  Eigen::Matrix<double, 2, 1> U_max;
-  U_max << 12.0, 12.0;
-  Eigen::Matrix<double, 2, 1> U_min;
-  U_min << -12.0, -12.0;
-  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients() {
-  Eigen::Matrix<double, 2, 2> A;
-  A << 0.953388055571, 0.0100729449137, 0.0100729449137, 0.953388055571;
-  Eigen::Matrix<double, 2, 2> B;
-  B << 0.0119133285199, -0.00257449680311, -0.00257449680311, 0.0119133285199;
-  Eigen::Matrix<double, 2, 2> C;
-  C << 1.0, 0.0, 0.0, 1.0;
-  Eigen::Matrix<double, 2, 2> D;
-  D << 0.0, 0.0, 0.0, 0.0;
-  Eigen::Matrix<double, 2, 1> U_max;
-  U_max << 12.0, 12.0;
-  Eigen::Matrix<double, 2, 1> U_min;
-  U_min << -12.0, -12.0;
-  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients() {
-  Eigen::Matrix<double, 2, 2> A;
-  A << 0.953388055571, 0.0100729449137, 0.0100729449137, 0.953388055571;
-  Eigen::Matrix<double, 2, 2> B;
-  B << 0.0119133285199, -0.00257449680311, -0.00257449680311, 0.0119133285199;
-  Eigen::Matrix<double, 2, 2> C;
-  C << 1.0, 0.0, 0.0, 1.0;
-  Eigen::Matrix<double, 2, 2> D;
-  D << 0.0, 0.0, 0.0, 0.0;
-  Eigen::Matrix<double, 2, 1> U_max;
-  U_max << 12.0, 12.0;
-  Eigen::Matrix<double, 2, 1> U_min;
-  U_min << -12.0, -12.0;
-  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients() {
-  Eigen::Matrix<double, 2, 2> A;
-  A << 0.953388055571, 0.0100729449137, 0.0100729449137, 0.953388055571;
-  Eigen::Matrix<double, 2, 2> B;
-  B << 0.0119133285199, -0.00257449680311, -0.00257449680311, 0.0119133285199;
-  Eigen::Matrix<double, 2, 2> C;
-  C << 1.0, 0.0, 0.0, 1.0;
-  Eigen::Matrix<double, 2, 2> D;
-  D << 0.0, 0.0, 0.0, 0.0;
-  Eigen::Matrix<double, 2, 1> U_max;
-  U_max << 12.0, 12.0;
-  Eigen::Matrix<double, 2, 1> U_min;
-  U_min << -12.0, -12.0;
-  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController() {
-  Eigen::Matrix<double, 2, 2> L;
-  L << 0.933388055571, 0.0100729449137, 0.0100729449137, 0.933388055571;
-  Eigen::Matrix<double, 2, 2> K;
-  K << 31.3080614945, 7.61126069778, 7.61126069778, 31.3080614945;
-  Eigen::Matrix<double, 2, 2> A_inv;
-  A_inv << 1.04900794038, -0.0110832091253, -0.0110832091253, 1.04900794038;
-  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowLowPlantCoefficients());
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController() {
-  Eigen::Matrix<double, 2, 2> L;
-  L << 0.933388055571, 0.0100729449137, 0.0100729449137, 0.933388055571;
-  Eigen::Matrix<double, 2, 2> K;
-  K << 31.3080614945, 7.61126069778, 7.61126069778, 31.3080614945;
-  Eigen::Matrix<double, 2, 2> A_inv;
-  A_inv << 1.04900794038, -0.0110832091253, -0.0110832091253, 1.04900794038;
-  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowHighPlantCoefficients());
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController() {
-  Eigen::Matrix<double, 2, 2> L;
-  L << 0.933388055571, 0.0100729449137, 0.0100729449137, 0.933388055571;
-  Eigen::Matrix<double, 2, 2> K;
-  K << 31.3080614945, 7.61126069778, 7.61126069778, 31.3080614945;
-  Eigen::Matrix<double, 2, 2> A_inv;
-  A_inv << 1.04900794038, -0.0110832091253, -0.0110832091253, 1.04900794038;
-  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighLowPlantCoefficients());
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController() {
-  Eigen::Matrix<double, 2, 2> L;
-  L << 0.933388055571, 0.0100729449137, 0.0100729449137, 0.933388055571;
-  Eigen::Matrix<double, 2, 2> K;
-  K << 31.3080614945, 7.61126069778, 7.61126069778, 31.3080614945;
-  Eigen::Matrix<double, 2, 2> A_inv;
-  A_inv << 1.04900794038, -0.0110832091253, -0.0110832091253, 1.04900794038;
-  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighHighPlantCoefficients());
-}
-
-StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant() {
-  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>> plants(4);
-  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowLowPlantCoefficients()));
-  plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowHighPlantCoefficients()));
-  plants[2] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighLowPlantCoefficients()));
-  plants[3] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighHighPlantCoefficients()));
-  return StateFeedbackPlant<2, 2, 2>(&plants);
-}
-
-StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop() {
-  ::std::vector< ::std::unique_ptr<StateFeedbackController<2, 2, 2>>> controllers(4);
-  controllers[0] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowLowController()));
-  controllers[1] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowHighController()));
-  controllers[2] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighLowController()));
-  controllers[3] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighHighController()));
-  return StateFeedbackLoop<2, 2, 2>(&controllers);
-}
-
-}  // namespace control_loops
-}  // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h b/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
deleted file mode 100644
index 4442d35..0000000
--- a/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#ifndef Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
-#define Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowLowPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController();
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController();
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController();
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController();
-
-StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant();
-
-StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop();
-
-}  // namespace control_loops
-}  // namespace y2014_bot3
-
-#endif  // Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/y2014_bot3/control_loops/drivetrain/replay_drivetrain.cc b/y2014_bot3/control_loops/drivetrain/replay_drivetrain.cc
deleted file mode 100644
index 4f83c9e..0000000
--- a/y2014_bot3/control_loops/drivetrain/replay_drivetrain.cc
+++ /dev/null
@@ -1,24 +0,0 @@
-#include "aos/common/controls/replay_control_loop.h"
-#include "aos/linux_code/init.h"
-
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-
-// Reads one or more log files and sends out all the queue messages (in the
-// correct order and at the correct time) to feed a "live" drivetrain process.
-
-int main(int argc, char **argv) {
-  if (argc <= 1) {
-    fprintf(stderr, "Need at least one file to replay!\n");
-    return EXIT_FAILURE;
-  }
-
-  ::aos::InitNRT();
-
-  ::aos::controls::ControlLoopReplayer<::y2014_bot3::control_loops::DrivetrainQueue>
-      replayer(&::y2014_bot3::control_loops::drivetrain_queue, "drivetrain");
-  for (int i = 1; i < argc; ++i) {
-    replayer.ProcessFile(argv[i]);
-  }
-
-  ::aos::Cleanup();
-}
diff --git a/y2014_bot3/control_loops/python/BUILD b/y2014_bot3/control_loops/python/BUILD
index bb8dc29..756b60e 100644
--- a/y2014_bot3/control_loops/python/BUILD
+++ b/y2014_bot3/control_loops/python/BUILD
@@ -6,7 +6,21 @@
     'drivetrain.py',
   ],
   deps = [
+    '//external:python-gflags',
     '//external:python-glog',
     '//frc971/control_loops/python:controls',
   ]
 )
+
+py_binary(
+  name = 'polydrivetrain',
+  srcs = [
+    'polydrivetrain.py',
+    'drivetrain.py',
+  ],
+  deps = [
+    '//external:python-gflags',
+    '//external:python-glog',
+    '//frc971/control_loops/python:controls',
+  ],
+)
diff --git a/y2014_bot3/control_loops/python/drivetrain.py b/y2014_bot3/control_loops/python/drivetrain.py
index 4231887..b0555a0 100755
--- a/y2014_bot3/control_loops/python/drivetrain.py
+++ b/y2014_bot3/control_loops/python/drivetrain.py
@@ -4,10 +4,16 @@
 from frc971.control_loops.python import controls
 import numpy
 import sys
+import argparse
 from matplotlib import pylab
 
+import gflags
 import glog
 
+FLAGS = gflags.FLAGS
+
+gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+
 class CIM(control_loop.ControlLoop):
   def __init__(self):
     super(CIM, self).__init__("CIM")
@@ -22,10 +28,10 @@
     # Moment of inertia of the CIM in kg m^2
     self.J = 0.0001
     # Resistance of the motor, divided by 2 to account for the 2 motors
-    self.R = 12.0 / self.stall_current
+    self.resistance = 12.0 / self.stall_current
     # Motor velocity constant
     self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
-              (12.0 - self.R * self.free_current))
+              (12.0 - self.resistance * self.free_current))
     # Torque constant
     self.Kt = self.stall_torque / self.stall_current
     # Control loop time step
@@ -33,9 +39,9 @@
 
     # State feedback matrices
     self.A_continuous = numpy.matrix(
-        [[-self.Kt / self.Kv / (self.J * self.R)]])
+        [[-self.Kt / self.Kv / (self.J * self.resistance)]])
     self.B_continuous = numpy.matrix(
-        [[self.Kt / (self.J * self.R)]])
+        [[self.Kt / (self.J * self.resistance)]])
     self.C = numpy.matrix([[1]])
     self.D = numpy.matrix([[0]])
 
@@ -54,36 +60,34 @@
 class Drivetrain(control_loop.ControlLoop):
   def __init__(self, name="Drivetrain", left_low=True, right_low=True):
     super(Drivetrain, self).__init__(name)
+    # Number of motors per side
+    self.num_motors = 2
     # Stall Torque in N m
-    self.stall_torque = 2.42
+    self.stall_torque = 2.42 * self.num_motors * 0.60
     # Stall Current in Amps
-    self.stall_current = 133.0
+    self.stall_current = 133.0 * self.num_motors
     # Free Speed in RPM. Used number from last year.
-    self.free_speed = 4650.0
+    self.free_speed = 5500.0
     # Free Current in Amps
-    self.free_current = 2.7
+    self.free_current = 4.7 * self.num_motors
     # Moment of inertia of the drivetrain in kg m^2
-    # Just borrowed from last year.
-    self.J = 10
+    self.J = 1.8
     # Mass of the robot, in kg.
-    self.m = 68
-    # Radius of the robot, in meters (from last year).
-    self.rb = 0.9603 / 2.0
+    self.m = 37
+    # Radius of the robot, in meters (requires tuning by hand)
+    self.rb = 0.601 / 2.0
     # Radius of the wheels, in meters.
     self.r = 0.0508
     # Resistance of the motor, divided by the number of motors.
-    self.R = 12.0 / self.stall_current / 2
+    self.resistance = 12.0 / self.stall_current
     # Motor velocity constant
     self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
-               (12.0 - self.R * self.free_current))
+               (12.0 - self.resistance * self.free_current))
     # Torque constant
     self.Kt = self.stall_torque / self.stall_current
     # Gear ratios
-    self.G_const = 18.0 / 44.0 * 18.0 / 60.0
-
-    self.G_low = self.G_const
-    self.G_high = self.G_const
-
+    self.G_low = 28.0 / 60.0 * 19.0 / 50.0
+    self.G_high = 28.0 / 48.0 * 19.0 / 50.0
     if left_low:
       self.Gl = self.G_low
     else:
@@ -101,10 +105,10 @@
     self.msp = 1.0 / self.m + self.rb * self.rb / self.J
     self.msn = 1.0 / self.m - self.rb * self.rb / self.J
     # The calculations which we will need for A and B.
-    self.tcl = -self.Kt / self.Kv / (self.Gl * self.Gl * self.R * self.r * self.r)
-    self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.R * self.r * self.r)
-    self.mpl = self.Kt / (self.Gl * self.R * self.r)
-    self.mpr = self.Kt / (self.Gr * self.R * self.r)
+    self.tcl = -self.Kt / self.Kv / (self.Gl * self.Gl * self.resistance * self.r * self.r)
+    self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.resistance * self.r * self.r)
+    self.mpl = self.Kt / (self.Gl * self.resistance * self.r)
+    self.mpr = self.Kt / (self.Gr * self.resistance * self.r)
 
     # State feedback matrices
     # X will be of the format
@@ -124,17 +128,16 @@
     self.D = numpy.matrix([[0, 0],
                            [0, 0]])
 
-    #glog.debug('THE NUMBER I WANT %s', str(numpy.linalg.inv(self.A_continuous) * -self.B_continuous * numpy.matrix([[12.0], [12.0]])))
     self.A, self.B = self.ContinuousToDiscrete(
         self.A_continuous, self.B_continuous, self.dt)
 
-    # Poles from last year.
-    self.hp = 0.65
-    self.lp = 0.83
-    self.PlaceControllerPoles([self.hp, self.lp, self.hp, self.lp])
-    glog.info('K %s', str(self.K))
-    q_pos = 0.07
-    q_vel = 1.0
+    if left_low or right_low:
+      q_pos = 0.12
+      q_vel = 1.0
+    else:
+      q_pos = 0.14
+      q_vel = 0.95
+
     self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
                            [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
                            [0.0, 0.0, (1.0 / (q_pos ** 2.0)), 0.0],
@@ -143,10 +146,10 @@
     self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
                            [0.0, (1.0 / (12.0 ** 2.0))]])
     self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
-    glog.info('A %s', str(self.A))
-    glog.info('B %s', str(self.B))
-    glog.info('K %s', str(self.K))
-    glog.info('Poles are %s', str(numpy.linalg.eig(self.A - self.B * self.K)[0]))
+
+    glog.debug('DT q_pos %f q_vel %s %s', q_pos, q_vel, name)
+    glog.debug(str(numpy.linalg.eig(self.A - self.B * self.K)[0]))
+    glog.debug('K %s', repr(self.K))
 
     self.hlp = 0.3
     self.llp = 0.4
@@ -154,11 +157,102 @@
 
     self.U_max = numpy.matrix([[12.0], [12.0]])
     self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
     self.InitializeState()
 
+
+class KFDrivetrain(Drivetrain):
+  def __init__(self, name="KFDrivetrain", left_low=True, right_low=True):
+    super(KFDrivetrain, self).__init__(name, left_low, right_low)
+
+    self.unaugmented_A_continuous = self.A_continuous
+    self.unaugmented_B_continuous = self.B_continuous
+
+    # The states are
+    # The practical voltage applied to the wheels is
+    #   V_left = U_left + left_voltage_error
+    #
+    # [left position, left velocity, right position, right velocity,
+    #  left voltage error, right voltage error, angular_error]
+    #
+    # The left and right positions are filtered encoder positions and are not
+    # adjusted for heading error.
+    # The turn velocity as computed by the left and right velocities is
+    # adjusted by the gyro velocity.
+    # The angular_error is the angular velocity error between the wheel speed
+    # and the gyro speed.
+    self.A_continuous = numpy.matrix(numpy.zeros((7, 7)))
+    self.B_continuous = numpy.matrix(numpy.zeros((7, 2)))
+    self.A_continuous[0:4,0:4] = self.unaugmented_A_continuous
+    self.A_continuous[0:4,4:6] = self.unaugmented_B_continuous
+    self.B_continuous[0:4,0:2] = self.unaugmented_B_continuous
+    self.A_continuous[0,6] = 1
+    self.A_continuous[2,6] = -1
+
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    self.C = numpy.matrix([[1, 0, 0, 0, 0, 0, 0],
+                           [0, 0, 1, 0, 0, 0, 0],
+                           [0, -0.5 / self.rb, 0, 0.5 / self.rb, 0, 0, 0]])
+
+    self.D = numpy.matrix([[0, 0],
+                           [0, 0],
+                           [0, 0]])
+
+    q_pos = 0.05
+    q_vel = 1.00
+    q_voltage = 10.0
+    q_encoder_uncertainty = 2.00
+
+    self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
+                           [0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0],
+                           [0.0, 0.0, (q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0, 0.0],
+                           [0.0, 0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0],
+                           [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, (q_encoder_uncertainty ** 2.0)]])
+
+    r_pos =  0.0001
+    r_gyro = 0.000001
+    self.R = numpy.matrix([[(r_pos ** 2.0), 0.0, 0.0],
+                           [0.0, (r_pos ** 2.0), 0.0],
+                           [0.0, 0.0, (r_gyro ** 2.0)]])
+
+    # Solving for kf gains.
+    self.KalmanGain, self.Q_steady = controls.kalman(
+        A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+    self.L = self.A * self.KalmanGain
+
+    unaug_K = self.K
+
+    # Implement a nice closed loop controller for use by the closed loop
+    # controller.
+    self.K = numpy.matrix(numpy.zeros((self.B.shape[1], self.A.shape[0])))
+    self.K[0:2, 0:4] = unaug_K
+    self.K[0, 4] = 1.0
+    self.K[1, 5] = 1.0
+
+    self.Qff = numpy.matrix(numpy.zeros((4, 4)))
+    qff_pos = 0.005
+    qff_vel = 1.00
+    self.Qff[0, 0] = 1.0 / qff_pos ** 2.0
+    self.Qff[1, 1] = 1.0 / qff_vel ** 2.0
+    self.Qff[2, 2] = 1.0 / qff_pos ** 2.0
+    self.Qff[3, 3] = 1.0 / qff_vel ** 2.0
+    self.Kff = numpy.matrix(numpy.zeros((2, 7)))
+    self.Kff[0:2, 0:4] = controls.TwoStateFeedForwards(self.B[0:4,:], self.Qff)
+
+    self.InitializeState()
+
+
 def main(argv):
+  argv = FLAGS(argv)
+  glog.init()
+
   # Simulate the response of the system to a step input.
-  drivetrain = Drivetrain()
+  drivetrain = Drivetrain(left_low=False, right_low=False)
   simulated_left = []
   simulated_right = []
   for _ in xrange(100):
@@ -166,26 +260,37 @@
     simulated_left.append(drivetrain.X[0, 0])
     simulated_right.append(drivetrain.X[2, 0])
 
-  #pylab.plot(range(100), simulated_left)
-  #pylab.plot(range(100), simulated_right)
-  #pylab.show()
+  if FLAGS.plot:
+    pylab.plot(range(100), simulated_left)
+    pylab.plot(range(100), simulated_right)
+    pylab.suptitle('Acceleration Test')
+    pylab.show()
 
   # Simulate forwards motion.
-  drivetrain = Drivetrain()
+  drivetrain = Drivetrain(left_low=False, right_low=False)
   close_loop_left = []
   close_loop_right = []
+  left_power = []
+  right_power = []
   R = numpy.matrix([[1.0], [0.0], [1.0], [0.0]])
-  for _ in xrange(100):
+  for _ in xrange(300):
     U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
                    drivetrain.U_min, drivetrain.U_max)
     drivetrain.UpdateObserver(U)
     drivetrain.Update(U)
     close_loop_left.append(drivetrain.X[0, 0])
     close_loop_right.append(drivetrain.X[2, 0])
+    left_power.append(U[0, 0])
+    right_power.append(U[1, 0])
 
-  #pylab.plot(range(100), close_loop_left)
-  #pylab.plot(range(100), close_loop_right)
-  #pylab.show()
+  if FLAGS.plot:
+    pylab.plot(range(300), close_loop_left, label='left position')
+    pylab.plot(range(300), close_loop_right, label='right position')
+    pylab.plot(range(300), left_power, label='left power')
+    pylab.plot(range(300), right_power, label='right power')
+    pylab.suptitle('Linear Move')
+    pylab.legend()
+    pylab.show()
 
   # Try turning in place
   drivetrain = Drivetrain()
@@ -200,9 +305,11 @@
     close_loop_left.append(drivetrain.X[0, 0])
     close_loop_right.append(drivetrain.X[2, 0])
 
-  #pylab.plot(range(100), close_loop_left)
-  #pylab.plot(range(100), close_loop_right)
-  #pylab.show()
+  if FLAGS.plot:
+    pylab.plot(range(100), close_loop_left)
+    pylab.plot(range(100), close_loop_right)
+    pylab.suptitle('Angular Move')
+    pylab.show()
 
   # Try turning just one side.
   drivetrain = Drivetrain()
@@ -217,25 +324,75 @@
     close_loop_left.append(drivetrain.X[0, 0])
     close_loop_right.append(drivetrain.X[2, 0])
 
-  #pylab.plot(range(100), close_loop_left)
-  #pylab.plot(range(100), close_loop_right)
-  #pylab.show()
+  if FLAGS.plot:
+    pylab.plot(range(100), close_loop_left)
+    pylab.plot(range(100), close_loop_right)
+    pylab.suptitle('Pivot')
+    pylab.show()
 
   # Write the generated constants out to a file.
-  glog.info('Output one')
-  drivetrain_low_low = Drivetrain(name="DrivetrainLowLow", left_low=True, right_low=True)
-  drivetrain_low_high = Drivetrain(name="DrivetrainLowHigh", left_low=True, right_low=False)
-  drivetrain_high_low = Drivetrain(name="DrivetrainHighLow", left_low=False, right_low=True)
-  drivetrain_high_high = Drivetrain(name="DrivetrainHighHigh", left_low=False, right_low=False)
+  drivetrain_low_low = Drivetrain(
+      name="DrivetrainLowLow", left_low=True, right_low=True)
+  drivetrain_low_high = Drivetrain(
+      name="DrivetrainLowHigh", left_low=True, right_low=False)
+  drivetrain_high_low = Drivetrain(
+      name="DrivetrainHighLow", left_low=False, right_low=True)
+  drivetrain_high_high = Drivetrain(
+      name="DrivetrainHighHigh", left_low=False, right_low=False)
 
-  if len(argv) != 3:
-    glog.fatal('Expected .h file name and .cc file name')
+  kf_drivetrain_low_low = KFDrivetrain(
+      name="KFDrivetrainLowLow", left_low=True, right_low=True)
+  kf_drivetrain_low_high = KFDrivetrain(
+      name="KFDrivetrainLowHigh", left_low=True, right_low=False)
+  kf_drivetrain_high_low = KFDrivetrain(
+      name="KFDrivetrainHighLow", left_low=False, right_low=True)
+  kf_drivetrain_high_high = KFDrivetrain(
+      name="KFDrivetrainHighHigh", left_low=False, right_low=False)
+
+  if len(argv) != 5:
+    print "Expected .h file name and .cc file name"
   else:
+    namespaces = ['y2014_bot3', 'control_loops', 'drivetrain']
     dog_loop_writer = control_loop.ControlLoopWriter(
         "Drivetrain", [drivetrain_low_low, drivetrain_low_high,
                        drivetrain_high_low, drivetrain_high_high],
-        namespaces=['y2014_bot3', 'control_loops', 'drivetrain'])
+        namespaces = namespaces)
+    dog_loop_writer.AddConstant(control_loop.Constant("kDt", "%f",
+          drivetrain_low_low.dt))
+    dog_loop_writer.AddConstant(control_loop.Constant("kStallTorque", "%f",
+          drivetrain_low_low.stall_torque))
+    dog_loop_writer.AddConstant(control_loop.Constant("kStallCurrent", "%f",
+          drivetrain_low_low.stall_current))
+    dog_loop_writer.AddConstant(control_loop.Constant("kFreeSpeedRPM", "%f",
+          drivetrain_low_low.free_speed))
+    dog_loop_writer.AddConstant(control_loop.Constant("kFreeCurrent", "%f",
+          drivetrain_low_low.free_current))
+    dog_loop_writer.AddConstant(control_loop.Constant("kJ", "%f",
+          drivetrain_low_low.J))
+    dog_loop_writer.AddConstant(control_loop.Constant("kMass", "%f",
+          drivetrain_low_low.m))
+    dog_loop_writer.AddConstant(control_loop.Constant("kRobotRadius", "%f",
+          drivetrain_low_low.rb))
+    dog_loop_writer.AddConstant(control_loop.Constant("kWheelRadius", "%f",
+          drivetrain_low_low.r))
+    dog_loop_writer.AddConstant(control_loop.Constant("kR", "%f",
+          drivetrain_low_low.resistance))
+    dog_loop_writer.AddConstant(control_loop.Constant("kV", "%f",
+          drivetrain_low_low.Kv))
+    dog_loop_writer.AddConstant(control_loop.Constant("kT", "%f",
+          drivetrain_low_low.Kt))
+    dog_loop_writer.AddConstant(control_loop.Constant("kLowGearRatio", "%f",
+          drivetrain_low_low.G_low))
+    dog_loop_writer.AddConstant(control_loop.Constant("kHighGearRatio", "%f",
+          drivetrain_high_high.G_high))
+
     dog_loop_writer.Write(argv[1], argv[2])
 
+    kf_loop_writer = control_loop.ControlLoopWriter(
+        "KFDrivetrain", [kf_drivetrain_low_low, kf_drivetrain_low_high,
+                         kf_drivetrain_high_low, kf_drivetrain_high_high],
+        namespaces = namespaces)
+    kf_loop_writer.Write(argv[3], argv[4])
+
 if __name__ == '__main__':
   sys.exit(main(sys.argv))
diff --git a/y2014_bot3/control_loops/python/polydrivetrain.py b/y2014_bot3/control_loops/python/polydrivetrain.py
index 2ffbed6..e047c11 100755
--- a/y2014_bot3/control_loops/python/polydrivetrain.py
+++ b/y2014_bot3/control_loops/python/polydrivetrain.py
@@ -2,14 +2,23 @@
 
 import numpy
 import sys
-import polytope
-import drivetrain
-import control_loop
-import controls
+from frc971.control_loops.python import polytope
+from y2014_bot3.control_loops.python import drivetrain
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
 from matplotlib import pylab
 
+import gflags
+import glog
+
 __author__ = 'Austin Schuh (austin.linux@gmail.com)'
 
+FLAGS = gflags.FLAGS
+
+try:
+  gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+  pass
 
 def CoerceGoal(region, K, w, R):
   """Intersects a line with a region, and finds the closest point to R.
@@ -110,8 +119,8 @@
     self.B_continuous = numpy.matrix(
         [[self._drivetrain.B_continuous[1, 0], self._drivetrain.B_continuous[1, 1]],
          [self._drivetrain.B_continuous[3, 0], self._drivetrain.B_continuous[3, 1]]])
-    self.C = numpy.matrix(numpy.eye(2));
-    self.D = numpy.matrix(numpy.zeros((2, 2)));
+    self.C = numpy.matrix(numpy.eye(2))
+    self.D = numpy.matrix(numpy.zeros((2, 2)))
 
     self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
                                                self.B_continuous, self.dt)
@@ -119,12 +128,12 @@
     # FF * X = U (steady state)
     self.FF = self.B.I * (numpy.eye(2) - self.A)
 
-    self.PlaceControllerPoles([0.6, 0.6])
+    self.PlaceControllerPoles([0.67, 0.67])
     self.PlaceObserverPoles([0.02, 0.02])
 
     self.G_high = self._drivetrain.G_high
     self.G_low = self._drivetrain.G_low
-    self.R = self._drivetrain.R
+    self.resistance = self._drivetrain.resistance
     self.r = self._drivetrain.r
     self.Kv = self._drivetrain.Kv
     self.Kt = self._drivetrain.Kt
@@ -174,10 +183,14 @@
         [[0.0],
          [0.0]])
 
+    self.U_ideal = numpy.matrix(
+        [[0.0],
+         [0.0]])
+
     # ttrust is the comprimise between having full throttle negative inertia,
     # and having no throttle negative inertia.  A value of 0 is full throttle
     # inertia.  A value of 1 is no throttle negative inertia.
-    self.ttrust = 1.1
+    self.ttrust = 1.0
 
     self.left_gear = VelocityDrivetrain.LOW
     self.right_gear = VelocityDrivetrain.LOW
@@ -229,9 +242,9 @@
                  self.CurrentDrivetrain().r)
     #print gear_name, "Motor Energy Difference.", 0.5 * 0.000140032647 * (low_omega * low_omega - high_omega * high_omega), "joules"
     high_torque = ((12.0 - high_omega / self.CurrentDrivetrain().Kv) *
-                   self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
+                   self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().resistance)
     low_torque = ((12.0 - low_omega / self.CurrentDrivetrain().Kv) *
-                  self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
+                  self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().resistance)
     high_power = high_torque * high_omega
     low_power = low_torque * low_omega
     #if should_print:
@@ -250,16 +263,16 @@
     #goal_gear_is_high = True
 
     if not self.IsInGear(current_gear):
-      print gear_name, 'Not in gear.'
+      glog.debug('%s Not in gear.', gear_name)
       return current_gear
     else:
       is_high = current_gear is VelocityDrivetrain.HIGH
       if is_high != goal_gear_is_high:
         if goal_gear_is_high:
-          print gear_name, 'Shifting up.'
+          glog.debug('%s Shifting up.', gear_name)
           return VelocityDrivetrain.SHIFTING_UP
         else:
-          print gear_name, 'Shifting down.'
+          glog.debug('%s Shifting down.', gear_name)
           return VelocityDrivetrain.SHIFTING_DOWN
       else:
         return current_gear
@@ -303,7 +316,7 @@
     # wheel.
 
     self.left_gear = self.right_gear = True
-    if False:
+    if True:
       self.left_gear = self.ComputeGear(self.X[0, 0], should_print=True,
                                         current_gear=self.left_gear,
                                         gear_name="left")
@@ -316,8 +329,7 @@
       if self.IsInGear(self.right_gear):
         self.right_cim.X[0, 0] = self.MotorRPM(self.right_shifter_position, self.X[0, 0])
 
-    steering *= 2.3
-    if True or self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
+    if self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
       # Filter the throttle to provide a nicer response.
       fvel = self.FilterVelocity(throttle)
 
@@ -362,7 +374,7 @@
       FF_volts = self.CurrentDrivetrain().FF * self.boxed_R
       self.U_ideal = self.CurrentDrivetrain().K * (self.boxed_R - self.X) + FF_volts
     else:
-      print 'Not all in gear'
+      glog.debug('Not all in gear')
       if not self.IsInGear(self.left_gear) and not self.IsInGear(self.right_gear):
         # TODO(austin): Use battery volts here.
         R_left = self.MotorRPM(self.left_shifter_position, self.X[0, 0])
@@ -383,7 +395,7 @@
 
     # TODO(austin): Model the robot as not accelerating when you shift...
     # This hack only works when you shift at the same time.
-    if True or self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
+    if self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
       self.X = self.CurrentDrivetrain().A * self.X + self.CurrentDrivetrain().B * self.U
 
     self.left_gear, self.left_shifter_position = self.SimShifter(
@@ -391,37 +403,36 @@
     self.right_gear, self.right_shifter_position = self.SimShifter(
         self.right_gear, self.right_shifter_position)
 
-    print "U is", self.U[0, 0], self.U[1, 0]
-    print "Left shifter", self.left_gear, self.left_shifter_position, "Right shifter", self.right_gear, self.right_shifter_position
+    glog.debug('U is %s %s', str(self.U[0, 0]), str(self.U[1, 0]))
+    glog.debug('Left shifter %s %d Right shifter %s %d',
+               self.left_gear, self.left_shifter_position,
+               self.right_gear, self.right_shifter_position)
 
 
 def main(argv):
+  argv = FLAGS(argv)
+
   vdrivetrain = VelocityDrivetrain()
 
-  if len(argv) != 7:
-    print "Expected .h file name and .cc file name"
-  else:
-    dog_loop_writer = control_loop.ControlLoopWriter(
-        "VelocityDrivetrain", [vdrivetrain.drivetrain_low_low,
-                       vdrivetrain.drivetrain_low_high,
-                       vdrivetrain.drivetrain_high_low,
-                       vdrivetrain.drivetrain_high_high],
-        namespaces=['y2014_bot3', 'control_loops'])
-
-    if argv[1][-3:] == '.cc':
-      dog_loop_writer.Write(argv[2], argv[1])
+  if not FLAGS.plot:
+    if len(argv) != 5:
+      glog.fatal('Expected .h file name and .cc file name')
     else:
+      namespaces = ['y2014_bot3', 'control_loops', 'drivetrain']
+      dog_loop_writer = control_loop.ControlLoopWriter(
+          "VelocityDrivetrain", [vdrivetrain.drivetrain_low_low,
+                         vdrivetrain.drivetrain_low_high,
+                         vdrivetrain.drivetrain_high_low,
+                         vdrivetrain.drivetrain_high_high],
+                         namespaces=namespaces)
+
       dog_loop_writer.Write(argv[1], argv[2])
 
-    cim_writer = control_loop.ControlLoopWriter(
-        "CIM", [drivetrain.CIM()],
-        namespaces=['y2014_bot3', 'control_loops'])
+      cim_writer = control_loop.ControlLoopWriter(
+          "CIM", [drivetrain.CIM()])
 
-    if argv[5][-3:] == '.cc':
-      cim_writer.Write(argv[6], argv[5])
-    else:
-      cim_writer.Write(argv[5], argv[6])
-    return
+      cim_writer.Write(argv[3], argv[4])
+      return
 
   vl_plot = []
   vr_plot = []
@@ -436,16 +447,16 @@
   vdrivetrain.left_gear = VelocityDrivetrain.LOW
   vdrivetrain.right_gear = VelocityDrivetrain.LOW
 
-  print "K is", vdrivetrain.CurrentDrivetrain().K
+  glog.debug('K is %s', str(vdrivetrain.CurrentDrivetrain().K))
 
   if vdrivetrain.left_gear is VelocityDrivetrain.HIGH:
-    print "Left is high"
+    glog.debug('Left is high')
   else:
-    print "Left is low"
+    glog.debug('Left is low')
   if vdrivetrain.right_gear is VelocityDrivetrain.HIGH:
-    print "Right is high"
+    glog.debug('Right is high')
   else:
-    print "Right is low"
+    glog.debug('Right is low')
 
   for t in numpy.arange(0, 1.7, vdrivetrain.dt):
     if t < 0.5:
@@ -469,22 +480,6 @@
     else:
       radius_plot.append(turn_velocity / fwd_velocity)
 
-  cim_velocity_plot = []
-  cim_voltage_plot = []
-  cim_time = []
-  cim = drivetrain.CIM()
-  R = numpy.matrix([[300]])
-  for t in numpy.arange(0, 0.5, cim.dt):
-    U = numpy.clip(cim.K * (R - cim.X) + R / cim.Kv, cim.U_min, cim.U_max)
-    cim.Update(U)
-    cim_velocity_plot.append(cim.X[0, 0])
-    cim_voltage_plot.append(U[0, 0] * 10)
-    cim_time.append(t)
-  pylab.plot(cim_time, cim_velocity_plot, label='cim spinup')
-  pylab.plot(cim_time, cim_voltage_plot, label='cim voltage')
-  pylab.legend()
-  pylab.show()
-
   # TODO(austin):
   # Shifting compensation.
 
diff --git a/y2014_bot3/joystick_reader.cc b/y2014_bot3/joystick_reader.cc
index 6dfcbb4..86f78dc 100644
--- a/y2014_bot3/joystick_reader.cc
+++ b/y2014_bot3/joystick_reader.cc
@@ -11,11 +11,11 @@
 #include "aos/common/time.h"
 
 #include "frc971/queues/gyro.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
 #include "y2014_bot3/autonomous/auto.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
 #include "y2014_bot3/control_loops/rollers/rollers.q.h"
 
-using ::y2014_bot3::control_loops::drivetrain_queue;
+using ::frc971::control_loops::drivetrain_queue;
 using ::y2014_bot3::control_loops::rollers_queue;
 using ::frc971::sensors::gyro_reading;
 
@@ -30,9 +30,12 @@
 
 // Joystick & button addresses.
 const JoystickAxis kSteeringWheel(1, 1), kDriveThrottle(2, 2);
-const ButtonLocation kShiftHigh(2, 3), kShiftLow(2, 1);
+const ButtonLocation kShiftHigh(2, 3), kShiftHigh2(2, 2), kShiftLow(2, 1);
 const ButtonLocation kQuickTurn(1, 5);
 
+const ButtonLocation kTurn1(1, 7);
+const ButtonLocation kTurn2(1, 11);
+
 const ButtonLocation kFrontRollersIn(3, 8);
 const ButtonLocation kBackRollersIn(3, 7);
 const ButtonLocation kFrontRollersOut(3, 6);
@@ -62,15 +65,33 @@
   }
 
   void HandleDrivetrain(const ::aos::input::driver_station::Data &data) {
+    bool is_control_loop_driving = false;
+    static double left_goal = 0.0;
+    static double right_goal = 0.0;
     const double wheel = -data.GetAxis(kSteeringWheel);
     const double throttle = -data.GetAxis(kDriveThrottle);
 
+    if (data.PosEdge(kTurn1) || data.PosEdge(kTurn2)) {
+      drivetrain_queue.status.FetchLatest();
+      if (drivetrain_queue.status.get()) {
+        left_goal = drivetrain_queue.status->estimated_left_position;
+        right_goal = drivetrain_queue.status->estimated_right_position;
+      }
+    }
+    if (data.IsPressed(kTurn1) || data.IsPressed(kTurn2)) {
+      is_control_loop_driving = true;
+    }
+
     if (!drivetrain_queue.goal.MakeWithBuilder()
              .steering(wheel)
              .throttle(throttle)
-             .quickturn(data.IsPressed(kQuickTurn))
-             .control_loop_driving(false)
              .highgear(is_high_gear_)
+             .quickturn(data.IsPressed(kQuickTurn))
+             .control_loop_driving(is_control_loop_driving)
+             .left_goal(left_goal - wheel * 0.5 + throttle * 0.3)
+             .right_goal(right_goal + wheel * 0.5 + throttle * 0.3)
+             .left_velocity_goal(0)
+             .right_velocity_goal(0)
              .Send()) {
       LOG(WARNING, "sending stick values failed\n");
     }
@@ -79,7 +100,7 @@
       is_high_gear_ = false;
     }
 
-    if (data.PosEdge(kShiftHigh)) {
+    if (data.PosEdge(kShiftHigh) || data.PosEdge(kShiftHigh2)) {
       is_high_gear_ = true;
     }
   }
diff --git a/y2014_bot3/wpilib/BUILD b/y2014_bot3/wpilib/BUILD
index 5f5319c..8af099f 100644
--- a/y2014_bot3/wpilib/BUILD
+++ b/y2014_bot3/wpilib/BUILD
@@ -10,7 +10,7 @@
     '//aos/common:stl_mutex',
     '//aos/common/logging',
     '//third_party/allwpilib_2016:wpilib',
-    '//y2014_bot3/control_loops/drivetrain:drivetrain_queue',
+    '//frc971/control_loops/drivetrain:drivetrain_queue',
     '//aos/common/controls:control_loop',
     '//aos/common/util:log_interval',
     '//aos/common:time',
@@ -29,7 +29,7 @@
     '//frc971/wpilib:pdp_fetcher',
     '//frc971/wpilib:dma',
     '//y2014_bot3/autonomous:auto_queue',
-    '//y2014_bot3/control_loops/drivetrain:drivetrain_lib',
     '//y2014_bot3/control_loops/rollers:rollers_lib',
+    '//y2014_bot3/control_loops/drivetrain:drivetrain_base',
   ],
 )
diff --git a/y2014_bot3/wpilib/wpilib_interface.cc b/y2014_bot3/wpilib/wpilib_interface.cc
index e1e07a0..4abbfce 100644
--- a/y2014_bot3/wpilib/wpilib_interface.cc
+++ b/y2014_bot3/wpilib/wpilib_interface.cc
@@ -3,6 +3,7 @@
 #include <unistd.h>
 #include <inttypes.h>
 
+#include <chrono>
 #include <thread>
 #include <mutex>
 #include <functional>
@@ -27,10 +28,10 @@
 #include "aos/linux_code/init.h"
 #include "aos/common/messages/robot_state.q.h"
 
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "y2014_bot3/control_loops/drivetrain/drivetrain_base.h"
 #include "y2014_bot3/control_loops/rollers/rollers.q.h"
 #include "y2014_bot3/autonomous/auto.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
 #include "y2014_bot3/control_loops/rollers/rollers.h"
 
 #include "frc971/wpilib/joystick_sender.h"
@@ -48,7 +49,7 @@
 #endif
 
 using ::aos::util::SimpleLogInterval;
-using ::y2014_bot3::control_loops::drivetrain_queue;
+using ::frc971::control_loops::drivetrain_queue;
 using ::y2014_bot3::control_loops::rollers_queue;
 using ::frc971::wpilib::BufferedPcm;
 using ::frc971::wpilib::BufferedSolenoid;
@@ -61,13 +62,13 @@
 
 double drivetrain_translate(int32_t in) {
   return static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*4x*/) *
-         ::y2014_bot3::control_loops::kDrivetrainEncoderRatio *
+         ::y2014_bot3::control_loops::drivetrain::kDrivetrainEncoderRatio *
          (4 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
 }
 
 double drivetrain_velocity_translate(double in) {
   return (1.0 / in) / 256.0 /*cpr*/ *
-         ::y2014_bot3::control_loops::kDrivetrainEncoderRatio *
+         ::y2014_bot3::control_loops::drivetrain::kDrivetrainEncoderRatio *
          (4 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
 }
 
@@ -97,8 +98,8 @@
         &DriverStation::GetInstance();
 #endif
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                        ::aos::time::Time::InMS(4));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                        ::std::chrono::milliseconds(4));
 
     ::aos::SetCurrentThreadRealtimePriority(40);
     while (run_) {
@@ -154,7 +155,7 @@
  public:
   SolenoidWriter(const ::std::unique_ptr<::frc971::wpilib::BufferedPcm> &pcm)
       : pcm_(pcm),
-        drivetrain_(".y2014_bot3.control_loops.drivetrain_queue.output"),
+        drivetrain_(".frc971.control_loops.drivetrain_queue.output"),
         rollers_(".y2014_bot3.control_loops.rollers_queue.output") {}
 
   void set_pressure_switch(::std::unique_ptr<DigitalInput> pressure_switch) {
@@ -185,8 +186,8 @@
     ::aos::SetCurrentThreadName("Solenoids");
     ::aos::SetCurrentThreadRealtimePriority(27);
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
-                                        ::aos::time::Time::InMS(1));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+                                        ::std::chrono::milliseconds(1));
 
     while (run_) {
       {
@@ -249,7 +250,7 @@
   ::std::unique_ptr<DigitalInput> pressure_switch_;
   ::std::unique_ptr<Relay> compressor_relay_;
 
-  ::aos::Queue<::y2014_bot3::control_loops::DrivetrainQueue::Output>
+  ::aos::Queue<::frc971::control_loops::DrivetrainQueue::Output>
       drivetrain_;
   ::aos::Queue<::y2014_bot3::control_loops::RollersQueue::Output> rollers_;
 
@@ -269,11 +270,11 @@
 
  private:
   virtual void Read() override {
-    ::y2014_bot3::control_loops::drivetrain_queue.output.FetchAnother();
+    ::frc971::control_loops::drivetrain_queue.output.FetchAnother();
   }
 
   virtual void Write() override {
-    auto &queue = ::y2014_bot3::control_loops::drivetrain_queue.output;
+    auto &queue = ::frc971::control_loops::drivetrain_queue.output;
     LOG_STRUCT(DEBUG, "will output", *queue);
     left_drivetrain_talon_->Set(-queue->left_voltage / 12.0);
     right_drivetrain_talon_->Set(queue->right_voltage / 12.0);
@@ -373,9 +374,9 @@
     // Outputs
     DrivetrainWriter drivetrain_writer;
     drivetrain_writer.set_left_drivetrain_talon(
-        ::std::unique_ptr<Talon>(new Talon(2)));
-    drivetrain_writer.set_right_drivetrain_talon(
         ::std::unique_ptr<Talon>(new Talon(5)));
+    drivetrain_writer.set_right_drivetrain_talon(
+        ::std::unique_ptr<Talon>(new Talon(2)));
     ::std::thread drivetrain_writer_thread(::std::ref(drivetrain_writer));
 
     RollersWriter rollers_writer;
diff --git a/y2015/wpilib/wpilib_interface.cc b/y2015/wpilib/wpilib_interface.cc
index 3130424..14ca146 100644
--- a/y2015/wpilib/wpilib_interface.cc
+++ b/y2015/wpilib/wpilib_interface.cc
@@ -3,9 +3,10 @@
 #include <unistd.h>
 #include <inttypes.h>
 
-#include <thread>
-#include <mutex>
+#include <chrono>
 #include <functional>
+#include <mutex>
+#include <thread>
 
 #include "Encoder.h"
 #include "Talon.h"
@@ -241,8 +242,8 @@
     wrist_encoder_.Start();
     dma_synchronizer_->Start();
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                        ::aos::time::Time::InMS(4));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                        ::std::chrono::milliseconds(4));
 
     ::aos::SetCurrentThreadRealtimePriority(40);
     while (run_) {
@@ -418,8 +419,8 @@
     ::aos::SetCurrentThreadName("Solenoids");
     ::aos::SetCurrentThreadRealtimePriority(27);
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
-                                        ::aos::time::Time::InMS(1));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+                                        ::std::chrono::milliseconds(1));
 
     while (run_) {
       {
diff --git a/y2015_bot3/wpilib/wpilib_interface.cc b/y2015_bot3/wpilib/wpilib_interface.cc
index cb2acf1..bbfa91e 100644
--- a/y2015_bot3/wpilib/wpilib_interface.cc
+++ b/y2015_bot3/wpilib/wpilib_interface.cc
@@ -3,6 +3,7 @@
 #include <unistd.h>
 #include <inttypes.h>
 
+#include <chrono>
 #include <thread>
 #include <mutex>
 #include <functional>
@@ -137,8 +138,8 @@
         &DriverStation::GetInstance();
 #endif
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                        ::aos::time::Time::InMS(4));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                        ::std::chrono::milliseconds(4));
 
     ::aos::SetCurrentThreadRealtimePriority(40);
     while (run_) {
@@ -242,8 +243,8 @@
     ::aos::SetCurrentThreadName("Solenoids");
     ::aos::SetCurrentThreadRealtimePriority(27);
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
-                                        ::aos::time::Time::InMS(1));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+                                        ::std::chrono::milliseconds(1));
 
     while (run_) {
       {
diff --git a/y2016/actors/autonomous_actor.cc b/y2016/actors/autonomous_actor.cc
index 199dda5..7b3fc60 100644
--- a/y2016/actors/autonomous_actor.cc
+++ b/y2016/actors/autonomous_actor.cc
@@ -2,6 +2,7 @@
 
 #include <inttypes.h>
 
+#include <chrono>
 #include <cmath>
 
 #include "aos/common/util/phased_loop.h"
@@ -102,8 +103,8 @@
     return;
   }
 
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   while (true) {
     // Poll the running bit and see if we should cancel.
     phased_loop.SleepUntilNext();
@@ -116,8 +117,8 @@
 constexpr double kDoNotTurnCare = 2.0;
 
 bool AutonomousActor::WaitForDriveNear(double distance, double angle) {
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   constexpr double kPositionTolerance = 0.02;
   constexpr double kProfileTolerance = 0.001;
 
@@ -164,8 +165,8 @@
 }
 
 bool AutonomousActor::WaitForDriveProfileDone() {
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   constexpr double kProfileTolerance = 0.001;
 
   while (true) {
@@ -187,8 +188,8 @@
 }
 
 bool AutonomousActor::WaitForMaxBy(double angle) {
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   double max_angle = -M_PI;
   while (true) {
     if (ShouldCancel()) {
@@ -211,8 +212,8 @@
 }
 
 bool AutonomousActor::WaitForAboveAngle(double angle) {
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   while (true) {
     if (ShouldCancel()) {
       return false;
@@ -231,8 +232,8 @@
 }
 
 bool AutonomousActor::WaitForBelowAngle(double angle) {
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   while (true) {
     if (ShouldCancel()) {
       return false;
@@ -276,8 +277,8 @@
 }
 
 bool AutonomousActor::WaitForDriveDone() {
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
 
   while (true) {
     if (ShouldCancel()) {
@@ -397,8 +398,8 @@
     LOG(ERROR, "Sending shooter goal failed.\n");
   }
 
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   while (true) {
     if (ShouldCancel()) return;
 
@@ -414,8 +415,8 @@
 }
 
 void AutonomousActor::WaitForShooterSpeed() {
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   while (true) {
     if (ShouldCancel()) return;
 
@@ -442,8 +443,8 @@
   double last_angle = 0.0;
   int ready_to_fire = 0;
 
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   ::aos::time::Time end_time =
       ::aos::time::Time::Now() + align_duration;
   while (end_time > ::aos::time::Time::Now()) {
@@ -632,8 +633,10 @@
 
 void AutonomousActor::BackLongShotTwoBallFinish() {
   LOG(INFO, "Expanding for back long shot\n");
-  MoveSuperstructure(0.00, M_PI / 2.0 - 0.2, -0.625, {7.0, 40.0}, {4.0, 6.0},
-                     {10.0, 25.0}, false, 0.0);
+  MoveSuperstructure(
+      0.00, M_PI / 2.0 - 0.2, -0.625 + 0.03, {7.0, 40.0},
+      {4.0, 6.0},
+      {10.0, 25.0}, false, 0.0);
 }
 
 void AutonomousActor::BackLongShot() {
@@ -783,8 +786,8 @@
 }
 
 void AutonomousActor::WaitForBallOrDriveDone() {
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   while (true) {
     if (ShouldCancel()) {
       return;
@@ -1164,8 +1167,8 @@
 
   LOG(INFO, "Done %f\n", (aos::time::Time::Now() - start_time).ToSeconds());
 
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
 
   while (!ShouldCancel()) {
     phased_loop.SleepUntilNext();
diff --git a/y2016/actors/vision_align_actor.cc b/y2016/actors/vision_align_actor.cc
index 00695f0..9491cd4 100644
--- a/y2016/actors/vision_align_actor.cc
+++ b/y2016/actors/vision_align_actor.cc
@@ -1,5 +1,6 @@
 #include "y2016/actors/vision_align_actor.h"
 
+#include <chrono>
 #include <functional>
 #include <numeric>
 
@@ -28,8 +29,8 @@
     const actors::VisionAlignActionParams & /*params*/) {
   const double robot_radius =
       control_loops::drivetrain::GetDrivetrainConfig().robot_radius;
-  ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                      ::aos::time::Time::InMS(5) / 2);
+  ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                      ::std::chrono::milliseconds(5) / 2);
   while (true) {
     const int iterations = phased_loop.SleepUntilNext();
     if (iterations != 1) {
diff --git a/y2016/constants.cc b/y2016/constants.cc
index d692c3d..5353d6e 100644
--- a/y2016/constants.cc
+++ b/y2016/constants.cc
@@ -81,8 +81,7 @@
           5.0,  // drivetrain max speed
 
           // Intake
-          {
-           // Value to add to the pot reading for the intake.
+          {// Value to add to the pot reading for the intake.
            -4.550531 + 150.40906362 * M_PI / 180.0 + 0.5098 - 0.0178 - 0.0725,
            {Values::kZeroingSampleSize, Values::kIntakeEncoderIndexDifference,
             // Location of an index pulse.
@@ -90,21 +89,19 @@
           },
 
           // Shoulder
-          {
-           // Value to add to the pot reading for the shoulder.
-           -1.0 - 0.0822 + 0.06138835 * M_PI / 180.0 - 0.0323 - 0.1057 +
-               0.0035 + 0.0055 - 0.001 - 0.0103 + 0.0032,
+          {// Value to add to the pot reading for the shoulder.
+           -2.86275657117,
            {Values::kZeroingSampleSize, Values::kShoulderEncoderIndexDifference,
-            0.535359, 2.5},
+            0.097312, 2.5},
           },
 
           // Wrist
-          {
-           // Value to add to the pot reading for the wrist.
+          {// Value to add to the pot reading for the wrist.
            3.2390714288298668 + -0.06138835 * M_PI / 180.0 + 0.0078 - 0.0548 -
-               0.0167 + 0.002 - 0.0026 - 0.1040 - 0.0035 - 0.0012 + 0.0166 - 0.017 + 0.148 + 0.004,
+               0.0167 + 0.002 - 0.0026 - 0.1040 - 0.0035 - 0.0012 + 0.0166 -
+               0.017 + 0.148 + 0.004 + 0.024701 - 0.0741,
            {Values::kZeroingSampleSize, Values::kWristEncoderIndexDifference,
-            -0.354946, 2.5},
+            0.000820, 2.5},
           },
 
           0.0,
@@ -116,10 +113,9 @@
           5.0,  // drivetrain max speed
 
           // Intake
-          {
-           // Hard stop is 164.2067247 degrees.
-           -4.2193 + (164.2067247 * M_PI / 180.0 + 0.02 - 0.0235) + 0.0549 -
-               0.104 + 0.019 - 0.938 + 0.660 - 0.002,
+          {// Hard stop is 160.0185751389329 degrees.
+           -4.2193 + (160.0185751389329 * M_PI / 180.0 + 0.02 - 0.0235) +
+               0.0549 - 0.104 + 0.019 - 0.938 + 0.660 - 0.002 - 0.2081,
            {Values::kZeroingSampleSize, Values::kIntakeEncoderIndexDifference,
             0.332370, 1.3},
           },
@@ -135,7 +131,8 @@
           // Wrist
           {
            3.326328571170133 - 0.06138835 * M_PI / 180.0 - 0.177 + 0.0323 -
-               0.023 + 0.0488 + 0.0120 - 0.0005 - 0.0784 - 0.0010 - 0.080 + 0.1245,
+               0.023 + 0.0488 + 0.0120 - 0.0005 - 0.0784 - 0.0010 - 0.080 +
+               0.1245,
            {Values::kZeroingSampleSize, Values::kWristEncoderIndexDifference,
             -0.263227, 1.3},
           },
diff --git a/y2016/constants.h b/y2016/constants.h
index d52555c..a83456c 100644
--- a/y2016/constants.h
+++ b/y2016/constants.h
@@ -33,14 +33,14 @@
   // Ratios for our subsystems.
   static constexpr double kShooterEncoderRatio = 1.0;
   static constexpr double kIntakeEncoderRatio =
-      16.0 / 48.0 * 18.0 / 72.0 * 14.0 / 64.0;
+      14.0 / 64.0 * 18.0 / 72.0 * 16.0 / 48.0;
   static constexpr double kShoulderEncoderRatio =
-      12.0 / 42.0 * 18.0 / 72.0 * 14.0 / 64.0;
+      14.0 / 64.0 * 18.0 / 72.0 * 12.0 / 42.0;
   static constexpr double kWristEncoderRatio =
-      16.0 / 48.0 * 18.0 / 64.0 * 14.0 / 54.0;
+      14.0 / 54.0 * 18.0 / 64.0 * 16.0 / 48.0;
 
-  static constexpr double kIntakePotRatio = 16.0 / 48.0 * 18.0 / 72.0;
-  static constexpr double kShoulderPotRatio = 16.0 / 58.0;
+  static constexpr double kIntakePotRatio = 18.0 / 72.0 * 16.0 / 48.0;
+  static constexpr double kShoulderPotRatio = 12.0 / 42.0;
   static constexpr double kWristPotRatio = 16.0 / 48.0;
 
   // Difference in radians between index pulses.
diff --git a/y2016/dashboard/dashboard.cc b/y2016/dashboard/dashboard.cc
index bdfedb8..22a77fa 100644
--- a/y2016/dashboard/dashboard.cc
+++ b/y2016/dashboard/dashboard.cc
@@ -49,7 +49,7 @@
     : cur_raw_data_("no data"),
       sample_id_(0),
       measure_index_(0),
-      overflow_id_(20) {}
+      overflow_id_(1) {}
 
 void DataCollector::RunIteration() {
   ::aos::MutexLocker locker(&mutex_);
@@ -183,26 +183,28 @@
 
   // Note that we are ignoring the from_sample being sent to keep up with the
   // live data without worrying about client lag.
-  int32_t cur_sample = sample_id_ - 2;
+  int32_t cur_sample = sample_id_;
   int32_t adjusted_index = GetIndex(cur_sample);
   message << "$";  // Begin data packet.
 
   // Make sure we are not out of range.
-  if (static_cast<size_t>(adjusted_index) <
-      sample_items_.at(0).datapoints.size()) {
-    message << cur_sample << "%"
-            << sample_items_.at(0)
-                   .datapoints.at(adjusted_index)
-                   .time.ToSeconds() << "%";  // Send time.
-    // Add comma-separated list of data points.
-    for (size_t cur_measure = 0; cur_measure < sample_items_.size();
-         cur_measure++) {
-      if (cur_measure > 0) {
-        message << ",";
-      }
-      message << sample_items_.at(cur_measure)
+  if (sample_items_.size() > 0) {
+    if (static_cast<size_t>(adjusted_index) <
+        sample_items_.at(0).datapoints.size()) {
+      message << cur_sample << "%"
+              << sample_items_.at(0)
                      .datapoints.at(adjusted_index)
-                     .value;
+                     .time.ToSeconds() << "%";  // Send time.
+      // Add comma-separated list of data points.
+      for (size_t cur_measure = 0; cur_measure < sample_items_.size();
+           cur_measure++) {
+        if (cur_measure > 0) {
+          message << ",";
+        }
+        message << sample_items_.at(cur_measure)
+                       .datapoints.at(adjusted_index)
+                       .value;
+      }
     }
   }
 
diff --git a/y2016/dashboard/www/index.html b/y2016/dashboard/www/index.html
index da5512f..3821b48 100644
--- a/y2016/dashboard/www/index.html
+++ b/y2016/dashboard/www/index.html
@@ -7,11 +7,11 @@
 var escapable =
   /[\x00-\x1f\ud800-\udfff\u200c-\u200f\u2028-\u202f\u2060-\u206f\ufff0-\uffff]/g;
 var ws;
-var intervalTime = 50;
+var intervalTime = 100;
 var selected = 0;
 var reconnecting = false;
 var lastSampleID = 0;
-var resetTimeout;
+var reconnectTimeout;
 
 // Filter out junky JSON packets that will otherwise cause nasty decoding
 // errors. These errors come as a result of incomplete packets, corrupted data,
@@ -145,12 +145,13 @@
 }
 
 function reconnect() {
+  clearTimeout(reconnectTimeout);
   $('#message').text('Reconnecting...');
   $('#dataTable').empty();
   lastSampleID = 0;
   reconnecting = true;
 
-  setTimeout(function(){
+  reconnectTimeout = setTimeout(function(){
     initSocketLoop()
   }, 500);
 }
diff --git a/y2016/plotting/responsive_plotter.js b/y2016/plotting/responsive_plotter.js
new file mode 100644
index 0000000..0840e1d
--- /dev/null
+++ b/y2016/plotting/responsive_plotter.js
@@ -0,0 +1,238 @@
+"use strict";
+
+// Create anonymous namespace to avoid leaking these functions.
+(function() {
+// Convenience function that fetches a file and extracts the array buffer.
+function fetch_ArrayBuffer(url) { // returns Promise<ArrayBuffer>
+	return fetch(url).then(function(val) { return val.arrayBuffer(); });
+}
+
+// Two dimensional vector.
+class Point2d {
+	constructor(x, y) {
+		this.x = x;
+		this.y = y;
+	}
+	sub(o) { return new Point2d(this.x - o.x, this.y - o.y); }
+	add(o) { return new Point2d(this.x + o.x, this.y + o.y); }
+};
+
+// Drag event object for updating a Point2d class by reference.
+class PointDrag {
+	constructor(point) { // point : Point2d
+		this.point = point;
+	}
+	doDrag(delta) {
+		this.point.x += delta.x;
+		this.point.y += delta.y;
+	}
+	doMouseUp(e) { return null; }
+}
+
+// Takes in a canvas and adds the ability to click and drag the offset point.
+// scaleX and scaleY are allowed to be locked or not-locked as the scroll events
+// must be handled by the user of this class.
+//
+// offset.x and offset.y are defined in reference to the model-scale, not the viewport.
+// Thus to move the viewport you need to use offset.x * scaleX, etc.
+//
+// scaleX and scaleY aren't automatically applied to the rendering context because
+// differing x and y scales mess up the line width rendering.
+class ClickDrag {
+	constructor(canvas) {
+ 		canvas.addEventListener('selectstart', function(e) { e.preventDefault(); return false; }, false);
+  	canvas.addEventListener('mousemove', this.handleMouseMove.bind(this), true);
+		canvas.addEventListener('mousedown', this.handleMouseDown.bind(this), true);
+		canvas.addEventListener('mouseup', this.handleMouseUp.bind(this), true);
+		this.canvas = canvas;
+		this.dragger = null;
+		this.offset = new Point2d(0, 0);
+		this.scaleX = 1.0;
+		this.scaleY = 1.0;
+		this.old_point = null;
+		this.on_redraw = null;
+	}
+	translateContext(ctx) { // ctx : CanvasRenderingContext2D 
+		ctx.translate(this.offset.x * this.scaleX, this.offset.y * this.scaleY);
+	}
+	handleMouseMove(e) { // e : MouseEvent
+		let pos = new Point2d(e.offsetX / this.scaleX, e.offsetY / this.scaleY);
+		if (this.old_point !== null && this.dragger !== null) {
+			this.dragger.doDrag(pos.sub(this.old_point));
+			if (this.on_redraw !== null) { this.on_redraw(); }
+		}
+		this.old_point = pos;
+  }
+	get width() { return this.canvas.width; }
+	handleMouseDown(e) { // e : MouseEvent
+		this.dragger = new PointDrag(this.offset);
+	}
+	handleMouseUp(e) { // e : MouseEvent
+		if (this.dragger === null) { return; }
+		if (this.dragger.doMouseUp !== undefined) {
+			this.dragger = this.dragger.doMouseUp(e);
+			if (this.on_redraw !== null) { this.on_redraw(); }
+		}
+	}
+	multiplyScale(evt, dx, dy) {
+		let x_cur = evt.offsetX / this.scaleX - this.offset.x;
+		let y_cur = evt.offsetY / this.scaleY - this.offset.y;
+		this.scaleX *= dx;
+		this.scaleY *= dy;
+		this.offset.x = evt.offsetX / this.scaleX - x_cur;
+		this.offset.y = evt.offsetY / this.scaleY - y_cur;
+		if (this.on_redraw !== null) { this.on_redraw(); }
+	}
+};
+
+// This represents a particular downsampling of a timeseries dataset.
+// For the base level, data = min = max.
+// This is required
+class MipMapLevel {
+	// All arrays should be the same size.
+	constructor(data, min, max, scale) { // data : Float32Array, min : Float32Array, max : Float32Array, scale : Integer
+		this.data = data;
+		this.min = min;
+		this.max = max;
+		this.scale = scale;
+	}
+	get length() { return this.data.length; }
+	// Uses box filter to downsample. Guassian may be an improvement.
+	downsample() {
+		let new_length = (this.data.length / 2) | 0;
+		let data = new Float32Array(new_length);
+		let min = new Float32Array(new_length);
+		let max = new Float32Array(new_length);
+		for (let i = 0; i < new_length; i++) {
+			let i1 = i * 2;
+			let i2 = i1 + 1
+			data[i] = (this.data[i1] + this.data[i2]) / 2.0;
+			min[i] = Math.min(this.min[i1], this.min[i2]);
+			max[i] = Math.max(this.max[i1], this.max[i2]);
+		}
+		return new MipMapLevel(data, min, max, this.scale * 2);
+	}
+	static makeBaseLevel(data) { // data : Float32Array
+		return new MipMapLevel(data, data, data, 1);
+	}
+	clipv(v) { // v : Numeric
+		return Math.min(Math.max(v|0, 0), this.length - 1);
+	}
+	draw(ctx, clickDrag) { // ctx : CanvasRenderingContext2D, clickDrag : ClickDrag
+		let scalex = clickDrag.scaleX * this.scale;
+		let scaley = clickDrag.scaleY;
+		let stx = -clickDrag.offset.x / this.scale;
+		let edx = stx + clickDrag.width / scalex;
+		let sti = this.clipv(stx - 2);
+		let edi = this.clipv(edx + 2);
+		ctx.beginPath();
+		ctx.fillStyle="#00ff00";
+		ctx.moveTo(sti * scalex, scaley * this.min[sti]);
+		for (let i = sti + 1; i <= edi; i++) {
+			ctx.lineTo(i * scalex, scaley * this.min[i]);
+		}
+		for (let i = edi; i >= sti; --i) {
+			ctx.lineTo(i * scalex, scaley * this.max[i]);
+		}
+		ctx.fill();
+		ctx.closePath();
+
+		ctx.beginPath();
+		ctx.strokeStyle="#008f00";
+		ctx.moveTo(sti * scalex, scaley * this.data[sti]);
+		for (let i = sti + 1; i <= edi; i++) {
+			ctx.lineTo(i * scalex, scaley * this.data[i]);
+		}
+		ctx.stroke();
+		ctx.closePath();
+	}
+};
+
+// This class represents all downsampled data levels.
+// This must only be used for descrite time-series data.
+class MipMapper {
+	constructor(samples) { // samples : Float32Array
+		this.levels = [];
+		let level = MipMapLevel.makeBaseLevel(samples);
+		this.levels.push(level);
+		while (level.length > 2) {
+			level = level.downsample();
+			this.levels.push(level);
+		}
+	}
+	// Find the level such that samples are spaced at most 2 pixels apart
+	getLevel(scale) { // scale : Float
+		let level = this.levels[0];
+		for (let i = 0; i < this.levels.length; ++i) {
+			// Someone who understands nyquist could probably improve this.
+			if (this.levels[i].scale * scale <= 4.0) {
+				level = this.levels[i];
+			}
+		}
+		return level;
+	}
+}
+
+// Custom HTML element for x-responsive-plotter.
+// This should be the main entry-point for this code.
+class ResponsivePlotter extends HTMLElement {
+	createdCallback() {
+		this.data = null;
+		this.canvas = document.createElement("canvas");
+		this.canvas.style["background"] = "inherit";
+		this.canvas.addEventListener("mousewheel", this.doScroll.bind(this), false);
+		this.clickDrag = new ClickDrag(this.canvas);
+		this.clickDrag.on_redraw = this.doRedraw.bind(this);
+		this.clickDrag.offset.y = 160; //320;
+		this.updateInnerData();
+		this.appendChild(this.canvas);
+	}
+	doScroll(e) {
+		let factor = (e.wheelDelta < 0) ? 0.9 : 1.1;
+		this.clickDrag.multiplyScale(e, e.shiftKey ? 1.0 : factor, e.shiftKey ? factor : 1.0);
+		e.preventDefault();
+	}
+	doRedraw() {
+		this.redraw();
+	}
+	updateInnerData() {
+		this.canvas.width = this.getAttribute("width") || 640;
+		this.canvas.height = this.getAttribute("height") || 480;
+		fetch_ArrayBuffer(this.getAttribute("data")).then(this.dataUpdated.bind(this));
+		this.redraw();
+	}
+	attributeChangedCallback(attrName, oldVal, newVal) {
+		if (attrName == "width") {
+			this.canvas.width = this.getAttribute("width") || 640;
+			this.redraw();
+		} else if (attrName == "height") {
+			this.canvas.width = this.getAttribute("height") || 480;
+			this.redraw();
+		} else if (attrName == "data") {
+			// Should this clear out the canvas if a different url is selected?
+			// Well it does.
+			this.data = null;
+			fetch_ArrayBuffer(this.getAttribute("data")).then(this.dataUpdated.bind(this));
+		}
+	}
+	dataUpdated(data) { // data : ArrayBuffer
+		this.data = new MipMapper(new Float32Array(data));
+		this.redraw();
+	}
+	redraw() {
+		let ctx = this.canvas.getContext('2d');
+		ctx.clearRect(0, 0, this.canvas.width, this.canvas.height);
+		ctx.save();
+		this.clickDrag.translateContext(ctx);
+		if (this.data !== null) {
+			let level = this.data.getLevel(this.clickDrag.scaleX);
+			level.draw(ctx, this.clickDrag);
+		}
+		ctx.restore();
+	}
+};
+
+
+// TODO(parker): This is chrome-specific v0 version of this switch to v1 when available.
+document.registerElement('x-responsive-plotter', ResponsivePlotter);
+})();
diff --git a/y2016/plotting/test.html b/y2016/plotting/test.html
new file mode 100644
index 0000000..df278b0
--- /dev/null
+++ b/y2016/plotting/test.html
@@ -0,0 +1,12 @@
+<!DOCTYPE html>
+<html>
+	<head>
+		<meta charset="UTF-8">
+		<script src="/responsive_plotter.js" type="text/javascript"></script>
+	</head>
+
+	<body style=>
+		<x-responsive-plotter width=800 data="/test_data" style="background: lightblue;">
+		</x-responsive-plotter>
+	</body>
+</html>
diff --git a/y2016/plotting/test.rb b/y2016/plotting/test.rb
new file mode 100644
index 0000000..9f2f58a
--- /dev/null
+++ b/y2016/plotting/test.rb
@@ -0,0 +1,29 @@
+require "sinatra"
+
+# Must use sinatra server for this because fetch() in javascript
+# cannot load from the filesystem.
+get '/test.html' do
+	File.read("./test.html")
+end
+
+get '/responsive_plotter.js' do
+	content_type 'text/javascript'
+	File.read("./responsive_plotter.js")
+end
+
+get '/test_data' do
+	content_type 'binary/octet-stream'
+	data = ""
+	# Use ./test_data if it exists. Otherwise random data.
+	if (File.exists?("./test_data"))
+		data = File.read("./test_data")
+	else
+		1000.times do
+			data += (1024.times.collect do |i|
+				(rand() * 480  - 160)
+			end.pack("F*"))
+		end
+	end
+	data
+end
+
diff --git a/y2016/wpilib/wpilib_interface.cc b/y2016/wpilib/wpilib_interface.cc
index acf820f..d7fc261 100644
--- a/y2016/wpilib/wpilib_interface.cc
+++ b/y2016/wpilib/wpilib_interface.cc
@@ -3,6 +3,7 @@
 #include <unistd.h>
 #include <inttypes.h>
 
+#include <chrono>
 #include <thread>
 #include <mutex>
 #include <functional>
@@ -282,8 +283,8 @@
 
     dma_synchronizer_->Start();
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
-                                        ::aos::time::Time::InMS(4));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+                                        ::std::chrono::milliseconds(4));
 
     ::aos::SetCurrentThreadRealtimePriority(40);
     while (run_) {
@@ -472,8 +473,8 @@
     ::aos::SetCurrentThreadName("Solenoids");
     ::aos::SetCurrentThreadRealtimePriority(27);
 
-    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
-                                        ::aos::time::Time::InMS(1));
+    ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+                                        ::std::chrono::milliseconds(1));
 
     while (run_) {
       {