Merging in Brian's latest gyro board code.

Conflicts:
	gyro_board/src/usb/encoder.c
diff --git a/aos/atom_code/camera/Buffers.cpp b/aos/atom_code/camera/Buffers.cpp
index 9cd1a7d..d0d20f5 100644
--- a/aos/atom_code/camera/Buffers.cpp
+++ b/aos/atom_code/camera/Buffers.cpp
@@ -23,18 +23,15 @@
   } addr;
   const int r = socket(AF_UNIX, SOCK_STREAM, 0);
   if (r == -1) {
-    LOG(ERROR, "socket(AF_UNIX, SOCK_STREAM, 0) failed with %d: %s\n",
+    LOG(FATAL, "socket(AF_UNIX, SOCK_STREAM, 0) failed with %d: %s\n",
         errno, strerror(errno));
-    return -1;
   }
   addr.un.sun_family = AF_UNIX;
   memset(addr.un.sun_path, 0, sizeof(addr.un.sun_path));
   strcpy(addr.un.sun_path, kFDServerName.c_str());
   if (bind_connect(r, &addr.addr, sizeof(addr.un)) == -1) {
-    LOG(ERROR, "bind_connect(=%p)(%d, %p, %zd) failed with %d: %s\n",
+    LOG(FATAL, "bind_connect(=%p)(%d, %p, %zd) failed with %d: %s\n",
         bind_connect, r, &addr.addr, sizeof(addr.un), errno, strerror(errno));
-    close(r); // what are we going to do about an error?
-    return -1;
   }
   return r;
 }
diff --git a/aos/atom_code/camera/Reader.cpp b/aos/atom_code/camera/Reader.cpp
index 95f6128..125fde1 100644
--- a/aos/atom_code/camera/Reader.cpp
+++ b/aos/atom_code/camera/Reader.cpp
@@ -391,7 +391,7 @@
       }
 
       if (FD_ISSET(fd_, &fds)) {
-        LOG(INFO, "Got a frame\n");
+        LOG(DEBUG, "Got a frame\n");
         ReadFrame();
       }
       if (FD_ISSET(server_fd_, &fds)) {
diff --git a/aos/atom_code/input/joystick_input.cc b/aos/atom_code/input/joystick_input.cc
index 28618ed..97b2c95 100644
--- a/aos/atom_code/input/joystick_input.cc
+++ b/aos/atom_code/input/joystick_input.cc
@@ -62,6 +62,26 @@
           }
         }
       }
+
+      using driver_station::ControlBit;
+      if (data.PosEdge(ControlBit::kFmsAttached)) {
+        LOG(INFO, "PosEdge(kFmsAttached)\n");
+      }
+      if (data.NegEdge(ControlBit::kFmsAttached)) {
+        LOG(INFO, "NegEdge(kFmsAttached)\n");
+      }
+      if (data.PosEdge(ControlBit::kAutonomous)) {
+        LOG(INFO, "PosEdge(kAutonomous)\n");
+      }
+      if (data.NegEdge(ControlBit::kAutonomous)) {
+        LOG(INFO, "NegEdge(kAutonomous)\n");
+      }
+      if (data.PosEdge(ControlBit::kEnabled)) {
+        LOG(INFO, "PosEdge(kEnabled)\n");
+      }
+      if (data.NegEdge(ControlBit::kEnabled)) {
+        LOG(INFO, "NegEdge(kEnabled)\n");
+      }
     }
 
     RunIteration(data);
diff --git a/aos/build/download_externals.sh b/aos/build/download_externals.sh
index f671ac3..13c8eff 100755
--- a/aos/build/download_externals.sh
+++ b/aos/build/download_externals.sh
@@ -121,3 +121,18 @@
   CFLAGS='-m32' CXXFLAGS='-m32' LDFLAGS='-m32' \
   bash -c "cd ${LIBEVENT_DIR} && ./configure \
   --prefix=`readlink -f ${LIBEVENT_PREFIX}` && make && make install"
+
+# get and build libcdd
+LIBCDD_VERSION=094g
+LIBCDD_DIR=${EXTERNALS}/libcdd-${LIBCDD_VERSION}
+LIBCDD_PREFIX=${LIBCDD_DIR}-prefix
+LIBCDD_LIB=${LIBCDD_PREFIX}/lib/libcdd.a
+LIBCDD_URL=ftp://ftp.ifor.math.ethz.ch/pub/fukuda/cdd/cddlib-${LIBCDD_VERSION}.tar.gz
+[ -f ${LIBCDD_DIR}.tar.gz ] || \
+        wget ${LIBCDD_URL} -O ${LIBCDD_DIR}.tar.gz
+[ -d ${LIBCDD_DIR} ] || ( mkdir ${LIBCDD_DIR} && tar \
+        --strip-components=1 -C ${LIBCDD_DIR} -xf ${LIBCDD_DIR}.tar.gz )
+[ -f ${LIBCDD_LIB} ] || env -i PATH="${PATH}" \
+        CFLAGS='-m32' CXXFLAGS='-m32' LDFLAGS='-m32' \
+        bash -c "cd ${LIBCDD_DIR} && ./configure --disable-shared \
+        --prefix=`readlink -f ${LIBCDD_PREFIX}` && make && make install"
diff --git a/aos/build/externals.gyp b/aos/build/externals.gyp
index 2bfee69..99b26cf 100644
--- a/aos/build/externals.gyp
+++ b/aos/build/externals.gyp
@@ -15,6 +15,7 @@
     'libusb_apiversion': '1.0',
     'compiler_rt_version': 'RELEASE_32_final',
     'libevent_version': '2.0.21',
+    'libcdd_version': '094g',
   },
   'targets': [
     {
@@ -207,6 +208,16 @@
         'include_dirs': ['<(externals)/libusb-<(libusb_version)-prefix/include'],
       },
     },
+    {
+      'target_name': 'libcdd',
+      'type': 'none',
+      'link_settings': {
+        'libraries': ['<(externals_abs)/libcdd-<(libcdd_version)-prefix/lib/libcdd.a'],
+      },
+      'direct_dependent_settings': {
+        'include_dirs': ['<(externals_abs)/libcdd-<(libcdd_version)-prefix/include'],
+      },
+    },
   ],
   'includes': [
     'libgcc-additions/libgcc-additions.gypi',
diff --git a/aos/controls/polytope.h b/aos/controls/polytope.h
new file mode 100644
index 0000000..ed4b36d
--- /dev/null
+++ b/aos/controls/polytope.h
@@ -0,0 +1,126 @@
+#ifndef _AOS_CONTROLS_POLYTOPE_H_
+#define _AOS_CONTROLS_POLYTOPE_H_
+
+#include "Eigen/Dense"
+#include "aos/externals/libcdd-094g-prefix/include/setoper.h"
+#include "aos/externals/libcdd-094g-prefix/include/cdd.h"
+
+namespace aos {
+namespace controls {
+
+// A n dimension polytope.
+template <int number_of_dimensions>
+class HPolytope {
+ public:
+  // Constructs a polytope given the H and k matricies.
+  HPolytope(Eigen::Matrix<double, Eigen::Dynamic, number_of_dimensions> H,
+            Eigen::Matrix<double, Eigen::Dynamic, 1> k)
+      : H_(H),
+        k_(k) {
+  }
+
+  static void Init() {
+    dd_set_global_constants();
+  }
+
+  // Returns a reference to H.
+  const Eigen::Matrix<double, Eigen::Dynamic,
+                      number_of_dimensions> &H() const {
+    return H_;
+  }
+
+  // Returns a reference to k.
+  const Eigen::Matrix<double, Eigen::Dynamic,
+                      1> &k() const {
+    return k_;
+  }
+
+  // Returns the number of dimensions in the polytope.
+  int ndim() const { return number_of_dimensions; }
+
+  // Returns the number of constraints currently in the polytope.
+  int num_constraints() const { return k_.rows(); }
+
+  // Returns true if the point is inside the polytope.
+  bool IsInside(Eigen::Matrix<double, number_of_dimensions, 1> point);
+
+  // Returns the list of vertices inside the polytope.
+  Eigen::Matrix<double, number_of_dimensions, Eigen::Dynamic> Vertices();
+
+ private:
+  Eigen::Matrix<double, Eigen::Dynamic, number_of_dimensions> H_;
+  Eigen::Matrix<double, Eigen::Dynamic, 1> k_;
+};
+
+template <int number_of_dimensions>
+bool HPolytope<number_of_dimensions>::IsInside(
+    Eigen::Matrix<double, number_of_dimensions, 1> point) {
+  auto ev = H_ * point;
+  for (int i = 0; i < num_constraints(); ++i) {
+    if (ev(i, 0) > k_(i, 0)) {
+      return false;
+    }
+  }
+  return true;
+}
+
+template <int number_of_dimensions>
+Eigen::Matrix<double, number_of_dimensions, Eigen::Dynamic>
+    HPolytope<number_of_dimensions>::Vertices() {
+  dd_MatrixPtr matrix = dd_CreateMatrix(num_constraints(), ndim() + 1);
+
+  // Copy the data over. TODO(aschuh): Is there a better way?  I hate copying...
+  for (int i = 0; i < num_constraints(); ++i) {
+    dd_set_d(matrix->matrix[i][0], k_(i, 0));
+    for (int j = 0; j < ndim(); ++j) {
+      dd_set_d(matrix->matrix[i][j + 1], -H_(i, j));
+    }
+  }
+
+  matrix->representation = dd_Inequality;
+  matrix->numbtype = dd_Real;
+
+  dd_ErrorType error;
+  dd_PolyhedraPtr polyhedra = dd_DDMatrix2Poly(matrix, &error);
+  if (error != dd_NoError || polyhedra == NULL) {
+    dd_WriteErrorMessages(stderr, error);
+    dd_FreeMatrix(matrix);
+    Eigen::Matrix<double, number_of_dimensions, Eigen::Dynamic> ans(0, 0);
+    return ans;
+  }
+
+  dd_MatrixPtr vertex_matrix = dd_CopyGenerators(polyhedra);
+
+  int num_vertices = 0;
+  int num_rays = 0;
+  for (int i = 0; i < vertex_matrix->rowsize; ++i) {
+    if (dd_get_d(vertex_matrix->matrix[i][0]) == 0) {
+      num_rays += 1;
+    } else {
+      num_vertices += 1;
+    }
+  }
+
+  Eigen::Matrix<double, number_of_dimensions, Eigen::Dynamic> vertices(
+      number_of_dimensions, num_vertices);
+
+  int vertex_index = 0;
+  for (int i = 0; i < vertex_matrix->rowsize; ++i) {
+    if (dd_get_d(vertex_matrix->matrix[i][0]) != 0) {
+      for (int j = 0; j < number_of_dimensions; ++j) {
+        vertices(j, vertex_index) = dd_get_d(vertex_matrix->matrix[i][j + 1]);
+      }
+      ++vertex_index;
+    }
+  }
+  dd_FreeMatrix(vertex_matrix);
+  dd_FreePolyhedra(polyhedra);
+  dd_FreeMatrix(matrix);
+
+  return vertices;
+}
+
+}  // namespace controls
+}  // namespace aos
+
+#endif  // _AOS_CONTROLS_POLYTOPE_H_
diff --git a/aos/externals/.gitignore b/aos/externals/.gitignore
index 73cb3e2..694129e 100644
--- a/aos/externals/.gitignore
+++ b/aos/externals/.gitignore
@@ -25,3 +25,7 @@
 /libevent-2.0.21-prefix/
 /libevent-2.0.21.tar.gz
 /libevent-2.0.21/
+/libcdd-094g-prefix/
+/libcdd-094g.tar.gz
+/libcdd-094g/
+
diff --git a/frc971/constants.cc b/frc971/constants.cc
index 76a5f3b..d062c77 100644
--- a/frc971/constants.cc
+++ b/frc971/constants.cc
@@ -8,6 +8,11 @@
 #include "aos/common/once.h"
 #include "aos/common/network/team_number.h"
 
+#include "frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+#include "frc971/control_loops/drivetrain/polydrivetrain_clutch_motor_plant.h"
+#include "frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "frc971/control_loops/drivetrain/drivetrain_clutch_motor_plant.h"
+
 #ifndef M_PI
 #define M_PI 3.14159265358979323846
 #endif
@@ -19,8 +24,8 @@
 // It has about 0.029043 of gearbox slop.
 // For purposes of moving the end up/down by a certain amount, the wrist is 18
 // inches long.
-const double kCompWristHallEffectStartAngle = 1.285;
-const double kPracticeWristHallEffectStartAngle = 1.175;
+const double kCompWristHallEffectStartAngle = 1.27;
+const double kPracticeWristHallEffectStartAngle = 1.178;
 
 const double kWristHallEffectStopAngle = 100 * M_PI / 180.0;
 
@@ -70,8 +75,23 @@
 const int kCompCameraCenter = -2;
 const int kPracticeCameraCenter = -5;
 
-const int kCompDrivetrainGearboxPinion = 19;
-const int kPracticeDrivetrainGearboxPinion = 17;
+const double kCompDrivetrainEncoderRatio =
+    (15.0 / 50.0) /*output reduction*/ * (36.0 / 24.0) /*encoder gears*/;
+const double kCompLowGearRatio = 14.0 / 60.0 * 15.0 / 50.0;
+const double kCompHighGearRatio = 30.0 / 44.0 * 15.0 / 50.0;
+
+const double kPracticeDrivetrainEncoderRatio =
+    (17.0 / 50.0) /*output reduction*/ * (64.0 / 24.0) /*encoder gears*/;
+const double kPracticeLowGearRatio = 16.0 / 60.0 * 19.0 / 50.0;
+const double kPracticeHighGearRatio = 28.0 / 48.0 * 19.0 / 50.0;
+
+const ShifterHallEffect kCompLeftDriveShifter{0.83, 2.32, 1.2, 1.0};
+const ShifterHallEffect kCompRightDriveShifter{0.865, 2.375, 1.2, 1.0};
+
+const ShifterHallEffect kPracticeLeftDriveShifter{2.082283, 0.834433, 0.60,
+                                                  0.47};
+const ShifterHallEffect kPracticeRightDriveShifter{2.070124, 0.838993, 0.62,
+                                                   0.55};
 
 const Values *DoGetValues() {
   uint16_t team = ::aos::network::GetTeamNumber();
@@ -95,7 +115,14 @@
                         kAngleAdjustZeroingSpeed,
                         kAngleAdjustZeroingOffSpeed,
                         kCompAngleAdjustDeadband,
-                        kCompDrivetrainGearboxPinion,
+                        kCompDrivetrainEncoderRatio,
+                        kCompLowGearRatio,
+                        kCompHighGearRatio,
+                        kCompLeftDriveShifter,
+                        kCompRightDriveShifter,
+                        true,
+                        control_loops::MakeVClutchDrivetrainLoop,
+                        control_loops::MakeClutchDrivetrainLoop,
                         kCompCameraCenter};
       break;
     case kPracticeTeamNumber:
@@ -116,7 +143,14 @@
                         kAngleAdjustZeroingSpeed,
                         kAngleAdjustZeroingOffSpeed,
                         kPracticeAngleAdjustDeadband,
-                        kPracticeDrivetrainGearboxPinion,
+                        kPracticeDrivetrainEncoderRatio,
+                        kPracticeLowGearRatio,
+                        kPracticeHighGearRatio,
+                        kPracticeLeftDriveShifter,
+                        kPracticeRightDriveShifter,
+                        false,
+                        control_loops::MakeVDogDrivetrainLoop,
+                        control_loops::MakeDogDrivetrainLoop,
                         kPracticeCameraCenter};
       break;
     default:
diff --git a/frc971/constants.h b/frc971/constants.h
index 0c9bfdd..838bb35 100644
--- a/frc971/constants.h
+++ b/frc971/constants.h
@@ -3,15 +3,26 @@
 
 #include <stdint.h>
 
+#include "frc971/control_loops/state_feedback_loop.h"
+
 namespace frc971 {
 namespace constants {
 
 // Has all of the numbers that change for both robots and makes it easy to
 // retrieve the values for the current one.
 
-const uint16_t kCompTeamNumber = 5971;
+const uint16_t kCompTeamNumber = 8971;
 const uint16_t kPracticeTeamNumber = 971;
 
+// Contains the voltages for an analog hall effect sensor on a shifter.
+struct ShifterHallEffect {
+  // The numbers to use for scaling raw voltages to 0-1.
+  double high, low;
+
+  // The numbers for when the dog is clear of each gear.
+  double clear_high, clear_low;
+};
+
 // This structure contains current values for all of the things that change.
 struct Values {
   // Wrist hall effect positive and negative edges.
@@ -54,8 +65,20 @@
   // Deadband voltage.
   double angle_adjust_deadband;
 
-  // The number of teeth on the pinion that drives the drivetrain wheels.
-  int drivetrain_gearbox_pinion;
+  // The ratio from the encoder shaft to the drivetrain wheels.
+  double drivetrain_encoder_ratio;
+
+  // The gear ratios from motor shafts to the drivetrain wheels for high and low
+  // gear.
+  double low_gear_ratio;
+  double high_gear_ratio;
+
+  ShifterHallEffect left_drive, right_drive;
+
+  bool clutch_transmission;
+
+  ::std::function<StateFeedbackLoop<2, 2, 2>()> make_v_drivetrain_loop;
+  ::std::function<StateFeedbackLoop<4, 2, 2>()> make_drivetrain_loop;
 
   // How many pixels off center the vertical line
   // on the camera view is.
diff --git a/frc971/control_loops/control_loops.gyp b/frc971/control_loops/control_loops.gyp
index ea09d11..94c73d0 100644
--- a/frc971/control_loops/control_loops.gyp
+++ b/frc971/control_loops/control_loops.gyp
@@ -5,7 +5,6 @@
       'type': 'static_library',
       'sources': [
         #'state_feedback_loop.h'
-        #'StateFeedbackLoop.h'
       ],
       'dependencies': [
         '<(EXTERNALS):eigen',
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
index 548113e..921fab0 100644
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ b/frc971/control_loops/drivetrain/drivetrain.cc
@@ -4,14 +4,18 @@
 #include <sched.h>
 #include <cmath>
 #include <memory>
+#include "Eigen/Dense"
 
 #include "aos/common/logging/logging.h"
 #include "aos/common/queue.h"
+#include "aos/controls/polytope.h"
+#include "aos/common/commonmath.h"
 #include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/drivetrain/drivetrain_motor_plant.h"
+#include "frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h"
 #include "frc971/control_loops/drivetrain/drivetrain.q.h"
 #include "frc971/queues/GyroAngle.q.h"
 #include "frc971/queues/Piston.q.h"
+#include "frc971/constants.h"
 
 using frc971::sensors::gyro;
 
@@ -21,10 +25,58 @@
 // Width of the robot.
 const double width = 22.0 / 100.0 * 2.54;
 
+Eigen::Matrix<double, 2, 1> CoerceGoal(aos::controls::HPolytope<2> &region,
+                                       const Eigen::Matrix<double, 1, 2> &K,
+                                       double w,
+                                       const Eigen::Matrix<double, 2, 1> &R) {
+  if (region.IsInside(R)) {
+    return R;
+  }
+  Eigen::Matrix<double, 2, 1> parallel_vector;
+  Eigen::Matrix<double, 2, 1> perpendicular_vector;
+  perpendicular_vector = K.transpose().normalized();
+  parallel_vector << perpendicular_vector(1, 0), -perpendicular_vector(0, 0);
+
+  aos::controls::HPolytope<1> t_poly(
+      region.H() * parallel_vector,
+      region.k() - region.H() * perpendicular_vector * w);
+
+  Eigen::Matrix<double, 1, Eigen::Dynamic> vertices = t_poly.Vertices();
+  if (vertices.innerSize() > 0) {
+    double min_distance_sqr = 0;
+    Eigen::Matrix<double, 2, 1> closest_point;
+    for (int i = 0; i < vertices.innerSize(); i++) {
+      Eigen::Matrix<double, 2, 1> point;
+      point = parallel_vector * vertices(0, i) + perpendicular_vector * w;
+      const double length = (R - point).squaredNorm();
+      if (i == 0 || length < min_distance_sqr) {
+        closest_point = point;
+        min_distance_sqr = length;
+      }
+    }
+    return closest_point;
+  } else {
+    Eigen::Matrix<double, 2, Eigen::Dynamic> region_vertices =
+        region.Vertices();
+    double min_distance;
+    int closest_i = 0;
+    for (int i = 0; i < region_vertices.outerSize(); i++) {
+      const double length = ::std::abs(
+          (perpendicular_vector.transpose() * (region_vertices.col(i)))(0, 0));
+      if (i == 0 || length < min_distance) {
+        closest_i = i;
+        min_distance = length;
+      }
+    }
+    return region_vertices.col(closest_i);
+  }
+}
+
 class DrivetrainMotorsSS {
  public:
-  DrivetrainMotorsSS ()
-      : loop_(new StateFeedbackLoop<4, 2, 2>(MakeDrivetrainLoop())) {
+  DrivetrainMotorsSS()
+      : loop_(new StateFeedbackLoop<4, 2, 2>(
+            constants::GetValues().make_drivetrain_loop())) {
     _offset = 0;
     _integral_offset = 0;
     _left_goal = 0.0;
@@ -47,14 +99,14 @@
       double left, double right, double gyro, bool control_loop_driving) {
     // Decay the offset quickly because this gyro is great.
     _offset = (0.25) * (right - left - gyro * width) / 2.0 + 0.75 * _offset;
-    const double angle_error = (_right_goal - _left_goal) / width - (_raw_right - _offset - _raw_left - _offset) / width;
+    //const double angle_error = (_right_goal - _left_goal) / width - (_raw_right - _offset - _raw_left - _offset) / width;
     // TODO(aschuh): Add in the gyro.
     _integral_offset = 0.0;
     _offset = 0.0;
     _gyro = gyro;
     _control_loop_driving = control_loop_driving;
     SetRawPosition(left, right);
-    LOG(DEBUG, "Left %f->%f Right %f->%f Gyro %f aerror %f ioff %f\n", left + _offset, _left_goal, right - _offset, _right_goal, gyro, angle_error, _integral_offset);
+    //LOG(DEBUG, "Left %f->%f Right %f->%f Gyro %f aerror %f ioff %f\n", left + _offset, _left_goal, right - _offset, _right_goal, gyro, angle_error, _integral_offset);
   }
 
   void Update(bool update_observer, bool stop_motors) {
@@ -86,62 +138,485 @@
   bool _control_loop_driving;
 };
 
+class PolyDrivetrain {
+ public:
+
+  enum Gear {
+    HIGH,
+    LOW,
+    SHIFTING_UP,
+    SHIFTING_DOWN
+  };
+  // Stall Torque in N m
+  static constexpr double kStallTorque = 2.42;
+  // Stall Current in Amps
+  static constexpr double kStallCurrent = 133;
+  // 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 = 6.4;
+  // 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.617998644 / 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>(
+            constants::GetValues().make_v_drivetrain_loop())),
+        left_cim_(new StateFeedbackLoop<1, 1, 1>(MakeCIMLoop())),
+        right_cim_(new StateFeedbackLoop<1, 1, 1>(MakeCIMLoop())),
+        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 bool IsInGear(Gear gear) { return gear == LOW || gear == HIGH; }
+
+  static double MotorSpeed(double shifter_position, double velocity) {
+    // TODO(austin): G_high, G_low and kWheelRadius
+    if (shifter_position > 0.57) {
+      return velocity / constants::GetValues().high_gear_ratio / kWheelRadius;
+    } else {
+      return velocity / constants::GetValues().low_gear_ratio / kWheelRadius;
+    }
+  }
+
+  Gear ComputeGear(double velocity, Gear current) {
+    const double low_omega = MotorSpeed(0, ::std::abs(velocity));
+    const double high_omega = MotorSpeed(1.0, ::std::abs(velocity));
+
+    double high_torque = ((12.0 - high_omega / Kv) * Kt / kR);
+    double low_torque = ((12.0 - low_omega / Kv) * Kt / kR);
+    double high_power = high_torque * high_omega;
+    double low_power = low_torque * low_omega;
+
+    // TODO(aschuh): Do this right!
+    if ((current == HIGH || high_power > low_power + 160) &&
+        ::std::abs(velocity) > 0.14) {
+      return HIGH;
+    } else {
+      return LOW;
+    }
+  }
+
+  void SetGoal(double wheel, double throttle, bool quickturn, bool highgear) {
+    const double kWheelNonLinearity = 0.3;
+    // Apply a sin function that's scaled to make it feel better.
+    const double angular_range = M_PI_2 * kWheelNonLinearity;
+    wheel_ = sin(angular_range * wheel) / sin(angular_range);
+    wheel_ = sin(angular_range * wheel_) / sin(angular_range);
+    quickturn_ = quickturn;
+
+    static const double kThrottleDeadband = 0.05;
+    if (::std::abs(throttle) < kThrottleDeadband) {
+      throttle_ = 0;
+    } else {
+      throttle_ = copysign((::std::abs(throttle) - kThrottleDeadband) /
+                           (1.0 - kThrottleDeadband), throttle);
+    }
+
+    // TODO(austin): Fix the upshift logic to include states.
+    Gear requested_gear;
+    if (false) {
+      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_;
+
+      Gear left_requested = ComputeGear(current_left_velocity, left_gear_);
+      Gear right_requested = ComputeGear(current_right_velocity, right_gear_);
+      requested_gear =
+          (left_requested == HIGH || right_requested == HIGH) ? HIGH : LOW;
+    } else {
+      requested_gear = highgear ? HIGH : LOW;
+    }
+
+    const Gear shift_up =
+        constants::GetValues().clutch_transmission ? HIGH : SHIFTING_UP;
+    const Gear shift_down =
+        constants::GetValues().clutch_transmission ? LOW : SHIFTING_DOWN;
+
+    if (left_gear_ != requested_gear) {
+      if (IsInGear(left_gear_)) {
+        if (requested_gear == HIGH) {
+          left_gear_ = shift_up;
+        } else {
+          left_gear_ = shift_down;
+        }
+      } else {
+        if (requested_gear == HIGH && left_gear_ == SHIFTING_DOWN) {
+          left_gear_ = SHIFTING_UP;
+        } else if (requested_gear == LOW && left_gear_ == SHIFTING_UP) {
+          left_gear_ = SHIFTING_DOWN;
+        }
+      }
+    }
+    if (right_gear_ != requested_gear) {
+      if (IsInGear(right_gear_)) {
+        if (requested_gear == HIGH) {
+          right_gear_ = shift_up;
+        } else {
+          right_gear_ = shift_down;
+        }
+      } else {
+        if (requested_gear == HIGH && right_gear_ == SHIFTING_DOWN) {
+          right_gear_ = SHIFTING_UP;
+        } else if (requested_gear == LOW && right_gear_ == SHIFTING_UP) {
+          right_gear_ = SHIFTING_DOWN;
+        }
+      }
+    }
+  }
+  void SetPosition(const Drivetrain::Position *position) {
+    if (position == NULL) {
+      ++stale_count_;
+    } else {
+      last_position_ = position_;
+      position_ = *position;
+      position_time_delta_ = (stale_count_ + 1) * 0.01;
+      stale_count_ = 0;
+    }
+
+    if (position) {
+      // Switch to the correct controller.
+      // TODO(austin): Un-hard code 0.57
+      if (position->left_shifter_position < 0.57) {
+        if (position->right_shifter_position < 0.57 || right_gear_ == LOW) {
+          LOG(DEBUG, "Loop Left low, Right low\n");
+          loop_->set_controller_index(0);
+        } else {
+          LOG(DEBUG, "Loop Left low, Right high\n");
+          loop_->set_controller_index(1);
+        }
+      } else {
+        if (position->right_shifter_position < 0.57 || left_gear_ == LOW) {
+          LOG(DEBUG, "Loop Left high, Right low\n");
+          loop_->set_controller_index(2);
+        } else {
+          LOG(DEBUG, "Loop Left high, Right high\n");
+          loop_->set_controller_index(3);
+        }
+      }
+      switch (left_gear_) {
+        case LOW:
+          LOG(DEBUG, "Left is in low\n");
+          break;
+        case HIGH:
+          LOG(DEBUG, "Left is in high\n");
+          break;
+        case SHIFTING_UP:
+          LOG(DEBUG, "Left is shifting up\n");
+          break;
+        case SHIFTING_DOWN:
+          LOG(DEBUG, "Left is shifting down\n");
+          break;
+      }
+      switch (right_gear_) {
+        case LOW:
+          LOG(DEBUG, "Right is in low\n");
+          break;
+        case HIGH:
+          LOG(DEBUG, "Right is in high\n");
+          break;
+        case SHIFTING_UP:
+          LOG(DEBUG, "Right is shifting up\n");
+          break;
+        case SHIFTING_DOWN:
+          LOG(DEBUG, "Right is shifting down\n");
+          break;
+      }
+      // TODO(austin): Constants.
+      if (position->left_shifter_position > 0.9 && left_gear_ == SHIFTING_UP) {
+        left_gear_ = HIGH;
+      }
+      if (position->left_shifter_position < 0.1 && left_gear_ == SHIFTING_DOWN) {
+        left_gear_ = LOW;
+      }
+      if (position->right_shifter_position > 0.9 && right_gear_ == SHIFTING_UP) {
+        right_gear_ = HIGH;
+      }
+      if (position->right_shifter_position < 0.1 && right_gear_ == SHIFTING_DOWN) {
+        right_gear_ = LOW;
+      }
+    }
+  }
+
+  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(position_.left_shifter_position, current_left_velocity);
+    const double right_motor_speed =
+        MotorSpeed(position_.right_shifter_position, current_right_velocity);
+
+    // Reset the CIM model to the current conditions to be ready for when we shift.
+    if (IsInGear(left_gear_)) {
+      left_cim_->X_hat(0, 0) = left_motor_speed;
+      LOG(DEBUG, "Setting left CIM to %f at robot speed %f\n", left_motor_speed,
+          current_left_velocity);
+    }
+    if (IsInGear(right_gear_)) {
+      right_cim_->X_hat(0, 0) = right_motor_speed;
+      LOG(DEBUG, "Setting right CIM to %f at robot speed %f\n",
+          right_motor_speed, current_right_velocity);
+    }
+    LOG(DEBUG, "robot speed l=%f r=%f\n", current_left_velocity,
+        current_right_velocity);
+
+    if (IsInGear(left_gear_) && IsInGear(right_gear_)) {
+      // 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;
+
+      // Integrate velocity to get the position.
+      // This position is used to get integral control.
+      loop_->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_->R = 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_->U[i] = ::aos::Clip(U_ideal[i], -12, 12);
+      }
+
+      // TODO(austin): Model this better.
+      // TODO(austin): Feed back?
+      loop_->X_hat = loop_->A() * loop_->X_hat + loop_->B() * loop_->U;
+    } else {
+      // Any motor is not in gear.  Speed match.
+      ::Eigen::Matrix<double, 1, 1> R_left;
+      R_left(0, 0) = left_motor_speed;
+      const double wiggle = (static_cast<double>((counter_ % 4) / 2) - 0.5) * 3.5;
+
+      loop_->U(0, 0) =
+          ::aos::Clip((R_left / Kv)(0, 0) + wiggle, -position_.battery_voltage,
+                      position_.battery_voltage);
+      right_cim_->X_hat = right_cim_->A() * right_cim_->X_hat +
+                          right_cim_->B() * loop_->U(0, 0);
+
+      ::Eigen::Matrix<double, 1, 1> R_right;
+      R_right(0, 0) = right_motor_speed;
+      loop_->U(1, 0) =
+          ::aos::Clip((R_right / Kv)(0, 0) + wiggle, -position_.battery_voltage,
+                      position_.battery_voltage);
+      right_cim_->X_hat = right_cim_->A() * right_cim_->X_hat +
+                          right_cim_->B() * loop_->U(1, 0);
+      loop_->U *= 12.0 / position_.battery_voltage;
+    }
+  }
+
+  void SendMotors(Drivetrain::Output *output) {
+    LOG(DEBUG, "left pwm: %f right pwm: %f wheel: %f throttle: %f\n",
+        loop_->U(0, 0), loop_->U(1, 0), wheel_, throttle_);
+    if (output != NULL) {
+      output->left_voltage = loop_->U(0, 0);
+      output->right_voltage = loop_->U(1, 0);
+    }
+    // Go in high gear if anything wants to be in high gear.
+    // TODO(austin): Seperate these.
+    if (left_gear_ == HIGH || left_gear_ == SHIFTING_UP ||
+        right_gear_ == HIGH || right_gear_ == SHIFTING_UP) {
+      shifters.MakeWithBuilder().set(false).Send();
+    } else {
+      shifters.MakeWithBuilder().set(true).Send();
+    }
+  }
+
+ private:
+  const ::aos::controls::HPolytope<2> U_Poly_;
+
+  ::std::unique_ptr<StateFeedbackLoop<2, 2, 2>> loop_;
+  ::std::unique_ptr<StateFeedbackLoop<1, 1, 1>> left_cim_;
+  ::std::unique_ptr<StateFeedbackLoop<1, 1, 1>> right_cim_;
+
+  const double ttrust_;
+  double wheel_;
+  double throttle_;
+  bool quickturn_;
+  int stale_count_;
+  double position_time_delta_;
+  Gear left_gear_;
+  Gear right_gear_;
+  Drivetrain::Position last_position_;
+  Drivetrain::Position position_;
+  int counter_;
+};
+
+
 class DrivetrainMotorsOL {
  public:
   DrivetrainMotorsOL() {
     _old_wheel = 0.0;
-    _wheel = 0.0;
-    _throttle = 0.0;
-    _quickturn = false;
-    _highgear = true;
+    wheel_ = 0.0;
+    throttle_ = 0.0;
+    quickturn_ = false;
+    highgear_ = true;
     _neg_inertia_accumulator = 0.0;
     _left_pwm = 0.0;
     _right_pwm = 0.0;
   }
   void SetGoal(double wheel, double throttle, bool quickturn, bool highgear) {
-    _wheel = wheel;
-    _throttle = throttle;
-    _quickturn = quickturn;
-    _highgear = highgear;
+    wheel_ = wheel;
+    throttle_ = throttle;
+    quickturn_ = quickturn;
+    highgear_ = highgear;
     _left_pwm = 0.0;
     _right_pwm = 0.0;
   }
-  void Update(void) {
+  void Update() {
     double overPower;
     float sensitivity = 1.7;
     float angular_power;
     float linear_power;
     double wheel;
 
-    double neg_inertia = _wheel - _old_wheel;
-    _old_wheel = _wheel;
+    double neg_inertia = wheel_ - _old_wheel;
+    _old_wheel = wheel_;
 
     double wheelNonLinearity;
-    if (_highgear) {
+    if (highgear_) {
       wheelNonLinearity = 0.1;  // used to be csvReader->TURN_NONLIN_HIGH
       // Apply a sin function that's scaled to make it feel better.
       const double angular_range = M_PI / 2.0 * wheelNonLinearity;
-      wheel = sin(angular_range * _wheel) / sin(angular_range);
+      wheel = sin(angular_range * wheel_) / sin(angular_range);
       wheel = sin(angular_range * wheel) / sin(angular_range);
     } else {
       wheelNonLinearity = 0.2;  // used to be csvReader->TURN_NONLIN_LOW
       // Apply a sin function that's scaled to make it feel better.
       const double angular_range = M_PI / 2.0 * wheelNonLinearity;
-      wheel = sin(angular_range * _wheel) / sin(angular_range);
+      wheel = sin(angular_range * wheel_) / sin(angular_range);
       wheel = sin(angular_range * wheel) / sin(angular_range);
       wheel = sin(angular_range * wheel) / sin(angular_range);
     }
 
     static const double kThrottleDeadband = 0.05;
-    if (::std::abs(_throttle) < kThrottleDeadband) {
-      _throttle = 0;
+    if (::std::abs(throttle_) < kThrottleDeadband) {
+      throttle_ = 0;
     } else {
-      _throttle = copysign((::std::abs(_throttle) - kThrottleDeadband) /
-                           (1.0 - kThrottleDeadband), _throttle);
+      throttle_ = copysign((::std::abs(throttle_) - kThrottleDeadband) /
+                           (1.0 - kThrottleDeadband), throttle_);
     }
 
     double neg_inertia_scalar;
-    if (_highgear) {
+    if (highgear_) {
       neg_inertia_scalar = 8.0;  // used to be csvReader->NEG_INTERTIA_HIGH
       sensitivity = 1.22; // used to be csvReader->SENSE_HIGH
     } else {
@@ -168,9 +643,9 @@
       _neg_inertia_accumulator = 0;
     }
 
-    linear_power = _throttle;
+    linear_power = throttle_;
 
-    if (_quickturn) {
+    if (quickturn_) {
       double qt_angular_power = wheel;
       if (::std::abs(linear_power) < 0.2) {
         if (qt_angular_power > 1) qt_angular_power = 1.0;
@@ -179,7 +654,7 @@
         qt_angular_power = 0.0;
       }
       overPower = 1.0;
-      if (_highgear) {
+      if (highgear_) {
         sensitivity = 1.0;
       } else {
         sensitivity = 1.0;
@@ -187,7 +662,7 @@
       angular_power = wheel;
     } else {
       overPower = 0.0;
-      angular_power = ::std::abs(_throttle) * wheel * sensitivity;
+      angular_power = ::std::abs(throttle_) * wheel * sensitivity;
     }
 
     _right_pwm = _left_pwm = linear_power;
@@ -211,12 +686,12 @@
 
   void SendMotors(Drivetrain::Output *output) {
     LOG(DEBUG, "left pwm: %f right pwm: %f wheel: %f throttle: %f\n",
-        _left_pwm, _right_pwm, _wheel, _throttle);
+        _left_pwm, _right_pwm, wheel_, throttle_);
     if (output) {
       output->left_voltage = _left_pwm * 12.0;
       output->right_voltage = _right_pwm * 12.0;
     }
-    if (_highgear) {
+    if (highgear_) {
       shifters.MakeWithBuilder().set(false).Send();
     } else {
       shifters.MakeWithBuilder().set(true).Send();
@@ -225,10 +700,10 @@
 
  private:
   double _old_wheel;
-  double _wheel;
-  double _throttle;
-  bool _quickturn;
-  bool _highgear;
+  double wheel_;
+  double throttle_;
+  bool quickturn_;
+  bool highgear_;
   double _neg_inertia_accumulator;
   double _left_pwm;
   double _right_pwm;
@@ -240,10 +715,10 @@
                                   Drivetrain::Status * /*status*/) {
   // TODO(aschuh): These should be members of the class.
   static DrivetrainMotorsSS dt_closedloop;
-  static DrivetrainMotorsOL dt_openloop;
+  static PolyDrivetrain dt_openloop;
 
   bool bad_pos = false;
-  if (position == NULL) {
+  if (position == nullptr) {
     LOG(WARNING, "no position\n");
     bad_pos = true;
   }
@@ -257,20 +732,20 @@
   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_closedloop.SetGoal(left_goal, goal->left_velocity_goal, right_goal,
+                        goal->right_velocity_goal);
   if (!bad_pos) {
     const double left_encoder = position->left_encoder;
     const double right_encoder = position->right_encoder;
     if (gyro.FetchLatest()) {
-      dt_closedloop.SetPosition(left_encoder, right_encoder,
-          gyro->angle, control_loop_driving);
+      dt_closedloop.SetPosition(left_encoder, right_encoder, gyro->angle,
+                                control_loop_driving);
     } else {
       dt_closedloop.SetRawPosition(left_encoder, right_encoder);
     }
   }
+  dt_openloop.SetPosition(position);
   dt_closedloop.Update(position, output == NULL);
-  //dt_closedloop.PrintMotors();
   dt_openloop.SetGoal(wheel, throttle, quickturn, highgear);
   dt_openloop.Update();
   if (control_loop_driving) {
diff --git a/frc971/control_loops/drivetrain/drivetrain.gyp b/frc971/control_loops/drivetrain/drivetrain.gyp
index 1776056..53bb16c 100644
--- a/frc971/control_loops/drivetrain/drivetrain.gyp
+++ b/frc971/control_loops/drivetrain/drivetrain.gyp
@@ -18,20 +18,38 @@
       'includes': ['../../../aos/build/queues.gypi'],
     },
     {
+      'target_name': 'polydrivetrain_plants',
+      'type': 'static_library',
+      'sources': [
+        'polydrivetrain_dog_motor_plant.cc',
+        'polydrivetrain_clutch_motor_plant.cc',
+        'drivetrain_dog_motor_plant.cc',
+        'drivetrain_clutch_motor_plant.cc',
+      ],
+      'dependencies': [
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+      'export_dependent_settings': [
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+    },
+    {
       'target_name': 'drivetrain_lib',
       'type': 'static_library',
       'sources': [
         'drivetrain.cc',
-        'drivetrain_motor_plant.cc',
+        'polydrivetrain_cim_plant.cc',
       ],
       'dependencies': [
         'drivetrain_loop',
         '<(AOS)/common/common.gyp:controls',
         '<(DEPTH)/frc971/frc971.gyp:constants',
+        '<(DEPTH)/aos/build/externals.gyp:libcdd',
         '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
         '<(DEPTH)/frc971/queues/queues.gyp:queues',
       ],
       'export_dependent_settings': [
+        '<(DEPTH)/aos/build/externals.gyp:libcdd',
         '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
         '<(AOS)/common/common.gyp:controls',
         'drivetrain_loop',
diff --git a/frc971/control_loops/drivetrain/drivetrain.h b/frc971/control_loops/drivetrain/drivetrain.h
index 244f3e5..249de70 100644
--- a/frc971/control_loops/drivetrain/drivetrain.h
+++ b/frc971/control_loops/drivetrain/drivetrain.h
@@ -1,12 +1,21 @@
 #ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
 #define FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
 
+#include "Eigen/Dense"
+
+#include "aos/controls/polytope.h"
 #include "aos/common/control_loop/ControlLoop.h"
+#include "aos/controls/polytope.h"
 #include "frc971/control_loops/drivetrain/drivetrain.q.h"
 
 namespace frc971 {
 namespace control_loops {
 
+Eigen::Matrix<double, 2, 1> CoerceGoal(aos::controls::HPolytope<2> &region,
+                                       const Eigen::Matrix<double, 1, 2> &K,
+                                       double w,
+                                       const Eigen::Matrix<double, 2, 1> &R);
+
 class DrivetrainLoop
     : public aos::control_loops::ControlLoop<control_loops::Drivetrain, true, false> {
  public:
@@ -15,7 +24,9 @@
   explicit DrivetrainLoop(
       control_loops::Drivetrain *my_drivetrain = &control_loops::drivetrain)
       : aos::control_loops::ControlLoop<control_loops::Drivetrain, true, false>(
-          my_drivetrain) {}
+          my_drivetrain) {
+    ::aos::controls::HPolytope<0>::Init();
+  }
 
  protected:
   // Executes one cycle of the control loop.
diff --git a/frc971/control_loops/drivetrain/drivetrain.q b/frc971/control_loops/drivetrain/drivetrain.q
index 2085eb8..1dcc947 100644
--- a/frc971/control_loops/drivetrain/drivetrain.q
+++ b/frc971/control_loops/drivetrain/drivetrain.q
@@ -20,6 +20,9 @@
   message Position {
     double left_encoder;
     double right_encoder;
+    double left_shifter_position;
+    double right_shifter_position;
+    double battery_voltage;
   };
 
   message Output {
diff --git a/frc971/control_loops/drivetrain/drivetrain_clutch_motor_plant.cc b/frc971/control_loops/drivetrain/drivetrain_clutch_motor_plant.cc
new file mode 100644
index 0000000..b3aa088
--- /dev/null
+++ b/frc971/control_loops/drivetrain/drivetrain_clutch_motor_plant.cc
@@ -0,0 +1,47 @@
+#include "frc971/control_loops/drivetrain/drivetrain_clutch_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeClutchDrivetrainPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.00876671940282, 0.0, 0.000204905465153, 0.0, 0.764245148008, 0.0, 0.0373841350548, 0.0, 0.000204905465153, 1.0, 0.00876671940282, 0.0, 0.0373841350548, 0.0, 0.764245148008;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 0.000157874070659, -2.62302512161e-05, 0.0301793267864, -0.00478559834045, -2.62302512161e-05, 0.000157874070659, -0.00478559834045, 0.0301793267864;
+  Eigen::Matrix<double, 2, 4> C;
+  C << 1, 0, 0, 0, 0, 0, 1, 0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 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<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<4, 2, 2> MakeClutchDrivetrainController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.60424514801, 0.0373841350548, 53.4463554671, 4.58647914599, 0.0373841350548, 1.60424514801, 4.58647914599, 53.4463554671;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 292.330461448, 10.4890095334, -85.5980253252, -0.517234397951, -58.0206391358, -1.5636023242, 153.384904309, 5.5616531565;
+  return StateFeedbackController<4, 2, 2>(L, K, MakeClutchDrivetrainPlantCoefficients());
+}
+
+StateFeedbackPlant<4, 2, 2> MakeClutchDrivetrainPlant() {
+  ::std::vector<StateFeedbackPlantCoefficients<4, 2, 2> *> plants(1);
+  plants[0] = new StateFeedbackPlantCoefficients<4, 2, 2>(MakeClutchDrivetrainPlantCoefficients());
+  return StateFeedbackPlant<4, 2, 2>(plants);
+}
+
+StateFeedbackLoop<4, 2, 2> MakeClutchDrivetrainLoop() {
+  ::std::vector<StateFeedbackController<4, 2, 2> *> controllers(1);
+  controllers[0] = new StateFeedbackController<4, 2, 2>(MakeClutchDrivetrainController());
+  return StateFeedbackLoop<4, 2, 2>(controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/frc971/control_loops/drivetrain/drivetrain_clutch_motor_plant.h b/frc971/control_loops/drivetrain/drivetrain_clutch_motor_plant.h
new file mode 100644
index 0000000..e9444e6
--- /dev/null
+++ b/frc971/control_loops/drivetrain/drivetrain_clutch_motor_plant.h
@@ -0,0 +1,20 @@
+#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_CLUTCH_MOTOR_PLANT_H_
+#define FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_CLUTCH_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeClutchDrivetrainPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeClutchDrivetrainController();
+
+StateFeedbackPlant<4, 2, 2> MakeClutchDrivetrainPlant();
+
+StateFeedbackLoop<4, 2, 2> MakeClutchDrivetrainLoop();
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_CLUTCH_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.cc b/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
new file mode 100644
index 0000000..7822056
--- /dev/null
+++ b/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
@@ -0,0 +1,47 @@
+#include "frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDogDrivetrainPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.00923787174605, 0.0, 0.000131162317098, 0.0, 0.851672729447, 0.0, 0.0248457251406, 0.0, 0.000131162317098, 1.0, 0.00923787174605, 0.0, 0.0248457251406, 0.0, 0.851672729447;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 0.000126364935405, -2.17474127771e-05, 0.0245934537462, -0.00411955394149, -2.17474127771e-05, 0.000126364935405, -0.00411955394149, 0.0245934537462;
+  Eigen::Matrix<double, 2, 4> C;
+  C << 1, 0, 0, 0, 0, 0, 1, 0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 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<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<4, 2, 2> MakeDogDrivetrainController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.69167272945, 0.0248457251406, 64.4706646869, 3.2355304474, 0.0248457251406, 1.69167272945, 3.2355304474, 64.4706646869;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 248.918529922, 14.4460993245, 41.6953764051, 3.43594323497, 41.6953764051, 3.43594323497, 248.918529922, 14.4460993245;
+  return StateFeedbackController<4, 2, 2>(L, K, MakeDogDrivetrainPlantCoefficients());
+}
+
+StateFeedbackPlant<4, 2, 2> MakeDogDrivetrainPlant() {
+  ::std::vector<StateFeedbackPlantCoefficients<4, 2, 2> *> plants(1);
+  plants[0] = new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDogDrivetrainPlantCoefficients());
+  return StateFeedbackPlant<4, 2, 2>(plants);
+}
+
+StateFeedbackLoop<4, 2, 2> MakeDogDrivetrainLoop() {
+  ::std::vector<StateFeedbackController<4, 2, 2> *> controllers(1);
+  controllers[0] = new StateFeedbackController<4, 2, 2>(MakeDogDrivetrainController());
+  return StateFeedbackLoop<4, 2, 2>(controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h b/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h
new file mode 100644
index 0000000..ba3d584
--- /dev/null
+++ b/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h
@@ -0,0 +1,20 @@
+#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
+#define FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDogDrivetrainPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDogDrivetrainController();
+
+StateFeedbackPlant<4, 2, 2> MakeDogDrivetrainPlant();
+
+StateFeedbackLoop<4, 2, 2> MakeDogDrivetrainLoop();
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
index d15de44..0f8c87e 100644
--- a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -5,10 +5,12 @@
 #include "gtest/gtest.h"
 #include "aos/common/queue.h"
 #include "aos/common/queue_testutils.h"
+#include "aos/controls/polytope.h"
+
 #include "frc971/control_loops/drivetrain/drivetrain.q.h"
 #include "frc971/control_loops/drivetrain/drivetrain.h"
 #include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/drivetrain/drivetrain_motor_plant.h"
+#include "frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
 #include "frc971/queues/GyroAngle.q.h"
 
 
@@ -18,15 +20,27 @@
 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 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>(MakeDrivetrainPlant())),
+            new StateFeedbackPlant<4, 2, 2>(MakeDogDrivetrainPlant())),
         my_drivetrain_loop_(".frc971.control_loops.drivetrain",
                        0x8a8dde77, ".frc971.control_loops.drivetrain.goal",
                        ".frc971.control_loops.drivetrain.position",
@@ -182,6 +196,108 @@
   VerifyNearGoal();
 }
 
+::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 frc971
diff --git a/frc971/control_loops/drivetrain/drivetrain_motor_plant.cc b/frc971/control_loops/drivetrain/drivetrain_motor_plant.cc
deleted file mode 100644
index e543c9f..0000000
--- a/frc971/control_loops/drivetrain/drivetrain_motor_plant.cc
+++ /dev/null
@@ -1,47 +0,0 @@
-#include "frc971/control_loops/drivetrain/drivetrain_motor_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainPlantCoefficients() {
-  Eigen::Matrix<double, 4, 4> A;
-  A << 1.0, 0.00931379160739, 0.0, 4.70184876909e-06, 0.0, 0.865971883056, 0.0, 0.000895808426591, 0.0, 4.70184876909e-06, 1.0, 0.00931379160739, 0.0, 0.000895808426591, 0.0, 0.865971883056;
-  Eigen::Matrix<double, 4, 2> B;
-  B << 0.000126707931029, -8.6819330098e-07, 0.0247482041615, -0.000165410440259, -8.6819330098e-07, 0.000126707931029, -0.000165410440259, 0.0247482041615;
-  Eigen::Matrix<double, 2, 4> C;
-  C << 1, 0, 0, 0, 0, 0, 1, 0;
-  Eigen::Matrix<double, 2, 2> D;
-  D << 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<4, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainController() {
-  Eigen::Matrix<double, 4, 2> L;
-  L << 1.70597188306, 0.000895808426591, 66.3158545945, 0.117712892743, 0.000895808426591, 1.70597188306, 0.117712892743, 66.3158545945;
-  Eigen::Matrix<double, 2, 4> K;
-  K << 240.432225842, 14.3659115621, 1.60698530163, 0.13242189318, 1.60698530163, 0.13242189318, 240.432225842, 14.3659115621;
-  return StateFeedbackController<4, 2, 2>(L, K, MakeDrivetrainPlantCoefficients());
-}
-
-StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant() {
-  ::std::vector<StateFeedbackPlantCoefficients<4, 2, 2> *> plants(1);
-  plants[0] = new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainPlantCoefficients());
-  return StateFeedbackPlant<4, 2, 2>(plants);
-}
-
-StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop() {
-  ::std::vector<StateFeedbackController<4, 2, 2> *> controllers(1);
-  controllers[0] = new StateFeedbackController<4, 2, 2>(MakeDrivetrainController());
-  return StateFeedbackLoop<4, 2, 2>(controllers);
-}
-
-}  // namespace control_loops
-}  // namespace frc971
diff --git a/frc971/control_loops/drivetrain/drivetrain_motor_plant.h b/frc971/control_loops/drivetrain/drivetrain_motor_plant.h
deleted file mode 100644
index 2060b6f..0000000
--- a/frc971/control_loops/drivetrain/drivetrain_motor_plant.h
+++ /dev/null
@@ -1,20 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_MOTOR_PLANT_H_
-#define FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_MOTOR_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainPlantCoefficients();
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainController();
-
-StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant();
-
-StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop();
-
-}  // namespace control_loops
-}  // namespace frc971
-
-#endif  // FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.cc b/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.cc
new file mode 100644
index 0000000..1287483
--- /dev/null
+++ b/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.cc
@@ -0,0 +1,47 @@
+#include "frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<1, 1, 1> MakeCIMPlantCoefficients() {
+  Eigen::Matrix<double, 1, 1> A;
+  A << 0.614537580221;
+  Eigen::Matrix<double, 1, 1> B;
+  B << 15.9657598852;
+  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.604537580221;
+  Eigen::Matrix<double, 1, 1> K;
+  K << 0.0378646293422;
+  return StateFeedbackController<1, 1, 1>(L, K, MakeCIMPlantCoefficients());
+}
+
+StateFeedbackPlant<1, 1, 1> MakeCIMPlant() {
+  ::std::vector<StateFeedbackPlantCoefficients<1, 1, 1> *> plants(1);
+  plants[0] = new StateFeedbackPlantCoefficients<1, 1, 1>(MakeCIMPlantCoefficients());
+  return StateFeedbackPlant<1, 1, 1>(plants);
+}
+
+StateFeedbackLoop<1, 1, 1> MakeCIMLoop() {
+  ::std::vector<StateFeedbackController<1, 1, 1> *> controllers(1);
+  controllers[0] = new StateFeedbackController<1, 1, 1>(MakeCIMController());
+  return StateFeedbackLoop<1, 1, 1>(controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h b/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h
new file mode 100644
index 0000000..12b2c59
--- /dev/null
+++ b/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h
@@ -0,0 +1,20 @@
+#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
+#define FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+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 frc971
+
+#endif  // FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_clutch_motor_plant.cc b/frc971/control_loops/drivetrain/polydrivetrain_clutch_motor_plant.cc
new file mode 100644
index 0000000..82962f0
--- /dev/null
+++ b/frc971/control_loops/drivetrain/polydrivetrain_clutch_motor_plant.cc
@@ -0,0 +1,125 @@
+#include "frc971/control_loops/drivetrain/polydrivetrain_clutch_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeClutchVelocityDrivetrainLowLowPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.764245148008, 0.0373841350548, 0.0373841350548, 0.764245148008;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0301793267864, -0.00478559834045, -0.00478559834045, 0.0301793267864;
+  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> MakeClutchVelocityDrivetrainLowHighPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.763446428918, 0.00494258902788, 0.042202491067, 0.968991856576;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0302815719967, -0.00184882243178, -0.00540240320973, 0.011598890947;
+  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> MakeClutchVelocityDrivetrainHighLowPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.968991856576, 0.042202491067, 0.00494258902788, 0.763446428918;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.011598890947, -0.00540240320973, -0.00184882243178, 0.0302815719967;
+  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> MakeClutchVelocityDrivetrainHighHighPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.968881997557, 0.00555499847336, 0.00555499847336, 0.968881997557;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0116399847578, -0.0020779000091, -0.0020779000091, 0.0116399847578;
+  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> MakeClutchVelocityDrivetrainLowLowController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.744245148008, 0.0373841350548, 0.0373841350548, 0.744245148008;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 5.78417881324, 2.15594244513, 2.15594244513, 5.78417881324;
+  return StateFeedbackController<2, 2, 2>(L, K, MakeClutchVelocityDrivetrainLowLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeClutchVelocityDrivetrainLowHighController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.742469928763, 0.0421768815418, 0.0421768815418, 0.949968356732;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 5.78418649682, 2.16715237139, 6.33258809821, 32.8220766317;
+  return StateFeedbackController<2, 2, 2>(L, K, MakeClutchVelocityDrivetrainLowHighPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeClutchVelocityDrivetrainHighLowController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.954934950673, 0.00591596315544, 0.00591596315544, 0.737503334821;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 32.8220766317, 6.33258809821, 2.16715237139, 5.78418649682;
+  return StateFeedbackController<2, 2, 2>(L, K, MakeClutchVelocityDrivetrainHighLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeClutchVelocityDrivetrainHighHighController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.948881997557, 0.00555499847336, 0.00555499847336, 0.948881997557;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 32.8220767657, 6.33643373411, 6.33643373411, 32.8220767657;
+  return StateFeedbackController<2, 2, 2>(L, K, MakeClutchVelocityDrivetrainHighHighPlantCoefficients());
+}
+
+StateFeedbackPlant<2, 2, 2> MakeVClutchDrivetrainPlant() {
+  ::std::vector<StateFeedbackPlantCoefficients<2, 2, 2> *> plants(4);
+  plants[0] = new StateFeedbackPlantCoefficients<2, 2, 2>(MakeClutchVelocityDrivetrainLowLowPlantCoefficients());
+  plants[1] = new StateFeedbackPlantCoefficients<2, 2, 2>(MakeClutchVelocityDrivetrainLowHighPlantCoefficients());
+  plants[2] = new StateFeedbackPlantCoefficients<2, 2, 2>(MakeClutchVelocityDrivetrainHighLowPlantCoefficients());
+  plants[3] = new StateFeedbackPlantCoefficients<2, 2, 2>(MakeClutchVelocityDrivetrainHighHighPlantCoefficients());
+  return StateFeedbackPlant<2, 2, 2>(plants);
+}
+
+StateFeedbackLoop<2, 2, 2> MakeVClutchDrivetrainLoop() {
+  ::std::vector<StateFeedbackController<2, 2, 2> *> controllers(4);
+  controllers[0] = new StateFeedbackController<2, 2, 2>(MakeClutchVelocityDrivetrainLowLowController());
+  controllers[1] = new StateFeedbackController<2, 2, 2>(MakeClutchVelocityDrivetrainLowHighController());
+  controllers[2] = new StateFeedbackController<2, 2, 2>(MakeClutchVelocityDrivetrainHighLowController());
+  controllers[3] = new StateFeedbackController<2, 2, 2>(MakeClutchVelocityDrivetrainHighHighController());
+  return StateFeedbackLoop<2, 2, 2>(controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_clutch_motor_plant.h b/frc971/control_loops/drivetrain/polydrivetrain_clutch_motor_plant.h
new file mode 100644
index 0000000..85c87c1
--- /dev/null
+++ b/frc971/control_loops/drivetrain/polydrivetrain_clutch_motor_plant.h
@@ -0,0 +1,32 @@
+#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CLUTCH_MOTOR_PLANT_H_
+#define FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CLUTCH_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeClutchVelocityDrivetrainLowLowPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeClutchVelocityDrivetrainLowLowController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeClutchVelocityDrivetrainLowHighPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeClutchVelocityDrivetrainLowHighController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeClutchVelocityDrivetrainHighLowPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeClutchVelocityDrivetrainHighLowController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeClutchVelocityDrivetrainHighHighPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeClutchVelocityDrivetrainHighHighController();
+
+StateFeedbackPlant<2, 2, 2> MakeVClutchDrivetrainPlant();
+
+StateFeedbackLoop<2, 2, 2> MakeVClutchDrivetrainLoop();
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CLUTCH_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc b/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
new file mode 100644
index 0000000..b3d4277
--- /dev/null
+++ b/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
@@ -0,0 +1,125 @@
+#include "frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeDogVelocityDrivetrainLowLowPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.851672729447, 0.0248457251406, 0.0248457251406, 0.851672729447;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0245934537462, -0.00411955394149, -0.00411955394149, 0.0245934537462;
+  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> MakeDogVelocityDrivetrainLowHighPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.851389310398, 0.00553670185935, 0.0264939835067, 0.967000817219;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0246404461385, -0.00200815724925, -0.00439284398274, 0.0119687766843;
+  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> MakeDogVelocityDrivetrainHighLowPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.967000817219, 0.0264939835067, 0.00553670185935, 0.851389310398;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0119687766843, -0.00439284398274, -0.00200815724925, 0.0246404461385;
+  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> MakeDogVelocityDrivetrainHighHighPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.966936300149, 0.00589655754287, 0.00589655754287, 0.966936300149;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0119921769728, -0.00213867661221, -0.00213867661221, 0.0119921769728;
+  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> MakeDogVelocityDrivetrainLowLowController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.831672729447, 0.0248457251406, 0.0248457251406, 0.831672729447;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 10.7028500331, 2.80305051463, 2.80305051463, 10.7028500331;
+  return StateFeedbackController<2, 2, 2>(L, K, MakeDogVelocityDrivetrainLowLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeDogVelocityDrivetrainLowHighController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.831852326508, 0.0264837489415, 0.0264837489415, 0.946537801108;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 10.7028511964, 2.80768406175, 6.14180888507, 31.6936764099;
+  return StateFeedbackController<2, 2, 2>(L, K, MakeDogVelocityDrivetrainLowHighPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeDogVelocityDrivetrainHighLowController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.951097545753, 0.0063707209266, 0.0063707209266, 0.827292581863;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 31.6936764099, 6.14180888507, 2.80768406175, 10.7028511964;
+  return StateFeedbackController<2, 2, 2>(L, K, MakeDogVelocityDrivetrainHighLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeDogVelocityDrivetrainHighHighController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.946936300149, 0.00589655754287, 0.00589655754287, 0.946936300149;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 31.6936764663, 6.14392885659, 6.14392885659, 31.6936764663;
+  return StateFeedbackController<2, 2, 2>(L, K, MakeDogVelocityDrivetrainHighHighPlantCoefficients());
+}
+
+StateFeedbackPlant<2, 2, 2> MakeVDogDrivetrainPlant() {
+  ::std::vector<StateFeedbackPlantCoefficients<2, 2, 2> *> plants(4);
+  plants[0] = new StateFeedbackPlantCoefficients<2, 2, 2>(MakeDogVelocityDrivetrainLowLowPlantCoefficients());
+  plants[1] = new StateFeedbackPlantCoefficients<2, 2, 2>(MakeDogVelocityDrivetrainLowHighPlantCoefficients());
+  plants[2] = new StateFeedbackPlantCoefficients<2, 2, 2>(MakeDogVelocityDrivetrainHighLowPlantCoefficients());
+  plants[3] = new StateFeedbackPlantCoefficients<2, 2, 2>(MakeDogVelocityDrivetrainHighHighPlantCoefficients());
+  return StateFeedbackPlant<2, 2, 2>(plants);
+}
+
+StateFeedbackLoop<2, 2, 2> MakeVDogDrivetrainLoop() {
+  ::std::vector<StateFeedbackController<2, 2, 2> *> controllers(4);
+  controllers[0] = new StateFeedbackController<2, 2, 2>(MakeDogVelocityDrivetrainLowLowController());
+  controllers[1] = new StateFeedbackController<2, 2, 2>(MakeDogVelocityDrivetrainLowHighController());
+  controllers[2] = new StateFeedbackController<2, 2, 2>(MakeDogVelocityDrivetrainHighLowController());
+  controllers[3] = new StateFeedbackController<2, 2, 2>(MakeDogVelocityDrivetrainHighHighController());
+  return StateFeedbackLoop<2, 2, 2>(controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h b/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
new file mode 100644
index 0000000..613bff4
--- /dev/null
+++ b/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
@@ -0,0 +1,32 @@
+#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
+#define FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeDogVelocityDrivetrainLowLowPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeDogVelocityDrivetrainLowLowController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeDogVelocityDrivetrainLowHighPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeDogVelocityDrivetrainLowHighController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeDogVelocityDrivetrainHighLowPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeDogVelocityDrivetrainHighLowController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeDogVelocityDrivetrainHighHighPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeDogVelocityDrivetrainHighHighController();
+
+StateFeedbackPlant<2, 2, 2> MakeVDogDrivetrainPlant();
+
+StateFeedbackLoop<2, 2, 2> MakeVDogDrivetrainLoop();
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/index/index.cc b/frc971/control_loops/index/index.cc
index 6ac91b7..b36d517 100644
--- a/frc971/control_loops/index/index.cc
+++ b/frc971/control_loops/index/index.cc
@@ -108,7 +108,7 @@
 const /*static*/ double IndexMotor::kTransferRollerRadius = 1.25 * 0.0254 / 2;
 
 /*static*/ const int IndexMotor::kGrabbingDelay = 5;
-/*static*/ const int IndexMotor::kLiftingDelay = 2;
+/*static*/ const int IndexMotor::kLiftingDelay = 5;
 /*static*/ const int IndexMotor::kLiftingTimeout = 100;
 /*static*/ const int IndexMotor::kShootingDelay = 10;
 /*static*/ const int IndexMotor::kLoweringDelay = 4;
diff --git a/frc971/control_loops/python/drivetrain.py b/frc971/control_loops/python/drivetrain.py
index 0e791cb..fcca56a 100755
--- a/frc971/control_loops/python/drivetrain.py
+++ b/frc971/control_loops/python/drivetrain.py
@@ -5,9 +5,53 @@
 import sys
 from matplotlib import pylab
 
-class Drivetrain(control_loop.ControlLoop):
+
+class CIM(control_loop.ControlLoop):
   def __init__(self):
-    super(Drivetrain, self).__init__("Drivetrain")
+    super(CIM, self).__init__("CIM")
+    # Stall Torque in N m
+    self.stall_torque = 2.42
+    # Stall Current in Amps
+    self.stall_current = 133
+    # Free Speed in RPM
+    self.free_speed = 4650.0
+    # Free Current in Amps
+    self.free_current = 2.7
+    # 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
+    # Motor velocity constant
+    self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
+              (12.0 - self.R * self.free_current))
+    # Torque constant
+    self.Kt = self.stall_torque / self.stall_current
+    # Control loop time step
+    self.dt = 0.01
+
+    # State feedback matrices
+    self.A_continuous = numpy.matrix(
+        [[-self.Kt / self.Kv / (self.J * self.R)]])
+    self.B_continuous = numpy.matrix(
+        [[self.Kt / (self.J * self.R)]])
+    self.C = numpy.matrix([[1]])
+    self.D = numpy.matrix([[0]])
+
+    self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+                                               self.B_continuous, self.dt)
+
+    self.PlaceControllerPoles([0.01])
+    self.PlaceObserverPoles([0.01])
+
+    self.U_max = numpy.matrix([[12.0]])
+    self.U_min = numpy.matrix([[-12.0]])
+
+    self.InitializeState()
+
+
+class Drivetrain(control_loop.ControlLoop):
+  def __init__(self, left_low=True, right_low=True, is_clutch=False):
+    super(Drivetrain, self).__init__(("Clutch" if is_clutch else "Dog" )+"Drivetrain")
     # Stall Torque in N m
     self.stall_torque = 2.42
     # Stall Current in Amps
@@ -18,7 +62,7 @@
     self.free_current = 2.7
     # Moment of inertia of the drivetrain in kg m^2
     # Just borrowed from last year.
-    self.J = 6.4
+    self.J = 4.5
     # Mass of the robot, in kg.
     self.m = 68
     # Radius of the robot, in meters (from last year).
@@ -26,16 +70,27 @@
     # Radius of the wheels, in meters.
     self.r = .04445
     # Resistance of the motor, divided by the number of motors.
-    self.R = 12.0 / self.stall_current / 6 + 0.03
+    self.R = (12.0 / self.stall_current / 4 + 0.03) / (0.93 ** 2.0)
     # Motor velocity constant
     self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
                (12.0 - self.R * self.free_current))
     # Torque constant
     self.Kt = self.stall_torque / self.stall_current
     # Gear ratios
-    self.G_low = 16.0 / 60.0 * 19.0 / 50.0
-    self.G_high = 28.0 / 48.0 * 19.0 / 50.0
-    self.G = self.G_low
+    if is_clutch:
+      self.G_low = 14.0 / 60.0 * 15.0 / 50.0
+      self.G_high = 30.0 / 44.0 * 15.0 / 50.0
+    else:
+      self.G_low = 16.0 / 60.0 * 17.0 / 50.0
+      self.G_high = 28.0 / 48.0 * 17.0 / 50.0
+    if left_low:
+      self.Gl = self.G_low
+    else:
+      self.Gl = self.G_high
+    if right_low:
+      self.Gr = self.G_low
+    else:
+      self.Gr = self.G_high
     # Control loop time step
     self.dt = 0.01
 
@@ -44,22 +99,24 @@
     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.tc = -self.Kt / self.Kv / (self.G * self.G * self.R * self.r * self.r)
-    self.mp = self.Kt / (self.G * self.R * self.r)
+    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)
 
     # State feedback matrices
     # X will be of the format
-    # [[position1], [velocity1], [position2], velocity2]]
+    # [[positionl], [velocityl], [positionr], velocityr]]
     self.A_continuous = numpy.matrix(
         [[0, 1, 0, 0],
-         [0, self.msp * self.tc, 0, self.msn * self.tc],
+         [0, self.msp * self.tcl, 0, self.msn * self.tcr],
          [0, 0, 0, 1],
-         [0, self.msn * self.tc, 0, self.msp * self.tc]])
+         [0, self.msn * self.tcl, 0, self.msp * self.tcr]])
     self.B_continuous = numpy.matrix(
         [[0, 0],
-         [self.msp * self.mp, self.msn * self.mp],
+         [self.msp * self.mpl, self.msn * self.mpr],
          [0, 0],
-         [self.msn * self.mp, self.msp * self.mp]])
+         [self.msn * self.mpl, self.msp * self.mpr]])
     self.C = numpy.matrix([[1, 0, 0, 0],
                            [0, 0, 1, 0]])
     self.D = numpy.matrix([[0, 0],
@@ -73,8 +130,6 @@
     self.lp = 0.83
     self.PlaceControllerPoles([self.hp, self.hp, self.lp, self.lp])
 
-    print self.K
-
     self.hlp = 0.07
     self.llp = 0.09
     self.PlaceObserverPoles([self.hlp, self.hlp, self.llp, self.llp])
@@ -149,14 +204,23 @@
   #pylab.show()
 
   # Write the generated constants out to a file.
-  if len(argv) != 3:
+  dog_drivetrain = Drivetrain(is_clutch=False)
+  clutch_drivetrain = Drivetrain(is_clutch=True)
+
+  if len(argv) != 5:
     print "Expected .h file name and .cc file name"
   else:
-    loop_writer = control_loop.ControlLoopWriter("Drivetrain", [drivetrain])
+    dog_loop_writer = control_loop.ControlLoopWriter("DogDrivetrain", [dog_drivetrain])
     if argv[1][-3:] == '.cc':
-      loop_writer.Write(argv[2], argv[1])
+      dog_loop_writer.Write(argv[2], argv[1])
     else:
-      loop_writer.Write(argv[1], argv[2])
+      dog_loop_writer.Write(argv[1], argv[2])
+
+    clutch_loop_writer = control_loop.ControlLoopWriter("ClutchDrivetrain", [clutch_drivetrain])
+    if argv[3][-3:] == '.cc':
+      clutch_loop_writer.Write(argv[4], argv[3])
+    else:
+      clutch_loop_writer.Write(argv[3], argv[4])
 
 if __name__ == '__main__':
   sys.exit(main(sys.argv))
diff --git a/frc971/control_loops/python/libcdd.py b/frc971/control_loops/python/libcdd.py
index a217728..6305aaf 100644
--- a/frc971/control_loops/python/libcdd.py
+++ b/frc971/control_loops/python/libcdd.py
@@ -119,7 +119,7 @@
 
   # Return None on error.
   # The error values are enums, so they aren't exposed.
-  if error.value != NO_ERRORS:
+  if error.value != DD_NO_ERRORS:
     # Dump out the errors to stderr
     libcdd._Z21dd_WriteErrorMessagesP8_IO_FILE12dd_ErrorType(
         ctypes.pythonapi.PyFile_AsFile(ctypes.py_object(sys.stdout)),
diff --git a/frc971/control_loops/python/polydrivetrain.py b/frc971/control_loops/python/polydrivetrain.py
new file mode 100755
index 0000000..5ffcff4
--- /dev/null
+++ b/frc971/control_loops/python/polydrivetrain.py
@@ -0,0 +1,512 @@
+#!/usr/bin/python
+
+import numpy
+import sys
+import polytope
+import drivetrain
+import control_loop
+import controls
+from matplotlib import pylab
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+
+def CoerceGoal(region, K, w, R):
+  """Intersects a line with a region, and finds the closest point to R.
+
+  Finds a point that is closest to R inside the region, and on the line
+  defined by K X = w.  If it is not possible to find a point on the line,
+  finds a point that is inside the region and closest to the line.  This
+  function assumes that
+
+  Args:
+    region: HPolytope, the valid goal region.
+    K: numpy.matrix (2 x 1), the matrix for the equation [K1, K2] [x1; x2] = w
+    w: float, the offset in the equation above.
+    R: numpy.matrix (2 x 1), the point to be closest to.
+
+  Returns:
+    numpy.matrix (2 x 1), the point.
+  """
+
+  if region.IsInside(R):
+    return R
+
+  perpendicular_vector = K.T / numpy.linalg.norm(K)
+  parallel_vector = numpy.matrix([[perpendicular_vector[1, 0]],
+                                  [-perpendicular_vector[0, 0]]])
+  
+  # We want to impose the constraint K * X = w on the polytope H * X <= k.
+  # We do this by breaking X up into parallel and perpendicular components to
+  # the half plane.  This gives us the following equation.
+  #
+  #  parallel * (parallel.T \dot X) + perpendicular * (perpendicular \dot X)) = X
+  #
+  # Then, substitute this into the polytope.
+  #
+  #  H * (parallel * (parallel.T \dot X) + perpendicular * (perpendicular \dot X)) <= k
+  #
+  # Substitute K * X = w
+  #
+  # H * parallel * (parallel.T \dot X) + H * perpendicular * w <= k
+  #
+  # Move all the knowns to the right side.
+  #
+  # H * parallel * ([parallel1 parallel2] * X) <= k - H * perpendicular * w
+  #
+  # Let t = parallel.T \dot X, the component parallel to the surface.
+  #
+  # H * parallel * t <= k - H * perpendicular * w
+  #
+  # This is a polytope which we can solve, and use to figure out the range of X
+  # that we care about!
+
+  t_poly = polytope.HPolytope(
+      region.H * parallel_vector,
+      region.k - region.H * perpendicular_vector * w)
+
+  vertices = t_poly.Vertices()
+
+  if vertices.shape[0]:
+    # The region exists!
+    # Find the closest vertex
+    min_distance = numpy.infty
+    closest_point = None
+    for vertex in vertices:
+      point = parallel_vector * vertex + perpendicular_vector * w
+      length = numpy.linalg.norm(R - point)
+      if length < min_distance:
+        min_distance = length
+        closest_point = point
+
+    return closest_point
+  else:
+    # Find the vertex of the space that is closest to the line.
+    region_vertices = region.Vertices()
+    min_distance = numpy.infty
+    closest_point = None
+    for vertex in region_vertices:
+      point = vertex.T
+      length = numpy.abs((perpendicular_vector.T * point)[0, 0])
+      if length < min_distance:
+        min_distance = length
+        closest_point = point
+
+    return closest_point
+
+
+class VelocityDrivetrainModel(control_loop.ControlLoop):
+  def __init__(self, left_low=True, right_low=True, name="VelocityDrivetrainModel", is_clutch=False):
+    super(VelocityDrivetrainModel, self).__init__(name)
+    self._drivetrain = drivetrain.Drivetrain(left_low=left_low,
+                                             right_low=right_low,
+                                             is_clutch=is_clutch)
+    self.dt = 0.01
+    self.A_continuous = numpy.matrix(
+        [[self._drivetrain.A_continuous[1, 1], self._drivetrain.A_continuous[1, 3]],
+         [self._drivetrain.A_continuous[3, 1], self._drivetrain.A_continuous[3, 3]]])
+
+    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.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+                                               self.B_continuous, self.dt)
+
+    # FF * X = U (steady state)
+    self.FF = self.B.I * (numpy.eye(2) - self.A)
+
+    self.PlaceControllerPoles([0.6, 0.6])
+    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.r = self._drivetrain.r
+    self.Kv = self._drivetrain.Kv
+    self.Kt = self._drivetrain.Kt
+
+    self.U_max = self._drivetrain.U_max
+    self.U_min = self._drivetrain.U_min
+
+
+class VelocityDrivetrain(object):
+  HIGH = 'high'
+  LOW = 'low'
+  SHIFTING_UP = 'up'
+  SHIFTING_DOWN = 'down'
+
+  def __init__(self, is_clutch):
+    prefix = 'Clutch' if is_clutch else 'Dog'
+    self.drivetrain_low_low = VelocityDrivetrainModel(
+        left_low=True, right_low=True, name=prefix+'VelocityDrivetrainLowLow', is_clutch=is_clutch)
+    self.drivetrain_low_high = VelocityDrivetrainModel(left_low=True, right_low=False, name=prefix+'VelocityDrivetrainLowHigh', is_clutch=is_clutch)
+    self.drivetrain_high_low = VelocityDrivetrainModel(left_low=False, right_low=True, name = prefix+'VelocityDrivetrainHighLow', is_clutch=is_clutch)
+    self.drivetrain_high_high = VelocityDrivetrainModel(left_low=False, right_low=False, name = prefix+'VelocityDrivetrainHighHigh', is_clutch=is_clutch)
+
+    # X is [lvel, rvel]
+    self.X = numpy.matrix(
+        [[0.0],
+         [0.0]])
+
+    self.U_poly = polytope.HPolytope(
+        numpy.matrix([[1, 0],
+                      [-1, 0],
+                      [0, 1],
+                      [0, -1]]),
+        numpy.matrix([[12],
+                      [12],
+                      [12],
+                      [12]]))
+
+    self.U_max = numpy.matrix(
+        [[12.0],
+         [12.0]])
+    self.U_min = numpy.matrix(
+        [[-12.0000000000],
+         [-12.0000000000]])
+
+    self.dt = 0.01
+
+    self.R = 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.0
+
+    self.left_gear = VelocityDrivetrain.LOW
+    self.right_gear = VelocityDrivetrain.LOW
+    self.left_shifter_position = 0.0
+    self.right_shifter_position = 0.0
+    self.left_cim = drivetrain.CIM()
+    self.right_cim = drivetrain.CIM()
+
+  def IsInGear(self, gear):
+    return gear is VelocityDrivetrain.HIGH or gear is VelocityDrivetrain.LOW
+
+  def MotorRPM(self, shifter_position, velocity):
+    if shifter_position > 0.5:
+      return (velocity / self.CurrentDrivetrain().G_high /
+              self.CurrentDrivetrain().r)
+    else:
+      return (velocity / self.CurrentDrivetrain().G_low /
+              self.CurrentDrivetrain().r)
+
+  def CurrentDrivetrain(self):
+    if self.left_shifter_position > 0.5:
+      if self.right_shifter_position > 0.5:
+        return self.drivetrain_high_high
+      else:
+        return self.drivetrain_high_low
+    else:
+      if self.right_shifter_position > 0.5:
+        return self.drivetrain_low_high
+      else:
+        return self.drivetrain_low_low
+
+  def SimShifter(self, gear, shifter_position):
+    if gear is VelocityDrivetrain.HIGH or gear is VelocityDrivetrain.SHIFTING_UP:
+      shifter_position = min(shifter_position + 0.5, 1.0)
+    else:
+      shifter_position = max(shifter_position - 0.5, 0.0)
+
+    if shifter_position == 1.0:
+      gear = VelocityDrivetrain.HIGH
+    elif shifter_position == 0.0:
+      gear = VelocityDrivetrain.LOW
+
+    return gear, shifter_position
+
+  def ComputeGear(self, wheel_velocity, should_print=False, current_gear=False, gear_name=None):
+    high_omega = (wheel_velocity / self.CurrentDrivetrain().G_high /
+                  self.CurrentDrivetrain().r)
+    low_omega = (wheel_velocity / self.CurrentDrivetrain().G_low /
+                 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)
+    low_torque = ((12.0 - low_omega / self.CurrentDrivetrain().Kv) *
+                  self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
+    high_power = high_torque * high_omega
+    low_power = low_torque * low_omega
+    #if should_print:
+    #  print gear_name, "High omega", high_omega, "Low omega", low_omega
+    #  print gear_name, "High torque", high_torque, "Low torque", low_torque
+    #  print gear_name, "High power", high_power, "Low power", low_power
+
+    # Shift algorithm improvements.
+    # TODO(aschuh):
+    # It takes time to shift.  Shifting down for 1 cycle doesn't make sense
+    # because you will end up slower than without shifting.  Figure out how
+    # to include that info.
+    # If the driver is still in high gear, but isn't asking for the extra power
+    # from low gear, don't shift until he asks for it.
+    goal_gear_is_high = high_power > low_power
+    #goal_gear_is_high = True
+
+    if not self.IsInGear(current_gear):
+      print gear_name, 'Not in gear.'
+      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.'
+          return VelocityDrivetrain.SHIFTING_UP
+        else:
+          print gear_name, 'Shifting down.'
+          return VelocityDrivetrain.SHIFTING_DOWN
+      else:
+        return current_gear
+
+  def FilterVelocity(self, throttle):
+    # 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 equal.
+
+    # The throttle filter should filter such that the motor in the highest gear
+    # should be controlling the time constant.
+    # Do this by finding the index of FF that has the lowest value, and computing
+    # the sums using that index.
+    FF_sum = self.CurrentDrivetrain().FF.sum(axis=1)
+    min_FF_sum_index = numpy.argmin(FF_sum)
+    min_FF_sum = FF_sum[min_FF_sum_index, 0]
+    min_K_sum = self.CurrentDrivetrain().K[min_FF_sum_index, :].sum()
+    # Compute the FF sum for high gear.
+    high_min_FF_sum = self.drivetrain_high_high.FF[0, :].sum()
+
+    # U = self.K[0, :].sum() * (R - x_avg) + self.FF[0, :].sum() * R
+    # throttle * 12.0 = (self.K[0, :].sum() + self.FF[0, :].sum()) * R
+    #                   - self.K[0, :].sum() * x_avg
+
+    # R = (throttle * 12.0 + self.K[0, :].sum() * x_avg) /
+    #     (self.K[0, :].sum() + self.FF[0, :].sum())
+
+    # U = (K + FF) * R - K * X
+    # (K + FF) ^-1 * (U + K * X) = R
+
+    # Scale throttle by min_FF_sum / high_min_FF_sum.  This will make low gear
+    # have the same velocity goal as high gear, and so that the robot will hold
+    # the same speed for the same throttle for all gears.
+    adjusted_ff_voltage = numpy.clip(throttle * 12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0)
+    return ((adjusted_ff_voltage + self.ttrust * min_K_sum * (self.X[0, 0] + self.X[1, 0]) / 2.0)
+            / (self.ttrust * min_K_sum + min_FF_sum))
+
+  def Update(self, throttle, steering):
+    # Shift into the gear which sends the most power to the floor.
+    # This is the same as sending the most torque down to the floor at the
+    # wheel.
+
+    self.left_gear = self.ComputeGear(self.X[0, 0], should_print=True,
+                                      current_gear=self.left_gear,
+                                      gear_name="left")
+    self.right_gear = self.ComputeGear(self.X[1, 0], should_print=True,
+                                       current_gear=self.right_gear,
+                                       gear_name="right")
+    if self.IsInGear(self.left_gear):
+      self.left_cim.X[0, 0] = self.MotorRPM(self.left_shifter_position, self.X[0, 0])
+
+    if self.IsInGear(self.right_gear):
+      self.right_cim.X[0, 0] = self.MotorRPM(self.right_shifter_position, self.X[0, 0])
+
+    if self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
+      # Filter the throttle to provide a nicer response.
+      fvel = self.FilterVelocity(throttle)
+
+      # Constant radius means that angualar_velocity / linear_velocity = constant.
+      # Compute the left and right velocities.
+      left_velocity = fvel - steering * numpy.abs(fvel)
+      right_velocity = fvel + steering * numpy.abs(fvel)
+
+      # Write this constraint in the form of K * R = w
+      # angular velocity / linear velocity = constant
+      # (left - right) / (left + right) = constant
+      # left - right = constant * left + constant * right
+
+      # (fvel - steering * numpy.abs(fvel) - fvel - steering * numpy.abs(fvel)) /
+      #  (fvel - steering * numpy.abs(fvel) + fvel + steering * numpy.abs(fvel)) =
+      #       constant
+      # (- 2 * steering * numpy.abs(fvel)) / (2 * fvel) = constant
+      # (-steering * sign(fvel)) = constant
+      # (-steering * sign(fvel)) * (left + right) = left - right
+      # (steering * sign(fvel) + 1) * left + (steering * sign(fvel) - 1) * right = 0
+
+      equality_k = numpy.matrix(
+          [[1 + steering * numpy.sign(fvel), -(1 - steering * numpy.sign(fvel))]])
+      equality_w = 0.0
+
+      self.R[0, 0] = left_velocity
+      self.R[1, 0] = right_velocity
+
+      # Construct a constraint on R by manipulating the constraint on U
+      # Start out with H * U <= k
+      # U = FF * R + K * (R - X)
+      # H * (FF * R + K * R - K * X) <= k
+      # H * (FF + K) * R <= k + H * K * X
+      R_poly = polytope.HPolytope(
+          self.U_poly.H * (self.CurrentDrivetrain().K + self.CurrentDrivetrain().FF),
+          self.U_poly.k + self.U_poly.H * self.CurrentDrivetrain().K * self.X)
+
+      # Limit R back inside the box.
+      self.boxed_R = CoerceGoal(R_poly, equality_k, equality_w, self.R)
+
+      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'
+      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])
+        self.U_ideal[0, 0] = numpy.clip(
+            self.left_cim.K * (R_left - self.left_cim.X) + R_left / self.left_cim.Kv,
+            self.left_cim.U_min, self.left_cim.U_max)
+        self.left_cim.Update(self.U_ideal[0, 0])
+
+        R_right = self.MotorRPM(self.right_shifter_position, self.X[1, 0])
+        self.U_ideal[1, 0] = numpy.clip(
+            self.right_cim.K * (R_right - self.right_cim.X) + R_right / self.right_cim.Kv,
+            self.right_cim.U_min, self.right_cim.U_max)
+        self.right_cim.Update(self.U_ideal[1, 0])
+      else:
+        assert False
+
+    self.U = numpy.clip(self.U_ideal, self.U_min, self.U_max)
+
+    # TODO(austin): Model the robot as not accelerating when you shift...
+    # This hack only works when you shift at the same time.
+    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(
+        self.left_gear, self.left_shifter_position)
+    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
+
+
+def main(argv):
+  dog_vdrivetrain = VelocityDrivetrain(False)
+  clutch_vdrivetrain = VelocityDrivetrain(True)
+
+  if len(argv) != 7:
+    print "Expected .h file name and .cc file name"
+  else:
+    dog_loop_writer = control_loop.ControlLoopWriter(
+        "VDogDrivetrain", [dog_vdrivetrain.drivetrain_low_low,
+                           dog_vdrivetrain.drivetrain_low_high,
+                           dog_vdrivetrain.drivetrain_high_low,
+                           dog_vdrivetrain.drivetrain_high_high])
+
+    if argv[1][-3:] == '.cc':
+      dog_loop_writer.Write(argv[2], argv[1])
+    else:
+      dog_loop_writer.Write(argv[1], argv[2])
+
+    clutch_loop_writer = control_loop.ControlLoopWriter(
+        "VClutchDrivetrain", [clutch_vdrivetrain.drivetrain_low_low,
+                              clutch_vdrivetrain.drivetrain_low_high,
+                              clutch_vdrivetrain.drivetrain_high_low,
+                              clutch_vdrivetrain.drivetrain_high_high])
+
+    if argv[3][-3:] == '.cc':
+      clutch_loop_writer.Write(argv[4], argv[3])
+    else:
+      clutch_loop_writer.Write(argv[3], argv[4])
+
+    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
+
+  vl_plot = []
+  vr_plot = []
+  ul_plot = []
+  ur_plot = []
+  radius_plot = []
+  t_plot = []
+  left_gear_plot = []
+  right_gear_plot = []
+  vdrivetrain.left_shifter_position = 0.0
+  vdrivetrain.right_shifter_position = 0.0
+  vdrivetrain.left_gear = VelocityDrivetrain.LOW
+  vdrivetrain.right_gear = VelocityDrivetrain.LOW
+
+  print "K is", vdrivetrain.CurrentDrivetrain().K
+
+  if vdrivetrain.left_gear is VelocityDrivetrain.HIGH:
+    print "Left is high"
+  else:
+    print "Left is low"
+  if vdrivetrain.right_gear is VelocityDrivetrain.HIGH:
+    print "Right is high"
+  else:
+    print "Right is low"
+
+  for t in numpy.arange(0, 4.0, vdrivetrain.dt):
+    if t < 1.0:
+      vdrivetrain.Update(throttle=1.00, steering=0.0)
+    elif t < 1.2:
+      vdrivetrain.Update(throttle=1.00, steering=0.0)
+    else:
+      vdrivetrain.Update(throttle=1.00, steering=0.0)
+    t_plot.append(t)
+    vl_plot.append(vdrivetrain.X[0, 0])
+    vr_plot.append(vdrivetrain.X[1, 0])
+    ul_plot.append(vdrivetrain.U[0, 0])
+    ur_plot.append(vdrivetrain.U[1, 0])
+    left_gear_plot.append((vdrivetrain.left_gear is VelocityDrivetrain.HIGH) * 2.0 - 10.0)
+    right_gear_plot.append((vdrivetrain.right_gear is VelocityDrivetrain.HIGH) * 2.0 - 10.0)
+
+    fwd_velocity = (vdrivetrain.X[1, 0] + vdrivetrain.X[0, 0]) / 2
+    turn_velocity = (vdrivetrain.X[1, 0] - vdrivetrain.X[0, 0])
+    if abs(fwd_velocity) < 0.0000001:
+      radius_plot.append(turn_velocity)
+    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.
+
+  # Tighten the turn.
+  # Closed loop drive.
+
+  pylab.plot(t_plot, vl_plot, label='left velocity')
+  pylab.plot(t_plot, vr_plot, label='right velocity')
+  pylab.plot(t_plot, ul_plot, label='left voltage')
+  pylab.plot(t_plot, ur_plot, label='right voltage')
+  pylab.plot(t_plot, radius_plot, label='radius')
+  pylab.plot(t_plot, left_gear_plot, label='left gear high')
+  pylab.plot(t_plot, right_gear_plot, label='right gear high')
+  pylab.legend()
+  pylab.show()
+  return 0
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/frc971/control_loops/python/polydrivetrain_test.py b/frc971/control_loops/python/polydrivetrain_test.py
new file mode 100755
index 0000000..434cdca
--- /dev/null
+++ b/frc971/control_loops/python/polydrivetrain_test.py
@@ -0,0 +1,82 @@
+#!/usr/bin/python
+
+import polydrivetrain
+import numpy
+from numpy.testing import *
+import polytope
+import unittest
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+
+class TestVelocityDrivetrain(unittest.TestCase):
+  def MakeBox(self, x1_min, x1_max, x2_min, x2_max):
+    H = numpy.matrix([[1, 0],
+                      [-1, 0],
+                      [0, 1],
+                      [0, -1]])
+    K = numpy.matrix([[x1_max],
+                      [-x1_min],
+                      [x2_max],
+                      [-x2_min]])
+    return polytope.HPolytope(H, K)
+
+  def test_coerce_inside(self):
+    """Tests coercion when the point is inside the box."""
+    box = self.MakeBox(1, 2, 1, 2)
+
+    # x1 = x2
+    K = numpy.matrix([[1, -1]])
+    w = 0
+
+    assert_array_equal(polydrivetrain.CoerceGoal(box, K, w,
+                                                 numpy.matrix([[1.5], [1.5]])),
+                       numpy.matrix([[1.5], [1.5]]))
+
+  def test_coerce_outside_intersect(self):
+    """Tests coercion when the line intersects the box."""
+    box = self.MakeBox(1, 2, 1, 2)
+
+    # x1 = x2
+    K = numpy.matrix([[1, -1]])
+    w = 0
+
+    assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
+                       numpy.matrix([[2.0], [2.0]]))
+
+  def test_coerce_outside_no_intersect(self):
+    """Tests coercion when the line does not intersect the box."""
+    box = self.MakeBox(3, 4, 1, 2)
+
+    # x1 = x2
+    K = numpy.matrix([[1, -1]])
+    w = 0
+
+    assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
+                       numpy.matrix([[3.0], [2.0]]))
+
+  def test_coerce_middle_of_edge(self):
+    """Tests coercion when the line intersects the middle of an edge."""
+    box = self.MakeBox(0, 4, 1, 2)
+
+    # x1 = x2
+    K = numpy.matrix([[-1, 1]])
+    w = 0
+
+    assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
+                       numpy.matrix([[2.0], [2.0]]))
+
+  def test_coerce_perpendicular_line(self):
+    """Tests coercion when the line does not intersect and is in quadrant 2."""
+    box = self.MakeBox(1, 2, 1, 2)
+
+    # x1 = -x2
+    K = numpy.matrix([[1, 1]])
+    w = 0
+
+    assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
+                       numpy.matrix([[1.0], [1.0]]))
+
+
+if __name__ == '__main__':
+  unittest.main()
diff --git a/frc971/control_loops/state_feedback_loop.h b/frc971/control_loops/state_feedback_loop.h
index cc11dfc..034ee9e 100644
--- a/frc971/control_loops/state_feedback_loop.h
+++ b/frc971/control_loops/state_feedback_loop.h
@@ -5,9 +5,6 @@
 
 #include <vector>
 
-// Stupid vxworks system headers define it which blows up Eigen...
-#undef m_data
-
 #include "Eigen/Dense"
 
 template <int number_of_states, int number_of_inputs, int number_of_outputs>
@@ -223,15 +220,17 @@
   Eigen::Matrix<double, number_of_outputs, 1> U_ff;
   Eigen::Matrix<double, number_of_outputs, 1> Y;
 
-  ::std::vector<StateFeedbackController<number_of_states, number_of_inputs,
-                                        number_of_outputs> *> controllers_;
-
-  const StateFeedbackController<
-      number_of_states, number_of_inputs, number_of_outputs>
-          &controller() const {
+  const StateFeedbackController<number_of_states, number_of_inputs,
+                                number_of_outputs> &controller() const {
     return *controllers_[controller_index_];
   }
 
+  const StateFeedbackController<number_of_states, number_of_inputs,
+                                number_of_outputs> &controller(
+                                    int index) const {
+    return *controllers_[index];
+  }
+
   void Reset() {
     X_hat.setZero();
     R.setZero();
@@ -241,22 +240,17 @@
     Y.setZero();
   }
 
-  StateFeedbackLoop(
-      const StateFeedbackController<number_of_states, number_of_inputs,
-                                    number_of_outputs> &controller)
+  StateFeedbackLoop(const StateFeedbackController<
+      number_of_states, number_of_inputs, number_of_outputs> &controller)
       : controller_index_(0) {
-    controllers_.push_back(
-        new StateFeedbackController<number_of_states, number_of_inputs,
-                                    number_of_outputs>(controller));
+    controllers_.push_back(new StateFeedbackController<
+        number_of_states, number_of_inputs, number_of_outputs>(controller));
     Reset();
   }
 
-  StateFeedbackLoop(
-      const ::std::vector<StateFeedbackController<
-          number_of_states, number_of_inputs,
-          number_of_outputs> *> &controllers)
-      : controllers_(controllers),
-        controller_index_(0) {
+  StateFeedbackLoop(const ::std::vector<StateFeedbackController<
+      number_of_states, number_of_inputs, number_of_outputs> *> &controllers)
+      : controllers_(controllers), controller_index_(0) {
     Reset();
   }
 
@@ -328,6 +322,9 @@
   void controller_index() const { return controller_index_; }
 
  protected:
+  ::std::vector<StateFeedbackController<number_of_states, number_of_inputs,
+                                        number_of_outputs> *> controllers_;
+
   // these are accessible from non-templated subclasses
   static const int kNumStates = number_of_states;
   static const int kNumOutputs = number_of_outputs;
diff --git a/frc971/control_loops/update_drivetrain.sh b/frc971/control_loops/update_drivetrain.sh
index 9d17e99..bad1074 100755
--- a/frc971/control_loops/update_drivetrain.sh
+++ b/frc971/control_loops/update_drivetrain.sh
@@ -1,6 +1,10 @@
 #!/bin/bash
 #
-# Updates the drivetrain controller.
+# Updates the drivetrain controllers (for both robots).
 
-./python/drivetrain.py drivetrain/drivetrain_motor_plant.h \
-    drivetrain/drivetrain_motor_plant.cc
+cd $(dirname $0)
+
+./python/drivetrain.py drivetrain/drivetrain_dog_motor_plant.h \
+    drivetrain/drivetrain_dog_motor_plant.cc \
+    drivetrain/drivetrain_clutch_motor_plant.h \
+    drivetrain/drivetrain_clutch_motor_plant.cc
diff --git a/frc971/control_loops/update_polydrivetrain.sh b/frc971/control_loops/update_polydrivetrain.sh
new file mode 100755
index 0000000..2e2748e
--- /dev/null
+++ b/frc971/control_loops/update_polydrivetrain.sh
@@ -0,0 +1,12 @@
+#!/bin/bash
+#
+# Updates the polydrivetrain controllers (for both robots) and CIM models.
+
+cd $(dirname $0)
+
+./python/polydrivetrain.py drivetrain/polydrivetrain_dog_motor_plant.h \
+    drivetrain/polydrivetrain_dog_motor_plant.cc \
+    drivetrain/polydrivetrain_clutch_motor_plant.h \
+    drivetrain/polydrivetrain_clutch_motor_plant.cc \
+    drivetrain/polydrivetrain_cim_plant.h \
+    drivetrain/polydrivetrain_cim_plant.cc
diff --git a/frc971/frc971.gyp b/frc971/frc971.gyp
index 6d5202c..b6d842d 100644
--- a/frc971/frc971.gyp
+++ b/frc971/frc971.gyp
@@ -10,6 +10,11 @@
         '<(AOS)/build/aos.gyp:logging',
         '<(AOS)/common/common.gyp:once',
         '<(AOS)/common/network/network.gyp:team_number',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(DEPTH)/frc971/control_loops/drivetrain/drivetrain.gyp:polydrivetrain_plants',
+      ],
+      'export_dependent_settings': [
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
       ],
     }
   ],
diff --git a/frc971/input/gyro_board_data.h b/frc971/input/gyro_board_data.h
index fb47642..94200c9 100644
--- a/frc971/input/gyro_board_data.h
+++ b/frc971/input/gyro_board_data.h
@@ -1,6 +1,8 @@
 #ifndef FRC971_INPUT_GYRO_BOARD_DATA_H_
 #define FRC971_INPUT_GYRO_BOARD_DATA_H_
 
+#include <stdint.h>
+
 namespace frc971 {
 
 #define DATA_STRUCT_NAME GyroBoardData
diff --git a/frc971/input/gyro_sensor_receiver.cc b/frc971/input/gyro_sensor_receiver.cc
index 411fb5e..fcfabb2 100644
--- a/frc971/input/gyro_sensor_receiver.cc
+++ b/frc971/input/gyro_sensor_receiver.cc
@@ -11,6 +11,7 @@
 #include "frc971/control_loops/shooter/shooter_motor.q.h"
 #include "frc971/queues/GyroAngle.q.h"
 #include "frc971/input/usb_receiver.h"
+#include "frc971/constants.h"
 
 #ifndef M_PI
 #define M_PI 3.14159265358979323846
@@ -27,50 +28,57 @@
 namespace frc971 {
 namespace {
 
-inline double drivetrain_translate(int32_t in) {
+double drivetrain_translate(int32_t in) {
   return static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*quad*/) *
-      (19.0 / 50.0) /*output reduction*/ * (64.0 / 24.0) /*encoder gears*/ *
+      constants::GetValues().drivetrain_encoder_ratio *
       (3.5 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
 }
 
-inline double wrist_translate(int32_t in) {
+double wrist_translate(int32_t in) {
   return static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*quad*/) *
       (14.0 / 50.0 * 20.0 / 84.0) /*gears*/ * (2 * M_PI);
 }
 
-inline double angle_adjust_translate(int32_t in) {
+double angle_adjust_translate(int32_t in) {
   static const double kCableDiameter = 0.060;
   return -static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*quad*/) *
       ((0.75 + kCableDiameter) / (16.61125 + kCableDiameter)) /*pulleys*/ *
       (2 * M_PI);
 }
 
-inline double shooter_translate(int32_t in) {
+double shooter_translate(int32_t in) {
  return static_cast<double>(in) / (32.0 /*cpr*/ * 4.0 /*quad*/) *
       (15.0 / 34.0) /*gears*/ * (2 * M_PI);
 }
 
-inline double index_translate(int32_t in) {
+double index_translate(int32_t in) {
   return -static_cast<double>(in) / (128.0 /*cpr*/ * 4.0 /*quad*/) *
       (1.0) /*gears*/ * (2 * M_PI);
 }
 
 // Translates values from the ADC into voltage.
-inline double adc_translate(uint16_t in) {
+double adc_translate(uint16_t in) {
   static const double kVRefN = 0;
   static const double kVRefP = 3.3;
-  static const int kMaximumValue = 0x3FF;
-  return kVRefN +
+  static const int kMaximumValue = 0xFFF;
+  static const double kDividerGnd = 31.6, kDividerOther = 28;
+  return (kVRefN +
       (static_cast<double>(in) / static_cast<double>(kMaximumValue) *
-       (kVRefP - kVRefN));
+       (kVRefP - kVRefN))) * (kDividerGnd + kDividerOther) / kDividerGnd;
 }
 
-inline double gyro_translate(int64_t in) {
+double gyro_translate(int64_t in) {
   return in / 16.0 / 1000.0 / (180.0 / M_PI);
 }
 
-inline double battery_translate(uint16_t in) {
-  return adc_translate(in) * 80.8 / 17.8;
+double battery_translate(uint16_t in) {
+  static const double kDividerBig = 98.9, kDividerSmall = 17.8;
+  return adc_translate(in) * kDividerBig / kDividerSmall;
+}
+
+double hall_translate(const constants::ShifterHallEffect &k, uint16_t in) {
+  const double voltage = adc_translate(in);
+  return (voltage - k.low) / (k.high - k.low);
 }
 
 }  // namespace
@@ -79,14 +87,34 @@
  public:
   GyroSensorReceiver() : USBReceiver(2) {}
 
+  virtual void PacketReceived(const ::aos::time::Time &/*timestamp*/) override {
+    if (data()->bad_gyro) {
+      LOG(ERROR, "bad gyro\n");
+      bad_gyro_ = true;
+      gyro.MakeWithBuilder().angle(0).Send();
+    } else if (data()->old_gyro_reading) {
+      LOG(WARNING, "old gyro reading\n");
+      bad_gyro_ = true;
+    } else {
+      bad_gyro_ = false;
+    }
+  }
+
   virtual void ProcessData(const ::aos::time::Time &/*timestamp*/) override {
-    gyro.MakeWithBuilder()
-        .angle(gyro_translate(data()->gyro_angle))
-        .Send();
+    if (!bad_gyro_) {
+      gyro.MakeWithBuilder()
+          .angle(gyro_translate(data()->gyro_angle))
+          .Send();
+    }
 
     drivetrain.position.MakeWithBuilder()
         .right_encoder(drivetrain_translate(data()->main.right_drive))
         .left_encoder(-drivetrain_translate(data()->main.left_drive))
+        .left_shifter_position(hall_translate(constants::GetValues().left_drive,
+                                              data()->main.left_drive_hall))
+        .right_shifter_position(hall_translate(
+             constants::GetValues().right_drive, data()->main.right_drive_hall))
+        .battery_voltage(battery_translate(data()->main.battery_voltage))
         .Send();
 
     wrist.position.MakeWithBuilder()
@@ -130,16 +158,10 @@
         .loader_top(data()->main.loader_top)
         .loader_bottom(data()->main.loader_bottom)
         .Send();
-
-    LOG(DEBUG, "battery %f %f %" PRIu16 "\n",
-        battery_translate(data()->main.battery_voltage),
-        adc_translate(data()->main.battery_voltage),
-        data()->main.battery_voltage);
-    LOG(DEBUG, "halls l=%f r=%f\n",
-        adc_translate(data()->main.left_drive_hall),
-        adc_translate(data()->main.right_drive_hall));
   }
 
+  bool bad_gyro_;
+
   WrappingCounter top_rise_;
   WrappingCounter top_fall_;
   WrappingCounter bottom_rise_;
diff --git a/frc971/input/input.gyp b/frc971/input/input.gyp
index 9a26bce..b0bcb20 100644
--- a/frc971/input/input.gyp
+++ b/frc971/input/input.gyp
@@ -38,6 +38,7 @@
         '<(AOS)/build/aos.gyp:logging',
         '<(AOS)/common/util/util.gyp:wrapping_counter',
         'usb_receiver',
+        '<(DEPTH)/frc971/frc971.gyp:constants',
       ],
     },
     {
@@ -56,6 +57,13 @@
         '<(DEPTH)/gyro_board/src/libusb-driver/libusb-driver.gyp:libusb_wrap',
         '<(AOS)/common/common.gyp:time',
       ],
+      'variables': {
+        # TODO(brians): Add dependency on this file too (or something).
+        'checksum': '<!(<(DEPTH)/gyro_board/src/usb/data_struct_checksum.sh)',
+      },
+      'defines': [
+        'GYRO_BOARD_DATA_CHECKSUM=<(checksum)',
+      ],
     },
   ],
 }
diff --git a/frc971/input/joystick_reader.cc b/frc971/input/joystick_reader.cc
index be4e188..b29e17d 100644
--- a/frc971/input/joystick_reader.cc
+++ b/frc971/input/joystick_reader.cc
@@ -82,7 +82,7 @@
       bool is_control_loop_driving = false;
       double left_goal = 0.0;
       double right_goal = 0.0;
-      const double wheel = data.GetAxis(kSteeringWheel);
+      const double wheel = -data.GetAxis(kSteeringWheel);
       const double throttle = -data.GetAxis(kDriveThrottle);
       LOG(DEBUG, "wheel %f throttle %f\n", wheel, throttle);
       const double kThrottleGain = 1.0 / 2.5;
@@ -177,22 +177,13 @@
           shooter_goal->velocity = target_angle->shooter_speed;
           angle_adjust_goal = target_angle->shooter_angle;
           // TODO(brians): do the math right here
-          wrist_up_position = 0.70;
+          if (!hopper_clear) wrist_up_position = 0.70;
         } else {
           LOG(WARNING, "camera frame too old\n");
-          // pretend like no button is pressed
+          // Pretend like no button is pressed.
         }
 #endif
-        // This shot is from 30'.
-        shooter_goal->velocity = 360;
-        if (!hopper_clear) wrist_up_position = 1.23 - 0.4;
-        angle_adjust_goal = 0.630;
       } else if (data.IsPressed(kMediumShot)) {
-#if 0
-        shooter_goal->velocity = 375;
-        wrist_up_position = 0.70;
-        angle_adjust_goal = 0.564;
-#endif
         // middle wheel on the back line (same as auto)
         shooter_goal->velocity = 395;
         if (!hopper_clear) wrist_up_position = 1.23 - 0.4;
diff --git a/frc971/input/usb_receiver.cc b/frc971/input/usb_receiver.cc
index b70ff61..06eb7df 100644
--- a/frc971/input/usb_receiver.cc
+++ b/frc971/input/usb_receiver.cc
@@ -18,23 +18,27 @@
   if (ReceiveData()) {
     Reset();
   } else {
-    if (phase_locker_.IsCurrentPacketGood(transfer_received_time_, frame_number_)) {
-      static const int kCountsPerSecond = 100000;
-      const ::aos::time::Time timestamp =
-          ::aos::time::Time(data()->timestamp / kCountsPerSecond,
-                            (data()->timestamp * ::aos::time::Time::kNSecInSec /
-                             kCountsPerSecond) %
-                                ::aos::time::Time::kNSecInSec);
+    const ::aos::time::Time timestamp =
+        ::aos::time::Time::InMS(data()->frame_number);
 
-      if (data()->robot_id != expected_robot_id_) {
-        LOG(ERROR, "gyro board sent data for robot id %hhd instead of %hhd!"
-            " dip switches are %hhx\n",
-            data()->robot_id, expected_robot_id_, data()->dip_switches);
-        return;
-      } else {
-        LOG(DEBUG, "processing dips %hhx frame %" PRId32 " at %f\n",
-            data()->dip_switches, data()->frame_number, timestamp.ToSeconds());
-      }
+    if (data()->robot_id != expected_robot_id_) {
+      LOG(ERROR, "gyro board sent data for robot id %hhd instead of %hhd!"
+          " dip switches are %hhx\n",
+          data()->robot_id, expected_robot_id_, data()->dip_switches);
+      return;
+    }
+    if (data()->checksum != GYRO_BOARD_DATA_CHECKSUM) {
+      LOG(ERROR,
+          "gyro board sent checksum %" PRIu16 " instead of %" PRIu16 "!\n",
+          data()->checksum, GYRO_BOARD_DATA_CHECKSUM);
+      return;
+    }
+
+    PacketReceived(timestamp);
+
+    if (phase_locker_.IsCurrentPacketGood(transfer_received_time_, frame_number_)) {
+      LOG(DEBUG, "processing dips %hhx frame %" PRId32 " at %f\n",
+          data()->dip_switches, data()->frame_number, timestamp.ToSeconds());
 
       ProcessData(timestamp);
     }
@@ -50,6 +54,9 @@
   good_phase_early_ = good_phase_late_ = 0;
 }
 
+void USBReceiver::PacketReceived(const ::aos::time::Time &/*timestamp*/) {}
+void USBReceiver::ProcessData(const ::aos::time::Time &/*timestamp*/) {}
+
 bool USBReceiver::PhaseLocker::IsCurrentPacketGood(
     const ::aos::time::Time &received_time,
     uint32_t sequence) {
@@ -176,7 +183,6 @@
 void USBReceiver::TransferCallback(libusb::Transfer *transfer) {
   transfer_received_time_ = ::aos::time::Time::Now();
   if (transfer->status() == LIBUSB_TRANSFER_COMPLETED) {
-    LOG(DEBUG, "transfer %p completed\n", transfer);
     completed_transfer_ = transfer;
   } else if (transfer->status() == LIBUSB_TRANSFER_TIMED_OUT) {
     LOG(WARNING, "transfer %p timed out\n", transfer);
@@ -227,8 +233,8 @@
       LOG(WARNING, "frame number went from %" PRId32" to %" PRId32 "\n",
           frame_number_before, frame_number_);
     }
-    if (frame_number_ < last_frame_number_) {
-      LOG(WARNING, "frame number went down\n");
+    if (frame_number_ < last_frame_number_ - 2) {
+      LOG(WARNING, "frame number went down a lot\n");
       return true;
     }
     last_frame_number_ = frame_number_;
diff --git a/frc971/input/usb_receiver.h b/frc971/input/usb_receiver.h
index 509b740..fec847f 100644
--- a/frc971/input/usb_receiver.h
+++ b/frc971/input/usb_receiver.h
@@ -102,7 +102,19 @@
 
   void Reset();
 
-  virtual void ProcessData(const ::aos::time::Time &timestamp) = 0;
+  // These 2 are the functions for subclasses to override and do stuff in.
+  // timestamp for both of them is the time (as best as this code can determine)
+  // that the values in the packet were captured.
+  // They both have empty implementations here for subclasses that don't want to
+  // do anything in one of them.
+
+  // Gets called after each packet is received (possibly before ProcessData for
+  // the same packet).
+  virtual void PacketReceived(const ::aos::time::Time &timestamp);
+  // Gets called every 10th packet (or so) (at the right time for data for
+  // control loops to get read). PacketReceived will always be called right
+  // before this.
+  virtual void ProcessData(const ::aos::time::Time &timestamp);
 
   const uint8_t expected_robot_id_;
 
diff --git a/gyro_board/schematic/.gitignore b/gyro_board/schematic/.gitignore
new file mode 100644
index 0000000..d6b9d75
--- /dev/null
+++ b/gyro_board/schematic/.gitignore
@@ -0,0 +1,2 @@
+*.b#*
+*.s#*
diff --git a/gyro_board/src/usb/CAN.c b/gyro_board/src/usb/CAN.c
index 35f811f..61e7f47 100644
--- a/gyro_board/src/usb/CAN.c
+++ b/gyro_board/src/usb/CAN.c
@@ -231,10 +231,6 @@
     vTaskDelete(NULL);
   }
 
-  // Set all of the CAN stuff to run at CCLK/6, which translates to about 1 Mbit
-  // (1.042).
-  SC->PCLKSEL0 |= 3 << 26 | 3 << 28 | 3 << 30;
-
   // Enable CAN
   SC->PCONP |= PCONP_PCCAN1;
 
@@ -279,6 +275,11 @@
   }
 }
 
+void CAN_PCLKSEL(void) {
+  // Set all of the CAN stuff to run at CCLK/6, which translates to about 1 Mbit
+  // (1.042).
+  SC->PCLKSEL0 |= 3 << 26 | 3 << 28 | 3 << 30;
+}
 
 void initCAN(void){
   xTaskCreate(vCAN1, (signed char *) "CAN1rx", configMINIMAL_STACK_SIZE + 400, NULL, tskIDLE_PRIORITY + 1, NULL);
diff --git a/gyro_board/src/usb/CAN.h b/gyro_board/src/usb/CAN.h
index 1ef39d5..60f2d10 100644
--- a/gyro_board/src/usb/CAN.h
+++ b/gyro_board/src/usb/CAN.h
@@ -14,6 +14,9 @@
 } can_message;
 
 int CAN_get(can_message *message);
+
+// Sets up PCLKSEL for CAN stuff (errata PCLKSELx.1).
+void CAN_PCLKSEL(void);
 void initCAN(void);
 
 #endif
diff --git a/gyro_board/src/usb/LPCUSB/USB_CDC.c b/gyro_board/src/usb/LPCUSB/USB_CDC.c
deleted file mode 100644
index 47d28db..0000000
--- a/gyro_board/src/usb/LPCUSB/USB_CDC.c
+++ /dev/null
@@ -1,454 +0,0 @@
-/*
-	LPCUSB, an USB device driver for LPC microcontrollers
-	Copyright (C) 2006 Bertrik Sikken (bertrik@sikken.nl)
-
-	Redistribution and use in source and binary forms, with or without
-	modification, are permitted provided that the following conditions are met:
-
-	1. Redistributions of source code must retain the above copyright
-	   notice, this list of conditions and the following disclaimer.
-	2. Redistributions in binary form must reproduce the above copyright
-	   notice, this list of conditions and the following disclaimer in the
-	   documentation and/or other materials provided with the distribution.
-	3. The name of the author may not be used to endorse or promote products
-	   derived from this software without specific prior written permission.
-
-	THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
-	IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
-	OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
-	IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
-	INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
-	NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
-	DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
-	THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
-	(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
-	THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-*/
-
-/*
-	Minimal implementation of a USB serial port, using the CDC class.
-	This example application simply echoes everything it receives right back
-	to the host.
-
-	Windows:
-	Extract the usbser.sys file from .cab file in C:\WINDOWS\Driver Cache\i386
-	and store it somewhere (C:\temp is a good place) along with the usbser.inf
-	file. Then plug in the LPC176x and direct windows to the usbser driver.
-	Windows then creates an extra COMx port that you can open in a terminal
-	program, like hyperterminal. [Note for FreeRTOS users - the required .inf
-	file is included in the project directory.]
-
-	Linux:
-	The device should be recognised automatically by the cdc_acm driver,
-	which creates a /dev/ttyACMx device file that acts just like a regular
-	serial port.
-
-*/
-
-#include "FreeRTOS.h"
-#include "queue.h"
-#include "task.h"
-
-#include <stdio.h>
-#include <string.h>
-
-#include "usbapi.h"
-#include "usbdebug.h"
-#include "usbstruct.h"
-
-#include "LPC17xx.h"
-
-#define usbMAX_SEND_BLOCK		( 20 / portTICK_RATE_MS )
-#define usbRXBUFFER_LEN			( 80 )
-#define usbTXBUFFER_LEN			( 600 )
-
-#define INCREMENT_ECHO_BY 0
-#define BAUD_RATE	115200
-
-#define INT_IN_EP		0x81
-#define BULK_OUT_EP		0x05
-#define BULK_IN_EP		0x82
-
-#define MAX_PACKET_SIZE	64
-
-#define LE_WORD(x)		((x)&0xFF),((x)>>8)
-
-// CDC definitions
-#define CS_INTERFACE			0x24
-#define CS_ENDPOINT				0x25
-
-#define	SET_LINE_CODING			0x20
-#define	GET_LINE_CODING			0x21
-#define	SET_CONTROL_LINE_STATE	0x22
-
-// data structure for GET_LINE_CODING / SET_LINE_CODING class requests
-typedef struct {
-	unsigned long		dwDTERate;
-	unsigned char		bCharFormat;
-	unsigned char		bParityType;
-	unsigned char		bDataBits;
-} TLineCoding;
-
-static TLineCoding LineCoding = {115200, 0, 0, 8};
-static unsigned char abBulkBuf[64];
-static unsigned char abClassReqData[8];
-
-static xQueueHandle xRxedChars = NULL, xCharsForTx = NULL;
-
-// forward declaration of interrupt handler
-void USBIntHandler(void);
-
-static const unsigned char abDescriptors[] = {
-
-// device descriptor
-	0x12,
-	DESC_DEVICE,
-	LE_WORD(0x0101),		// bcdUSB
-	0x02,				// bDeviceClass
-	0x00,				// bDeviceSubClass
-	0x00,				// bDeviceProtocol
-	MAX_PACKET_SIZE0,		// bMaxPacketSize
-	LE_WORD(0xFFFF),		// idVendor
-	LE_WORD(0x0005),		// idProduct
-	LE_WORD(0x0100),		// bcdDevice
-	0x01,				// iManufacturer
-	0x02,				// iProduct
-	0x03,				// iSerialNumber
-	0x01,				// bNumConfigurations
-
-// configuration descriptor
-	0x09,
-	DESC_CONFIGURATION,
-	LE_WORD(67),			// wTotalLength
-	0x02,				// bNumInterfaces
-	0x01,				// bConfigurationValue
-	0x00,				// iConfiguration
-	0xC0,				// bmAttributes
-	0x32,				// bMaxPower
-// control class interface
-	0x09,
-	DESC_INTERFACE,
-	0x00,				// bInterfaceNumber
-	0x00,				// bAlternateSetting
-	0x01,				// bNumEndPoints
-	0x02,				// bInterfaceClass
-	0x02,				// bInterfaceSubClass
-	0x01,				// bInterfaceProtocol, linux requires value of 1 for the cdc_acm module
-	0x00,				// iInterface
-// header functional descriptor
-	0x05,
-	CS_INTERFACE,
-	0x00,
-	LE_WORD(0x0110),
-// call management functional descriptor
-	0x05,
-	CS_INTERFACE,
-	0x01,
-	0x01,				// bmCapabilities = device handles call management
-	0x01,				// bDataInterface
-// ACM functional descriptor
-	0x04,
-	CS_INTERFACE,
-	0x02,
-	0x02,				// bmCapabilities
-// union functional descriptor
-	0x05,
-	CS_INTERFACE,
-	0x06,
-	0x00,				// bMasterInterface
-	0x01,				// bSlaveInterface0
-// notification EP
-	0x07,
-	DESC_ENDPOINT,
-	INT_IN_EP,			// bEndpointAddress
-	0x03,				// bmAttributes = intr
-	LE_WORD(8),			// wMaxPacketSize
-	0x0A,				// bInterval
-// data class interface descriptor
-	0x09,
-	DESC_INTERFACE,
-	0x01,				// bInterfaceNumber
-	0x00,				// bAlternateSetting
-	0x02,				// bNumEndPoints
-	0x0A,				// bInterfaceClass = data
-	0x00,				// bInterfaceSubClass
-	0x00,				// bInterfaceProtocol
-	0x00,				// iInterface
-// data EP OUT
-	0x07,
-	DESC_ENDPOINT,
-	BULK_OUT_EP,			// bEndpointAddress
-	0x02,				// bmAttributes = bulk
-	LE_WORD(MAX_PACKET_SIZE),	// wMaxPacketSize
-	0x00,				// bInterval
-// data EP in
-	0x07,
-	DESC_ENDPOINT,
-	BULK_IN_EP,			// bEndpointAddress
-	0x02,				// bmAttributes = bulk
-	LE_WORD(MAX_PACKET_SIZE),	// wMaxPacketSize
-	0x00,				// bInterval
-
-	// string descriptors
-	0x04,
-	DESC_STRING,
-	LE_WORD(0x0409),
-
-	0x0E,
-	DESC_STRING,
-	'L', 0, 'P', 0, 'C', 0, 'U', 0, 'S', 0, 'B', 0,
-
-	0x14,
-	DESC_STRING,
-	'U', 0, 'S', 0, 'B', 0, 'S', 0, 'e', 0, 'r', 0, 'i', 0, 'a', 0, 'l', 0,
-
-	0x12,
-	DESC_STRING,
-	'A', 0, 'B', 0, 'S', 0, 'M', 0, 'o', 0, 't', 0, 'o', 0, 'r', 0,
-
-// terminating zero
-	0
-};
-
-
-/**
-	Local function to handle incoming bulk data
-
-	@param [in] bEP
-	@param [in] bEPStatus
- */
-static void BulkOut(unsigned char bEP, unsigned char bEPStatus)
-{
-	int i, iLen;
-	long lHigherPriorityTaskWoken = pdFALSE;
-
-	(void) bEPStatus;
-
-	// get data from USB into intermediate buffer
-	iLen = USBHwEPRead(bEP, abBulkBuf, sizeof(abBulkBuf));
-	for (i = 0; i < iLen; i++) {
-		// put into queue
-		xQueueSendFromISR(xRxedChars, &(abBulkBuf[ i ]), &lHigherPriorityTaskWoken);
-	}
-
-	portEND_SWITCHING_ISR(lHigherPriorityTaskWoken);
-}
-
-
-/**
-	Local function to handle outgoing bulk data
-
-	@param [in] bEP
-	@param [in] bEPStatus
- */
-static void BulkIn(unsigned char bEP, unsigned char bEPStatus)
-{
-	int i, iLen;
-	long lHigherPriorityTaskWoken = pdFALSE;
-
-	(void) bEPStatus;
-
-	if (uxQueueMessagesWaitingFromISR(xCharsForTx) == 0) {
-		// no more data, disable further NAK interrupts until next USB frame
-		USBHwNakIntEnable(0);
-		return;
-	}
-
-	// get bytes from transmit FIFO into intermediate buffer
-	for (i = 0; i < MAX_PACKET_SIZE; i++) {
-		if (xQueueReceiveFromISR(xCharsForTx, (&abBulkBuf[i]), &lHigherPriorityTaskWoken) != pdPASS) {
-			break;
-		}
-	}
-	iLen = i;
-
-	// send over USB
-	if (iLen > 0) {
-		USBHwEPWrite(bEP, abBulkBuf, iLen);
-	}
-
-	portEND_SWITCHING_ISR(lHigherPriorityTaskWoken);
-}
-
-
-/**
-	Local function to handle the USB-CDC class requests
-
-	@param [in] pSetup
-	@param [out] piLen
-	@param [out] ppbData
- */
-static BOOL HandleClassRequest(TSetupPacket *pSetup, int *piLen, unsigned char **ppbData)
-{
-	switch (pSetup->bRequest) {
-
-		// set line coding
-	case SET_LINE_CODING:
-		DBG("SET_LINE_CODING\n");
-		memcpy((unsigned char *)&LineCoding, *ppbData, 7);
-		*piLen = 7;
-		DBG("dwDTERate=%u, bCharFormat=%u, bParityType=%u, bDataBits=%u\n",
-		    LineCoding.dwDTERate,
-		    LineCoding.bCharFormat,
-		    LineCoding.bParityType,
-		    LineCoding.bDataBits);
-		break;
-
-		// get line coding
-	case GET_LINE_CODING:
-		DBG("GET_LINE_CODING\n");
-		*ppbData = (unsigned char *) & LineCoding;
-		*piLen = 7;
-		break;
-
-		// set control line state
-	case SET_CONTROL_LINE_STATE:
-		// bit0 = DTR, bit = RTS
-		DBG("SET_CONTROL_LINE_STATE %X\n", pSetup->wValue);
-		break;
-
-	default:
-		return FALSE;
-	}
-	return TRUE;
-}
-
-
-/**
-	Writes one character to VCOM port
-
-	@param [in] c character to write
-	@returns character written, or EOF if character could not be written
- */
-int VCOM_putchar(int c)
-{
-	char cc = (char) c;
-
-	if (xQueueSend(xCharsForTx, &cc, usbMAX_SEND_BLOCK) == pdPASS) {
-		return c;
-	} else {
-		return EOF;
-	}
-}
-
-
-/**
-	Reads one character from VCOM port
-
-	@returns character read, or EOF if character could not be read
- */
-int VCOM_getchar(void)
-{
-	unsigned char c;
-
-	/* Block the task until a character is available. */
-	xQueueReceive(xRxedChars, &c, portMAX_DELAY);
-	return c;
-}
-
-
-/**
-	Interrupt handler
-
-	Simply calls the USB ISR
- */
-void USB_IRQHandler(void)
-{
-	USBHwISR();
-}
-
-
-static void USBFrameHandler(unsigned short wFrame)
-{
-	(void) wFrame;
-
-	if (uxQueueMessagesWaitingFromISR(xCharsForTx) > 0) {
-		// data available, enable NAK interrupt on bulk in
-		USBHwNakIntEnable(INACK_BI);
-	}
-}
-
-unsigned long CPUcpsie(void)
-{
-	unsigned long ulRet;
-
-	//
-	// Read PRIMASK and enable interrupts.
-	//
-	__asm("    mrs     %0, PRIMASK\n"
-	      "    cpsie   i\n"
-	      "    bx      lr\n"
-      : "=r"(ulRet));
-
-	//
-	// The return is handled in the inline assembly, but the compiler will
-	// still complain if there is not an explicit return here (despite the fact
-	// that this does not result in any code being produced because of the
-	// naked attribute).
-	//
-	return(ulRet);
-}
-
-void vUSBTask(void *pvParameters)
-{
-	//int c;
-	portTickType xLastFlashTime;
-
-	/* Just to prevent compiler warnings about the unused parameter. */
-	(void) pvParameters;
-	DBG("Initialising USB stack\n");
-
-	xRxedChars = xQueueCreate(usbRXBUFFER_LEN, sizeof(char));
-	xCharsForTx = xQueueCreate(usbTXBUFFER_LEN, sizeof(char));
-
-	if ((xRxedChars == NULL) || (xCharsForTx == NULL)) {
-		/* Not enough heap available to create the buffer queues, can't do
-		anything so just delete ourselves. */
-		vTaskDelete(NULL);
-	}
-
-
-	// initialise stack
-	USBInit();
-
-	// register descriptors
-	USBRegisterDescriptors(abDescriptors);
-
-	// register class request handler
-	USBRegisterRequestHandler(REQTYPE_TYPE_CLASS, HandleClassRequest, abClassReqData);
-
-	// register endpoint handlers
-	USBHwRegisterEPIntHandler(INT_IN_EP, NULL);
-	USBHwRegisterEPIntHandler(BULK_IN_EP, BulkIn);
-	USBHwRegisterEPIntHandler(BULK_OUT_EP, BulkOut);
-
-	// register frame handler
-	USBHwRegisterFrameHandler(USBFrameHandler);
-
-	// enable bulk-in interrupts on NAKs
-	USBHwNakIntEnable(INACK_BI);
-
-	DBG("Starting USB communication\n");
-
-	NVIC_SetPriority(USB_IRQn, configUSB_INTERRUPT_PRIORITY);
-	NVIC_EnableIRQ(USB_IRQn);
-
-	// connect to bus
-
-	DBG("Connecting to USB bus\n");
-	USBHwConnect(TRUE);
-	
-	xLastFlashTime = xTaskGetTickCount();
-	
-	// echo any character received (do USB stuff in interrupt)
-	for (;;) {
-	//	c = VCOM_getchar();
-	//	if (c != EOF) {
-	//		// Echo character back with INCREMENT_ECHO_BY offset, so for example if
-	//		// INCREMENT_ECHO_BY is 1 and 'A' is received, 'B' will be echoed back.
-	//		VCOM_putchar(c + INCREMENT_ECHO_BY);
-	//	}
-		vTaskDelayUntil(&xLastFlashTime, 1000 / portTICK_RATE_MS);
-	}
-}
-
diff --git a/gyro_board/src/usb/Makefile b/gyro_board/src/usb/Makefile
index da8a4c5..a66848c 100644
--- a/gyro_board/src/usb/Makefile
+++ b/gyro_board/src/usb/Makefile
@@ -37,25 +37,27 @@
 	analog.c \
 	digital.c \
 	encoder.c \
+	gyro.c \
+	CAN.c \
 	FreeRTOS/portable/GCC/ARM_CM3/port.c \
 	FreeRTOS/tasks.c \
 	FreeRTOS/list.c \
 	FreeRTOS/queue.c \
-	CAN.c \
 	LPCUSB/usbinit.c \
 	LPCUSB/usbcontrol.c \
-	usb_device.c \
 	LPCUSB/usbhw_lpc.c \
-	gyro.c \
-	LPCUSB/usbstdreq.c
+	LPCUSB/usbstdreq.c \
+	usb_device.c \
+
+DATA_STRUCT_CHECKSUM=$(shell ./data_struct_checksum.sh)
 
 all: $(NAME).hex
 
 $(NAME).elf: Makefile $(SOURCES:.c=.o) $(LDSCRIPT)
 	$(CC) $(CFLAGS) -nostartfiles -nostdlib -T $(LDSCRIPT) -o $@ -L$(TOOLS_PREFIX)/lib/gcc/arm-eabi/4.5.1/ $(SOURCES:.c=.o) -Wa,-Map -Wa,main.map -lgcc
 
-%.o: %.c Makefile
-	$(CC) $(CFLAGS) -nostartfiles -nostdlib -c -o $@ $< -Wall -std=gnu99
+%.o: %.c Makefile data_struct_checksum.sh
+	$(CC) $(CFLAGS) -nostartfiles -nostdlib -c -o $@ $< -Wall -std=gnu99 -DDATA_STRUCT_CHECKSUM=$(DATA_STRUCT_CHECKSUM)
 
 run: deploy
 	$(FLASHER) -termonly -control $(NAME).hex $(PORT) $(SPEED) $(OSC)
diff --git a/gyro_board/src/usb/analog.c b/gyro_board/src/usb/analog.c
index b2ab48f..7968094 100644
--- a/gyro_board/src/usb/analog.c
+++ b/gyro_board/src/usb/analog.c
@@ -1,39 +1,81 @@
 #include "analog.h"
 
 #include "LPC17xx.h"
+#include "FreeRTOS.h"
+
+static int discarded_samples[4];
+
+static uint16_t raw_analog(int channel) {
+  uint32_t value;
+  switch (channel) {
+    case 0:
+      value = ADC->ADDR0;
+      break;
+    case 1:
+      value = ADC->ADDR1;
+      break;
+    case 2:
+      value = ADC->ADDR2;
+      break;
+    case 3:
+      value = ADC->ADDR3;
+      break;
+  }
+
+  return (value >> 4) & 0xFFF;
+}
+
+void TIMER1_IRQHandler(void) {
+  TIM1->IR = 1 << 0;  // clear channel 0 match
+
+  static const int kBadSampleThreshold = 175;
+  static const int kMaxBadSamples = 4;
+
+  static const uint32_t kBitShift = 16;
+  static const uint32_t kA =
+      (1.0 - 0.8408964152537146 /*0.5^0.25*/) * (1 << kBitShift) + 0.5;
+  for (int i = 0; i < 4; ++i) {
+    uint16_t current = raw_analog(i);
+    uint16_t average = averaged_values[i];
+    if ((current - average) < -kBadSampleThreshold ||
+        (current - average) > kBadSampleThreshold) {
+      ++discarded_samples[i];
+      if (discarded_samples[i] >= kMaxBadSamples) {
+        discarded_samples[i] = 0;
+        averaged_values[i] = current;
+      }
+    } else {
+      discarded_samples[i] = 0;
+      averaged_values[i] =
+          ((uint32_t)current * kA +
+           (uint32_t)average * ((1 << kBitShift) - kA)) >> kBitShift;
+    }
+  }
+}
 
 void analog_init(void) {
   SC->PCONP |= PCONP_PCAD;
 
-  // Enable AD0.0, AD0.1, AD0.2, AD0.3
+  // Enable AD0.0, AD0.1, AD0.2, and AD0.3 (0.23 - 0.26).
   PINCON->PINSEL1 &= ~(3 << 14 | 3 << 16 | 3 << 18 | 3 << 20);
   PINCON->PINSEL1 |= 1 << 14 | 1 << 16 | 1 << 18 | 1 << 20;
+  PINCON->PINMODE1 &= ~(3 << 14 | 3 << 16 | 3 << 18 | 3 << 20);
+  PINCON->PINMODE1 |= 2 << 14 | 2 << 16 | 2 << 18 | 2 << 20;
+
   ADC->ADCR = (1 << 0 | 1 << 1 | 1 << 2 | 1 << 3) /* enable all 4 */ |
-      7 << 8 /* 100MHz / 8 = 12.5MHz */ |
+      79 << 8 /* takes 208us to scan through all 4 */ |
       1 << 16 /* enable burst mode */ |
       1 << 21 /* turn on ADC */;
-}
 
-uint16_t analog(int channel) {
-  uint32_t value;
-  do {
-    switch (channel) {
-      case 0:
-        value = ADC->ADDR0;
-        break;
-      case 1:
-        value = ADC->ADDR1;
-        break;
-      case 2:
-        value = ADC->ADDR2;
-        break;
-      case 3:
-        value = ADC->ADDR3;
-        break;
-      default:
-        return 0xFFFF;
-    }
-  } while (!(value & 1 << 31));
-
-  return (value >> 4) & 0x3FF;
+  // Set up the timer for the low-pass filter.
+  SC->PCONP |= 1 << 2;
+  TIM1->PR = (configCPU_CLOCK_HZ / 2000) - 1;
+  TIM1->TC = 0;  // don't match the first time around
+  TIM1->MR0 = 1;  // match every time it wraps
+  TIM1->MCR = 1 << 0 | 1 << 1;  // interrupt and reset on match channel 0
+  // Priority 4 is higher than any FreeRTOS-managed stuff (ie USB), but lower
+  // than encoders etc.
+  NVIC_SetPriority(TIMER1_IRQn, 4);
+  NVIC_EnableIRQ(TIMER1_IRQn);
+  TIM1->TCR = 1;  // enable it
 }
diff --git a/gyro_board/src/usb/analog.h b/gyro_board/src/usb/analog.h
index 5a06290..a77ee65 100644
--- a/gyro_board/src/usb/analog.h
+++ b/gyro_board/src/usb/analog.h
@@ -3,13 +3,22 @@
 
 #include <stdint.h>
 
+// Internal variable for holding the averaged value. USE analog TO GET TO THIS
+// IN CASE IT CHANGES!
+uint16_t averaged_values[4];
+
 // Starts the hardware constantly doing conversions on all 4 of our analog
 // inputs.
 void analog_init(void);
 
 // Retrieves the most recent reading on channel (0-3).
 // Returns 0xFFFF for invalid channel.
-// 0 means 0V and 0x3FF means 3.3V.
-uint16_t analog(int channel);
+// 0 means 0V and 0xFFF means 3.3V.
+// These values are run through a low-pass filter with unreasonable readings
+// discarded first.
+static inline uint16_t analog(int channel) {
+  if (channel < 0 || channel > 3) return 0xFFFF;
+  return averaged_values[channel];
+}
 
 #endif  // __ANALOG_H__
diff --git a/gyro_board/src/usb/data_struct.h b/gyro_board/src/usb/data_struct.h
index 317b0f5..0f54fe2 100644
--- a/gyro_board/src/usb/data_struct.h
+++ b/gyro_board/src/usb/data_struct.h
@@ -13,19 +13,31 @@
 struct DATA_STRUCT_NAME {
   int64_t gyro_angle;
 
-  // In units of 100,000 counts/second.
-  uint64_t timestamp;
-
   union {
     struct {
-      // This is the USB frame number for this data. It gets incremented on
-      // every packet sent.
+      // This is the USB frame number for this data. It (theoretically) gets
+      // incremented on every packet sent, but the gyro board will deal with it
+      // correctly if it misses a frame or whatever by tracking the frame
+      // numbers sent out by the host.
       // Negative numbers mean that the gyro board has no idea what the right
       // answer is.
       // This value going down at all indicates that the code on the gyro board
       // dealing with it reset.
+      //
+      // The USB 2.0 standard says that timing of frames is 1.000ms +- 500ns.
+      // Testing with a fitpc and gyro board on 2013-10-30 by Brian gave 10us
+      // (the resolution of the timer on the gyro board that was used) of drift
+      // every 90-130 frames (~100ns per frame) and no jitter (and the timer on
+      // the gyro board isn't necessarily that good). This is plenty accurate
+      // for what we need for timing, so this number is what the code uses to do
+      // all timing calculations.
       int32_t frame_number;
 
+      // Checksum of this file calculated with sum(1).
+      // The gyro board sets this and then the fitpc checks it to make sure that
+      // they're both using the same version of this file.
+      uint16_t checksum;
+
       // Which robot (+version) the gyro board is sending out data for.
       // We should keep this in the same place for all gyro board software
       // versions so that the fitpc can detect when it's reading from a gyro
@@ -62,7 +74,9 @@
         uint8_t unknown_frame : 1;
       };
     };
-    uint64_t header;
+    struct {
+      uint64_t header0, header1;
+    };
   };
 
   // We are 64-bit aligned at this point.
diff --git a/gyro_board/src/usb/data_struct_checksum.sh b/gyro_board/src/usb/data_struct_checksum.sh
new file mode 100755
index 0000000..147a365
--- /dev/null
+++ b/gyro_board/src/usb/data_struct_checksum.sh
@@ -0,0 +1,3 @@
+#!/bin/bash
+
+sum $(dirname $0)/data_struct.h | sed 's/^\([0-9]*\) .*$/\1/'
diff --git a/gyro_board/src/usb/encoder.c b/gyro_board/src/usb/encoder.c
index c625026..c735126 100644
--- a/gyro_board/src/usb/encoder.c
+++ b/gyro_board/src/usb/encoder.c
@@ -14,19 +14,6 @@
 // before reading the indexer encoder.
 static const int kBottomFallDelayTime = 32;
 
-// How long to wait for a revolution of the shooter wheel (on the third robot)
-// before said wheel is deemed "stopped". (In secs)
-static const float kWheelStopThreshold = 2.0;
-
-// The timer to use for timestamping sensor readings.
-// This is a constant to avoid hard-coding it in a lot of places, but there ARE
-// things (PCONP bits, IRQ numbers, etc) that have this value in them
-// implicitly.
-#define SENSOR_TIMING_TIMER TIM1
-// How many counts per second SENSOR_TIMING_TIMER should be.
-// This will wrap the counter about every 1/3 of a second.
-static const int kSensorTimingRate = 100000;
-
 #define ENC(gpio, a, b) readGPIO(gpio, a) * 2 + readGPIO(gpio, b)
 int encoder_bits(int channel) {
   switch (channel) {
@@ -446,24 +433,7 @@
 
 static volatile uint32_t sensor_timing_wraps = 0;
 
-void TIMER1_IRQHandler(void) {
-  SENSOR_TIMING_TIMER->IR = 1 << 0;  // clear channel 0 match
-  ++sensor_timing_wraps;
-}
-
 void encoder_init(void) {
-  // Set up the timer for timestamping sensor readings.
-  SC->PCONP |= 1 << 2;
-  SENSOR_TIMING_TIMER->PR = (configCPU_CLOCK_HZ / kSensorTimingRate) - 1UL;
-  SENSOR_TIMING_TIMER->TC = 1;  // don't match the first time around
-  SENSOR_TIMING_TIMER->MR0 = 0;  // match every time it wraps
-  SENSOR_TIMING_TIMER->MCR = 1 << 0;  // interrupt on match channel 0
-  // Priority 4 is higher than any FreeRTOS-managed stuff (ie USB), but lower
-  // than encoders etc.
-  NVIC_SetPriority(TIMER1_IRQn, 4);
-  NVIC_EnableIRQ(TIMER1_IRQn);
-  SENSOR_TIMING_TIMER->TCR = 1;  // enable it
-
   // Setup the encoder interface.
   SC->PCONP |= PCONP_PCQEI;
   PINCON->PINSEL3 = ((PINCON->PINSEL3 & 0xffff3dff) | 0x00004100);
@@ -587,9 +557,7 @@
     packet->bad_gyro = 0;
   }
 
-  NVIC_DisableIRQ(TIMER1_IRQn);
-  packet->timestamp = ((uint64_t)sensor_timing_wraps << 32) | TIM1->TC;
-  NVIC_EnableIRQ(TIMER1_IRQn);
+  packet->checksum = DATA_STRUCT_CHECKSUM;
 
   packet->dip_switch0 = dip_switch(0);
   packet->dip_switch1 = dip_switch(1);
@@ -617,9 +585,6 @@
 
     packet->main.shooter = encoder1_val;
     packet->main.indexer = encoder3_val;
-    packet->main.battery_voltage = analog(3);
-    packet->main.left_drive_hall = analog(1);
-    packet->main.right_drive_hall = analog(2);
 
     NVIC_DisableIRQ(EINT3_IRQn);
 
@@ -643,6 +608,7 @@
     packet->main.capture_bottom_fall_delay = capture_bottom_fall_delay;
     packet->main.bottom_fall_delay_count = bottom_fall_delay_count;
     packet->main.bottom_fall_count = bottom_fall_count;
+    packet->main.bottom_rise_count = bottom_rise_count;
     packet->main.bottom_disc = !digital(1);
 
     NVIC_EnableIRQ(EINT3_IRQn);
@@ -661,6 +627,10 @@
 
     NVIC_EnableIRQ(EINT3_IRQn);
 
-    packet->main.bottom_rise_count = bottom_rise_count;
+    // Do all of the analogs last because they have the potential to be slow and
+    // jittery.
+    packet->main.battery_voltage = analog(1);
+    packet->main.left_drive_hall = analog(3);
+    packet->main.right_drive_hall = analog(2);
   }
 }
diff --git a/gyro_board/src/usb/gyro.c b/gyro_board/src/usb/gyro.c
index ad49658..40734ff 100644
--- a/gyro_board/src/usb/gyro.c
+++ b/gyro_board/src/usb/gyro.c
@@ -187,10 +187,6 @@
 static portTASK_FUNCTION(gyro_read_task, pvParameters) {
   SC->PCONP |= PCONP_PCSSP0;
 
-  // Make sure that the clock is set up right.
-  SC->PCLKSEL1 &= ~(3 << 10);
-  SC->PCLKSEL1 |= 1 << 10;
-
   // Set up SSEL.
   // It's is just a GPIO pin because we're the master (it would be special if we
   // were a slave).
diff --git a/gyro_board/src/usb/main.c b/gyro_board/src/usb/main.c
index 4e74ce7..e186bba 100644
--- a/gyro_board/src/usb/main.c
+++ b/gyro_board/src/usb/main.c
@@ -149,14 +149,19 @@
 
   setup_PLL1();
 
-  // Set everything to run at full CCLK by default.
-  SC->PCLKSEL0 = 0x55555555;
-
   /* Configure the LEDs. */
   vParTestInitialise();
 }
 
 int main(void) {
+  // Errata PCLKSELx.1 says that we have to do all of this BEFORE setting up
+  // PLL0 or it might not work.
+
+  // Set everything to run at full CCLK by default.
+  SC->PCLKSEL0 = 0x55555555;
+
+  CAN_PCLKSEL();
+
   setup_hardware();
 
   digital_init();
@@ -203,7 +208,6 @@
 
   /* Power up and feed the timer. */
   SC->PCONP |= 0x02UL;
-  SC->PCLKSEL0 = (SC->PCLKSEL0 & (~(0x3 << 2))) | (0x01 << 2);
 
   /* Reset Timer 0 */
   TIM0->TCR = TCR_COUNT_RESET;
diff --git a/gyro_board/src/usb/usb_device.c b/gyro_board/src/usb/usb_device.c
index 39c3cae..c90bd0d 100644
--- a/gyro_board/src/usb/usb_device.c
+++ b/gyro_board/src/usb/usb_device.c
@@ -260,14 +260,17 @@
 }
 
 // Instead of registering an lpcusb handler for this, we do it ourself so that
-// we can get the timing jitter down.
+// we can get the timing jitter down and deal with the frame number right.
 static void HandleFrame(void) {
   USB->USBDevIntClr = FRAME;
 
   static struct DataStruct sensor_values;
   fillSensorPacket(&sensor_values);
 
+  // What the last good frame number that we got was.
+  // Values <0 are uninitialized.
   static int32_t current_frame = -1;
+  // How many extra frames we're guessing happened since we got a good one.
   static int guessed_frames = 0;
 
   uint8_t error_status = USBHwCmdRead(CMD_DEV_READ_ERROR_STATUS);
@@ -283,6 +286,11 @@
       current_frame = read_frame;
       guessed_frames = 0;
     } else {
+      // All of the complicated stuff in here tracks the frame number from
+      // hardware (which comes from the SOF tokens sent out by the host) except
+      // deal with it if we miss a couple or get off by a little bit (and reset
+      // completely if we get off by a lot or miss a lot in a row).
+
       static const uint32_t kMaxReadFrame = 0x800;
       static const uint32_t kReadMask = kMaxReadFrame - 1;
       if ((current_frame & kReadMask) == read_frame) {
@@ -290,21 +298,24 @@
         ++guessed_frames;
       } else {
         guessed_frames = 0;
+        // The frame number that we think we should have gotten.
+        int32_t expected_frame = current_frame + guessed_frames + 1;
         int16_t difference =
-            read_frame - (int16_t)((current_frame + 1) & kReadMask);
+            read_frame - (int16_t)(expected_frame & kReadMask);
         // If we're off by only a little.
         if (difference > -10 && difference < 10) {
-          current_frame = ((current_frame + 1) & ~kReadMask) | read_frame;
-          // If we're ahead by only a little but we wrapped.
+          current_frame = (expected_frame & ~kReadMask) | read_frame;
+          // If we're ahead by only a little (or dead on) but we wrapped.
         } else if (difference > kMaxReadFrame - 10) {
           current_frame =
-              ((current_frame & ~kReadMask) - kMaxReadFrame) | read_frame;
-          // If we're behind by only a little but the packet counter wrapped.
+              ((expected_frame & ~kReadMask) - kMaxReadFrame) | read_frame;
+          // If we're behind by only a little (or dead on) but the number in the
+          // token wrapped.
         } else if (difference < -(kMaxReadFrame - 10)) {
           current_frame =
-              ((current_frame & ~kReadMask) + kMaxReadFrame) | read_frame;
+              ((expected_frame & ~kReadMask) + kMaxReadFrame) | read_frame;
         } else {
-          // Give up and reset.
+          // We're way off, so give up and reset.
           current_frame = -1;
         }
       }
diff --git a/vision/BinaryServer.cpp b/vision/BinaryServer.cpp
index 29deee9..18cf85b 100644
--- a/vision/BinaryServer.cpp
+++ b/vision/BinaryServer.cpp
@@ -18,7 +18,7 @@
 namespace frc971 {
 namespace vision {
 
-static void echo_read_cb(struct bufferevent *bev, void * /*ctx*/){
+static void echo_read_cb(struct bufferevent *bev, void * /*ctx*/) {
   struct evbuffer *input = bufferevent_get_input(bev);
   struct evbuffer *output = bufferevent_get_output(bev);
 
@@ -32,94 +32,98 @@
   evbuffer_add_buffer(output, input);
 }
 
-void BinaryServer::ErrorEvent(struct bufferevent *bev, short events){
-  if (events & BEV_EVENT_ERROR)
-    perror("Error from bufferevent");
+void BinaryServer::ErrorEvent(struct bufferevent *bev, short events) {
+  if (events & BEV_EVENT_ERROR) perror("Error from bufferevent");
   if (events & (BEV_EVENT_EOF | BEV_EVENT_ERROR)) {
     have_id = false;
     bufferevent_free(bev);
   }
 }
 
-void BinaryServer::Accept(struct evconnlistener *listener,
-    evutil_socket_t fd, struct sockaddr * /*address*/, int /*socklen*/){
+void BinaryServer::Accept(struct evconnlistener *listener, evutil_socket_t fd,
+                          struct sockaddr * /*address*/, int /*socklen*/) {
   struct event_base *base = evconnlistener_get_base(listener);
-  if(!have_id){
-    struct bufferevent *bev = bufferevent_socket_new(base, fd, BEV_OPT_CLOSE_ON_FREE);
+  if (!have_id) {
+    struct bufferevent *bev =
+        bufferevent_socket_new(base, fd, BEV_OPT_CLOSE_ON_FREE);
     _output = bufferevent_get_output(bev);
     _bufev = bev;
     have_id = true;
     int no_delay_flag = 1;
-    setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &no_delay_flag,  sizeof(no_delay_flag));
+    setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &no_delay_flag,
+               sizeof(no_delay_flag));
 
     bufferevent_setcb(bev, echo_read_cb, NULL, StaticErrorEvent, this);
 
     bufferevent_enable(bev, EV_READ | EV_WRITE);
   }
 }
-static void accept_error_cb(struct evconnlistener *listener, void * /*ctx*/)
-{
+static void accept_error_cb(struct evconnlistener *listener, void * /*ctx*/) {
   struct event_base *base = evconnlistener_get_base(listener);
   int err = EVUTIL_SOCKET_ERROR();
   fprintf(stderr, "Got an error %d (%s) on the listener. "
-      "Shutting down.\n", err, evutil_socket_error_to_string(err));
+                  "Shutting down.\n",
+          err, evutil_socket_error_to_string(err));
 
   event_base_loopexit(base, NULL);
 }
 
-void BinaryServer::StartServer(uint16_t port){
+void BinaryServer::StartServer(uint16_t port) {
   _fd = socket(AF_INET, SOCK_STREAM, 0);
   struct sockaddr_in sin;
   memset(&sin, 0, sizeof(sin));
   sin.sin_family = AF_INET;
-  sin.sin_port = htons( port );
+  sin.sin_port = htons(port);
   sin.sin_addr.s_addr = inet_addr("0.0.0.0");
 
-  listener = evconnlistener_new_bind(_base, StaticAccept, this,
-      LEV_OPT_CLOSE_ON_FREE | LEV_OPT_REUSEABLE, -1,
-      (struct sockaddr *) (void *)&sin, sizeof(sin));
+  listener = evconnlistener_new_bind(
+      _base, StaticAccept, this, LEV_OPT_CLOSE_ON_FREE | LEV_OPT_REUSEABLE, -1,
+      (struct sockaddr *)(void *)&sin, sizeof(sin));
 
   if (!listener) {
-    fprintf(stderr,"%s:%d: Couldn't create listener\n", __FILE__, __LINE__);
+    fprintf(stderr, "%s:%d: Couldn't create listener\n", __FILE__, __LINE__);
     exit(-1);
   }
 
   evconnlistener_set_error_cb(listener, accept_error_cb);
 }
 
-void BinaryServer::Notify(int fd,short /*what*/){
+void BinaryServer::Notify(int fd, short /*what*/) {
   char notes[4096];
-  int count = read(fd,notes,4096);
-  if(count == 0){
+  int count = read(fd, notes, 4096);
+  if (count == 0) {
     close(fd);
-    fprintf(stderr,"%s:%d: Error No cheeze from OpenCV task!!!\n",__FILE__,__LINE__);
+    fprintf(stderr, "%s:%d: Error No cheeze from OpenCV task!!!\n", __FILE__,
+            __LINE__);
     exit(-1);
   }
-  printf("notified!: %d\n",count);
-  if(have_id){
+  printf("notified!: %d\n", count);
+  if (have_id) {
     printf("got someone to read my stuff!\n");
     char *binary_data;
     size_t len;
-    if(_notify->GetData(&binary_data,&len)){
+    if (_notify->GetData(&binary_data, &len)) {
       printf("here is for sending\n");
-      evbuffer_add_reference(_output, binary_data, len, PacketNotifier::StaticDataSent,_notify);
-      printf("this is how sending went %d\n",bufferevent_flush(_bufev,EV_WRITE, BEV_FLUSH));
+      evbuffer_add_reference(_output, binary_data, len,
+                             PacketNotifier::StaticDataSent, _notify);
+      printf("this is how sending went %d\n",
+             bufferevent_flush(_bufev, EV_WRITE, BEV_FLUSH));
     }
   }
 }
 
-//Constructor
-BinaryServer::BinaryServer(uint16_t port, 
-    frc971::vision::PacketNotifier *notify) :
-  _base(event_base_new()) {
-    have_id = false;
-    StartServer(port);
-    _notify = notify;
-    frame_notify = event_new(_base, notify->RecieverFD(), 
-        EV_READ|EV_PERSIST, StaticNotify, this);
-    event_add(frame_notify,NULL);
-    event_base_dispatch(_base);
-  }
+// Constructor
+BinaryServer::BinaryServer(uint16_t port,
+                           frc971::vision::PacketNotifier *notify)
+    : _base(event_base_new()) {
+  have_id = false;
+  StartServer(port);
+  _notify = notify;
+  frame_notify = event_new(_base, notify->RecieverFD(), EV_READ | EV_PERSIST,
+                           StaticNotify, this);
+  event_add(frame_notify, NULL);
+  event_base_dispatch(_base);
+}
 
 }  // namespace vision
 }  // namespace frc971
diff --git a/vision/CameraProcessor.cpp b/vision/CameraProcessor.cpp
index 56bd36e..856e12b 100644
--- a/vision/CameraProcessor.cpp
+++ b/vision/CameraProcessor.cpp
@@ -459,7 +459,7 @@
             raw_contour, rect, check, is_90));
     }
     if (contour.size() == 4 && cullObvious(rect, contourArea(contour))) {
-    	LOG(INFO, "check= %.2f\n", check);
+    	LOG(DEBUG, "check= %.2f\n", check);
     }
   }
 }
diff --git a/vision/GoalMaster.cpp b/vision/GoalMaster.cpp
index 3155cf7..5c8fad8 100644
--- a/vision/GoalMaster.cpp
+++ b/vision/GoalMaster.cpp
@@ -46,7 +46,8 @@
            kMetersToShooterAngles,
            meters);
 
-      LOG(DEBUG, "think target is %f meters away Speed %f Angle %f\n",
+      LOG(DEBUG, "%+f=> think target is %f meters away Speed %f Angle %f\n",
+          targets->percent_elevation_off_center,
           meters, shooter_speed, shooter_angle);
 
       target_angle.MakeWithBuilder()
diff --git a/vision/OpenCVWorkTask.cpp b/vision/OpenCVWorkTask.cpp
index 9d68065..f17803e 100644
--- a/vision/OpenCVWorkTask.cpp
+++ b/vision/OpenCVWorkTask.cpp
@@ -4,11 +4,13 @@
 #include <sys/mman.h>
 #include <errno.h>
 #include <string.h>
-#include <vector>
 #include <netinet/in.h>
 #include <netinet/tcp.h>
 #include <arpa/inet.h>
 
+#include <vector>
+#include <iostream>
+
 #include "aos/common/time.h"
 #include "aos/atom_code/camera/Buffers.h"
 #include "aos/externals/libjpeg/include/jpeglib.h"
@@ -17,8 +19,6 @@
 
 #include "vision/OpenCVWorkTask.h"
 #include "vision/CameraProcessor.h"
-#include "vision/BinaryServer.h"
-#include "vision/PacketNotifier.h"
 #include "vision/JPEGRoutines.h"
 
 
@@ -28,10 +28,6 @@
 }  // namespace vision
 }  // namespace frc971
 
-void reciever_main(frc971::vision::PacketNotifier *notify){
-  frc971::vision::BinaryServer test(8020,notify);
-}
-
 namespace {
 void SaveImageToFile(IplImage *image, const char *filename) {
   FILE *file = fopen(filename, "w");
@@ -56,13 +52,13 @@
 #include "frc971/queues/CameraTarget.q.h"
 using frc971::vision::targets;
 
-#include <iostream>
-void sender_main(frc971::vision::PacketNotifier *notify){
-  ::aos::InitNRT();
+void sender_main(){
   ::aos::camera::Buffers buffers;
   CvSize size;
   size.width = ::aos::camera::Buffers::Buffers::kWidth;
   size.height = ::aos::camera::Buffers::Buffers::kHeight;
+  unsigned char buffer[::aos::camera::Buffers::Buffers::kWidth *
+      ::aos::camera::Buffers::Buffers::kHeight * 3];
 
   // create processing object
   ProcessorData processor(size.width, size.height, false);
@@ -73,17 +69,15 @@
     //usleep(7500);
     size_t data_size;
   	timeval timestamp_timeval;
+    LOG(DEBUG, "getting new image\n");
     const void *image = buffers.GetNext(
 		    true, &data_size, &timestamp_timeval, NULL);
     ::aos::time::Time timestamp(timestamp_timeval);
 
-    //TODO(pschuh): find proper way to cast away const for this: :(
-    // parker you prolly want const_cast<type>(var);
-    LOG(INFO, "Got new image\n");
-    unsigned char *buffer = (unsigned char *)notify->GetBuffer();
-    frc971::vision::process_jpeg(buffer,
-                                 (unsigned char *)const_cast<void *>(image),
-                                 data_size);
+    LOG(DEBUG, "Got new image\n");
+    frc971::vision::process_jpeg(
+        buffer, static_cast<unsigned char *>(const_cast<void *>(image)),
+        data_size);
 
     // build the headers on top of the buffer
     cvSetData(processor.src_header_image,
@@ -104,7 +98,7 @@
     std::vector<Target>::iterator target_it;
     Target *best_target = NULL;
     // run through the targets
-    LOG(INFO, "Found %u targets\n", processor.target_list.size());
+    LOG(DEBUG, "Found %u targets\n", processor.target_list.size());
     for(target_it = processor.target_list.begin();
         target_it != processor.target_list.end(); target_it++){
       //target_contours.push_back(*(target_it->this_contour));
@@ -119,7 +113,7 @@
     }
     // if we found one then send it on
     if (best_target != NULL) {
-      LOG(INFO, "Target is %f\n", best_target->rect.centroid.x);
+      LOG(DEBUG, "Target is %f\n", best_target->rect.centroid.x);
       targets.MakeWithBuilder()
         .percent_azimuth_off_center(
             best_target->rect.centroid.y / (double)::aos::camera::Buffers::kHeight - 0.5)
@@ -128,29 +122,17 @@
         .timestamp(timestamp.ToNSec())
         .Send();
     }
-    notify->Notify();
     //static int counter = 0;
     //if (++counter > 2) {
       //break;
     //}
   }
-  ::aos::Cleanup();
 }
 
 
 int main(int /*argc*/, char** /*argv*/){
-  frc971::vision::PacketNotifier *notify = frc971::vision::PacketNotifier::MMap(
-      ::aos::camera::Buffers::kHeight * ::aos::camera::Buffers::kWidth * 3);
-  pid_t pid = fork();
-  if(pid < 0){
-    fprintf(stderr,"%s:%d: Error in fork()\n",__FILE__,__LINE__);
-  }
-  if(pid == 0){
-    notify->RegisterSender();
-    sender_main(notify);
-  }else{
-    notify->RegisterReciever();
-    reciever_main(notify);
-  }
+  ::aos::InitNRT();
+  sender_main();
+  ::aos::Cleanup();
 }
 
diff --git a/vision/SensorProcessor.h b/vision/SensorProcessor.h
index c219245..daf24be 100644
--- a/vision/SensorProcessor.h
+++ b/vision/SensorProcessor.h
@@ -10,27 +10,31 @@
 } Interpolation;
 
 static const Interpolation kPixelsToMeters[] = {
-	{43.0 / 320.0, 12.573},
-	{98.0 / 320.0, 6.604},
-	{145.75 / 320.0, 4.420},
-	{216.75 / 320.0, 2.794},
+  {-0.050781, 4.7498},
+  {-0.0375, 4.318},
+  {0.028125, 3.9878},
+  {0.080469, 3.51},
+  {0.126563, 3.1496},
+  {0.131, 2.9972},
+  {0.144, 2.921},
+  {0.196, 3.2258},
+  // Below here is junk because it starts coming off of the tower base.
+  {0.296875, 2.667},
+  {0.351562, 2.3876},
 };
 
 // Must be in reverse order in meters.
 static const Interpolation kMetersToShooterSpeeds[] = {
-  {12.5, 375.0},
-  {21.0, 360.0},
-  {25.0, 375.0},
+  {2.0, 375.0},
+  {3.0, 360.0},
+  {4.5, 375.0},
 };
 
 static const Interpolation kMetersToShooterAngles[] = {
-  {0.0, 0.7267},
-  {12.5, 0.7267},
-  {16.5, 0.604},
-  {18.0, 0.587},
-  {20.0, 0.576},
-  {21.0, 0.550},
-  {23.0, 0.540},
+  {3.0, 0.68},
+  {3.7, 0.635},
+  {4.15, 0.58},
+  {5.0, 0.51},
 };
 
 double interpolate(int num_interp_vals,
diff --git a/vision/vision.gyp b/vision/vision.gyp
index 8fe50a4..df27045 100644
--- a/vision/vision.gyp
+++ b/vision/vision.gyp
@@ -6,8 +6,8 @@
       'sources': [
         'OpenCVWorkTask.cpp',
         'CameraProcessor.cpp',
-        'BinaryServer.cpp',
-        'PacketNotifier.cpp',
+        #'BinaryServer.cpp',
+        #'PacketNotifier.cpp',
         'JPEGRoutines.cpp',
       ],
       'dependencies': [