Update bot3 drivetrain and get defense bot working.

Change-Id: I0e3d5c0e768ee77eaeaf0a963f15c3172389ea6e
diff --git a/NO_BUILD_ROBORIO b/NO_BUILD_ROBORIO
index 503a3a2..bd1907c 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/...
 -//y2015/control_loops/python/...
 -//y2015_bot3/control_loops/python/...
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..5692465 100644
--- a/y2014_bot3/wpilib/wpilib_interface.cc
+++ b/y2014_bot3/wpilib/wpilib_interface.cc
@@ -27,10 +27,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 +48,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 +61,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);
 }
 
@@ -154,7 +154,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) {
@@ -249,7 +249,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 +269,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 +373,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;