Copy back a lot of the 2014 code.

Change-Id: I552292d8bd7bce4409e02d254bef06a9cc009568
diff --git a/y2014/actors/actors.gyp b/y2014/actors/actors.gyp
new file mode 100644
index 0000000..291e597
--- /dev/null
+++ b/y2014/actors/actors.gyp
@@ -0,0 +1,111 @@
+{
+  'targets': [
+    {
+      'target_name': 'binaries',
+      'type': 'none',
+      'dependencies': [
+        'drivetrain_action',
+        'shoot_action',
+      ],
+    },
+    {
+      'target_name': 'shoot_action_queue',
+      'type': 'static_library',
+      'sources': ['shoot_action.q'],
+      'variables': {
+        'header_path': 'y2014/actors',
+      },
+      'dependencies': [
+        '<(AOS)/common/actions/actions.gyp:action_queue',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/actions/actions.gyp:action_queue',
+      ],
+      'includes': ['../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'shoot_action_lib',
+      'type': 'static_library',
+      'sources': [
+        'shoot_actor.cc',
+      ],
+      'dependencies': [
+        'shoot_action_queue',
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+        '<(DEPTH)/y2014/queues/queues.gyp:profile_params',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(DEPTH)/y2014/control_loops/shooter/shooter.gyp:shooter_queue',
+        '<(DEPTH)/y2014/control_loops/claw/claw.gyp:claw_queue',
+        '<(DEPTH)/y2014/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
+        '<(DEPTH)/y2014/y2014.gyp:constants',
+      ],
+      'export_dependent_settings': [
+        'shoot_action_queue',
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+      ],
+    },
+    {
+      'target_name': 'shoot_action',
+      'type': 'executable',
+      'sources': [
+        'shoot_actor_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'shoot_action_lib',
+        'shoot_action_queue',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_action_queue',
+      'type': 'static_library',
+      'sources': ['drivetrain_action.q'],
+      'variables': {
+        'header_path': 'y2014/actors',
+      },
+      'dependencies': [
+        '<(AOS)/common/actions/actions.gyp:action_queue',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/actions/actions.gyp:action_queue',
+      ],
+      'includes': ['../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'drivetrain_action_lib',
+      'type': 'static_library',
+      'sources': [
+        'drivetrain_actor.cc',
+      ],
+      'dependencies': [
+        'drivetrain_action_queue',
+        '<(DEPTH)/y2014/y2014.gyp:constants',
+        '<(AOS)/common/common.gyp:time',
+        '<(AOS)/common/util/util.gyp:phased_loop',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+        '<(EXTERNALS):eigen',
+        '<(AOS)/common/util/util.gyp:trapezoid_profile',
+        '<(DEPTH)/y2014/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+        'drivetrain_action_queue',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_action',
+      'type': 'executable',
+      'sources': [
+        'drivetrain_actor_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+        'drivetrain_action_queue',
+        'drivetrain_action_lib',
+      ],
+    },
+  ],
+}
diff --git a/y2014/actors/drivetrain_action.q b/y2014/actors/drivetrain_action.q
new file mode 100644
index 0000000..9ad55d3
--- /dev/null
+++ b/y2014/actors/drivetrain_action.q
@@ -0,0 +1,29 @@
+package frc971.actors;
+
+import "aos/common/actions/actions.q";
+
+// Parameters to send with start.
+struct DrivetrainActionParams {
+  double left_initial_position;
+  double right_initial_position;
+  double y_offset;
+  double theta_offset;
+  double maximum_velocity;
+  double maximum_acceleration;
+  double maximum_turn_velocity;
+  double maximum_turn_acceleration;
+};
+
+queue_group DrivetrainActionQueueGroup {
+  implements aos.common.actions.ActionQueueGroup;
+
+  message Goal {
+    uint32_t run;
+    DrivetrainActionParams params;
+  };
+
+  queue Goal goal;
+  queue aos.common.actions.Status status;
+};
+
+queue_group DrivetrainActionQueueGroup drivetrain_action;
diff --git a/y2014/actors/drivetrain_actor.cc b/y2014/actors/drivetrain_actor.cc
new file mode 100644
index 0000000..3cf86bd
--- /dev/null
+++ b/y2014/actors/drivetrain_actor.cc
@@ -0,0 +1,168 @@
+#include "y2014/actors/drivetrain_actor.h"
+
+#include <functional>
+#include <numeric>
+
+#include <Eigen/Dense>
+
+#include "aos/common/util/phased_loop.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/util/trapezoid_profile.h"
+#include "aos/common/commonmath.h"
+#include "aos/common/time.h"
+
+#include "y2014/actors/drivetrain_actor.h"
+#include "y2014/constants.h"
+#include "y2014/control_loops/drivetrain/drivetrain.q.h"
+
+namespace frc971 {
+namespace actors {
+
+DrivetrainActor::DrivetrainActor(actors::DrivetrainActionQueueGroup* s)
+    : aos::common::actions::ActorBase<actors::DrivetrainActionQueueGroup>(s) {}
+
+bool DrivetrainActor::RunAction(const actors::DrivetrainActionParams &params) {
+  static const auto K = constants::GetValues().make_drivetrain_loop().K();
+
+  const double yoffset = params.y_offset;
+  const double turn_offset =
+      params.theta_offset * constants::GetValues().turn_width / 2.0;
+  LOG(INFO, "Going to move %f and turn %f\n", yoffset, turn_offset);
+
+  // Measured conversion to get the distance right.
+  ::aos::util::TrapezoidProfile profile(::aos::time::Time::InMS(5));
+  ::aos::util::TrapezoidProfile turn_profile(::aos::time::Time::InMS(5));
+  const double goal_velocity = 0.0;
+  const double epsilon = 0.01;
+  ::Eigen::Matrix<double, 2, 1> left_goal_state, right_goal_state;
+
+  profile.set_maximum_acceleration(params.maximum_acceleration);
+  profile.set_maximum_velocity(params.maximum_velocity);
+  turn_profile.set_maximum_acceleration(params.maximum_turn_acceleration *
+                                        constants::GetValues().turn_width /
+                                        2.0);
+  turn_profile.set_maximum_velocity(params.maximum_turn_velocity *
+                                    constants::GetValues().turn_width / 2.0);
+
+  while (true) {
+    ::aos::time::PhasedLoopXMS(10, 5000);
+
+    control_loops::drivetrain_queue.status.FetchLatest();
+    if (control_loops::drivetrain_queue.status.get()) {
+      const auto& status = *control_loops::drivetrain_queue.status;
+      if (::std::abs(status.uncapped_left_voltage -
+                     status.uncapped_right_voltage) > 24) {
+        LOG(DEBUG, "spinning in place\n");
+        // They're more than 24V apart, so stop moving forwards and let it deal
+        // with spinning first.
+        profile.SetGoal(
+            (status.filtered_left_position + status.filtered_right_position -
+             params.left_initial_position - params.right_initial_position) /
+            2.0);
+      } else {
+        static const double divisor = K(0, 0) + K(0, 2);
+        double dx_left, dx_right;
+        if (status.uncapped_left_voltage > 12.0) {
+          dx_left = (status.uncapped_left_voltage - 12.0) / divisor;
+        } else if (status.uncapped_left_voltage < -12.0) {
+          dx_left = (status.uncapped_left_voltage + 12.0) / divisor;
+        } else {
+          dx_left = 0;
+        }
+        if (status.uncapped_right_voltage > 12.0) {
+          dx_right = (status.uncapped_right_voltage - 12.0) / divisor;
+        } else if (status.uncapped_right_voltage < -12.0) {
+          dx_right = (status.uncapped_right_voltage + 12.0) / divisor;
+        } else {
+          dx_right = 0;
+        }
+        double dx;
+        if (dx_left == 0 && dx_right == 0) {
+          dx = 0;
+        } else if (dx_left != 0 && dx_right != 0 &&
+                   ::aos::sign(dx_left) != ::aos::sign(dx_right)) {
+          // Both saturating in opposite directions. Don't do anything.
+          LOG(DEBUG, "Saturating opposite ways, not adjusting\n");
+          dx = 0;
+        } else if (::std::abs(dx_left) > ::std::abs(dx_right)) {
+          dx = dx_left;
+        } else {
+          dx = dx_right;
+        }
+        if (dx != 0) {
+          LOG(DEBUG, "adjusting goal by %f\n", dx);
+          profile.MoveGoal(-dx);
+        }
+      }
+    } else {
+      // If we ever get here, that's bad and we should just give up
+      LOG(ERROR, "no drivetrain status!\n");
+      return false;
+    }
+
+    const auto drive_profile_goal_state =
+        profile.Update(yoffset, goal_velocity);
+    const auto turn_profile_goal_state = turn_profile.Update(turn_offset, 0.0);
+    left_goal_state = drive_profile_goal_state - turn_profile_goal_state;
+    right_goal_state = drive_profile_goal_state + turn_profile_goal_state;
+
+    if (::std::abs(drive_profile_goal_state(0, 0) - yoffset) < epsilon &&
+        ::std::abs(turn_profile_goal_state(0, 0) - turn_offset) < epsilon) {
+      break;
+    }
+
+    if (ShouldCancel()) return true;
+
+    LOG(DEBUG, "Driving left to %f, right to %f\n",
+        left_goal_state(0, 0) + params.left_initial_position,
+        right_goal_state(0, 0) + params.right_initial_position);
+    control_loops::drivetrain_queue.goal.MakeWithBuilder()
+        .control_loop_driving(true)
+        //.highgear(false)
+        .left_goal(left_goal_state(0, 0) + params.left_initial_position)
+        .right_goal(right_goal_state(0, 0) + params.right_initial_position)
+        .left_velocity_goal(left_goal_state(1, 0))
+        .right_velocity_goal(right_goal_state(1, 0))
+        .Send();
+  }
+  if (ShouldCancel()) return true;
+  control_loops::drivetrain_queue.status.FetchLatest();
+  while (!control_loops::drivetrain_queue.status.get()) {
+    LOG(WARNING,
+        "No previous drivetrain status packet, trying to fetch again\n");
+    control_loops::drivetrain_queue.status.FetchNextBlocking();
+    if (ShouldCancel()) return true;
+  }
+  while (true) {
+    if (ShouldCancel()) return true;
+    const double kPositionThreshold = 0.05;
+
+    const double left_error = ::std::abs(
+        control_loops::drivetrain_queue.status->filtered_left_position -
+        (left_goal_state(0, 0) + params.left_initial_position));
+    const double right_error = ::std::abs(
+        control_loops::drivetrain_queue.status->filtered_right_position -
+        (right_goal_state(0, 0) + params.right_initial_position));
+    const double velocity_error =
+        ::std::abs(control_loops::drivetrain_queue.status->robot_speed);
+    if (left_error < kPositionThreshold && right_error < kPositionThreshold &&
+        velocity_error < 0.2) {
+      break;
+    } else {
+      LOG(DEBUG, "Drivetrain error is %f, %f, %f\n", left_error, right_error,
+          velocity_error);
+    }
+    control_loops::drivetrain_queue.status.FetchNextBlocking();
+  }
+  LOG(INFO, "Done moving\n");
+  return true;
+}
+
+::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
+    const ::frc971::actors::DrivetrainActionParams& params) {
+  return ::std::unique_ptr<DrivetrainAction>(
+      new DrivetrainAction(&::frc971::actors::drivetrain_action, params));
+}
+
+}  // namespace actors
+}  // namespace frc971
diff --git a/y2014/actors/drivetrain_actor.h b/y2014/actors/drivetrain_actor.h
new file mode 100644
index 0000000..aa8f0b3
--- /dev/null
+++ b/y2014/actors/drivetrain_actor.h
@@ -0,0 +1,31 @@
+#ifndef Y2014_ACTIONS_DRIVETRAIN_ACTION_H_
+#define Y2014_ACTIONS_DRIVETRAIN_ACTION_H_
+
+#include <memory>
+
+#include "y2014/actors/drivetrain_action.q.h"
+#include "aos/common/actions/actor.h"
+#include "aos/common/actions/actions.h"
+
+namespace frc971 {
+namespace actors {
+
+class DrivetrainActor
+    : public aos::common::actions::ActorBase<DrivetrainActionQueueGroup> {
+ public:
+  explicit DrivetrainActor(DrivetrainActionQueueGroup* s);
+
+  bool RunAction(const actors::DrivetrainActionParams &params) override;
+};
+
+typedef aos::common::actions::TypedAction<DrivetrainActionQueueGroup>
+    DrivetrainAction;
+
+// Makes a new DrivetrainActor action.
+::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
+    const ::frc971::actors::DrivetrainActionParams& params);
+
+}  // namespace actors
+}  // namespace frc971
+
+#endif
diff --git a/y2014/actors/drivetrain_actor_main.cc b/y2014/actors/drivetrain_actor_main.cc
new file mode 100644
index 0000000..375e71c
--- /dev/null
+++ b/y2014/actors/drivetrain_actor_main.cc
@@ -0,0 +1,18 @@
+#include <stdio.h>
+
+#include "aos/linux_code/init.h"
+#include "y2014/actors/drivetrain_action.q.h"
+#include "y2014/actors/drivetrain_actor.h"
+
+using ::aos::time::Time;
+
+int main(int /*argc*/, char * /*argv*/[]) {
+  ::aos::Init();
+
+  frc971::actors::DrivetrainActor drivetrain(
+      &::frc971::actors::drivetrain_action);
+  drivetrain.Run();
+
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2014/actors/shoot_action.q b/y2014/actors/shoot_action.q
new file mode 100644
index 0000000..1c545aa
--- /dev/null
+++ b/y2014/actors/shoot_action.q
@@ -0,0 +1,12 @@
+package frc971.actors;
+
+import "aos/common/actions/actions.q";
+
+queue_group ShootActionQueueGroup {
+  implements frc971.actions.ActionQueueGroup;
+
+  queue aos.common.actions.Goal goal;
+  queue aos.common.actions.Status status;
+};
+
+queue_group ShootActionQueueGroup shoot_action;
diff --git a/y2014/actors/shoot_actor.cc b/y2014/actors/shoot_actor.cc
new file mode 100644
index 0000000..9db34c4
--- /dev/null
+++ b/y2014/actors/shoot_actor.cc
@@ -0,0 +1,178 @@
+#include "y2014/actors/shoot_actor.h"
+
+#include <functional>
+
+#include "aos/common/logging/logging.h"
+
+#include "y2014/control_loops/shooter/shooter.q.h"
+#include "y2014/control_loops/claw/claw.q.h"
+#include "y2014/constants.h"
+#include "y2014/control_loops/drivetrain/drivetrain.q.h"
+
+namespace frc971 {
+namespace actors {
+namespace {
+
+bool IntakeOff() {
+  control_loops::claw_queue.goal.FetchLatest();
+  if (!control_loops::claw_queue.goal.get()) {
+    LOG(WARNING, "no claw goal\n");
+    // If it doesn't have a goal, then the intake isn't on so we don't have to
+    // turn it off.
+    return true;
+  } else {
+    if (!control_loops::claw_queue.goal.MakeWithBuilder()
+             .bottom_angle(control_loops::claw_queue.goal->bottom_angle)
+             .separation_angle(control_loops::claw_queue.goal->separation_angle)
+             .intake(0.0)
+             .centering(0.0)
+             .Send()) {
+      LOG(WARNING, "sending claw goal failed\n");
+      return false;
+    }
+  }
+  return true;
+}
+
+}  // namespace
+
+constexpr double ShootActor::kOffsetRadians;
+constexpr double ShootActor::kClawShootingSeparation;
+constexpr double ShootActor::kClawShootingSeparationGoal;
+
+ShootActor::ShootActor(actors::ShootActionQueueGroup* s)
+    : ::aos::common::actions::ActorBase<actors::ShootActionQueueGroup>(s) {}
+
+double ShootActor::SpeedToAngleOffset(double speed) {
+  const frc971::constants::Values& values = frc971::constants::GetValues();
+  // scale speed to a [0.0-1.0] on something close to the max
+  return (speed / values.drivetrain_max_speed) * kOffsetRadians;
+}
+
+bool ShootActor::RunAction(const double&) {
+  InnerRunAction();
+
+  // Now do our 'finally' block and make sure that we aren't requesting shots
+  // continually.
+  control_loops::shooter_queue.goal.FetchLatest();
+  if (control_loops::shooter_queue.goal.get() == nullptr) {
+    return true;
+  }
+  if (!control_loops::shooter_queue.goal.MakeWithBuilder()
+           .shot_power(control_loops::shooter_queue.goal->shot_power)
+           .shot_requested(false)
+           .unload_requested(false)
+           .load_requested(false)
+           .Send()) {
+    LOG(WARNING, "sending shooter goal failed\n");
+    return false;
+  }
+
+  LOG(INFO, "finished\n");
+  return true;
+}
+
+void ShootActor::InnerRunAction() {
+  LOG(INFO, "Shooting at the current angle and power.\n");
+
+  // wait for claw to be ready
+  if (WaitUntil(::std::bind(&ShootActor::DoneSetupShot, this))) {
+    return;
+  }
+
+  if (!IntakeOff()) return;
+
+  // Make sure that we have the latest shooter status.
+  control_loops::shooter_queue.status.FetchLatest();
+  // Get the number of shots fired up to this point. This should not be updated
+  // again for another few cycles.
+  previous_shots_ = control_loops::shooter_queue.status->shots;
+  // Shoot!
+  if (!control_loops::shooter_queue.goal.MakeWithBuilder()
+           .shot_power(control_loops::shooter_queue.goal->shot_power)
+           .shot_requested(true)
+           .unload_requested(false)
+           .load_requested(false)
+           .Send()) {
+    LOG(WARNING, "sending shooter goal failed\n");
+    return;
+  }
+
+  // wait for record of shot having been fired
+  if (WaitUntil(::std::bind(&ShootActor::DoneShot, this))) return;
+
+  if (!IntakeOff()) return;
+}
+
+bool ClawIsReady() {
+  control_loops::claw_queue.goal.FetchLatest();
+
+  bool ans =
+      control_loops::claw_queue.status->zeroed &&
+      (::std::abs(control_loops::claw_queue.status->bottom_velocity) < 0.5) &&
+      (::std::abs(control_loops::claw_queue.status->bottom -
+                  control_loops::claw_queue.goal->bottom_angle) < 0.10) &&
+      (::std::abs(control_loops::claw_queue.status->separation -
+                  control_loops::claw_queue.goal->separation_angle) < 0.4);
+  LOG(DEBUG, "Claw is %sready zeroed %d bottom_velocity %f bottom %f sep %f\n",
+      ans ? "" : "not ", control_loops::claw_queue.status->zeroed,
+      ::std::abs(control_loops::claw_queue.status->bottom_velocity),
+      ::std::abs(control_loops::claw_queue.status->bottom -
+                 control_loops::claw_queue.goal->bottom_angle),
+      ::std::abs(control_loops::claw_queue.status->separation -
+                 control_loops::claw_queue.goal->separation_angle));
+  return ans;
+}
+
+bool ShooterIsReady() {
+  control_loops::shooter_queue.goal.FetchLatest();
+
+  LOG(DEBUG, "Power error is %f - %f -> %f, ready %d\n",
+      control_loops::shooter_queue.status->hard_stop_power,
+      control_loops::shooter_queue.goal->shot_power,
+      ::std::abs(control_loops::shooter_queue.status->hard_stop_power -
+                 control_loops::shooter_queue.goal->shot_power),
+      control_loops::shooter_queue.status->ready);
+  return (::std::abs(control_loops::shooter_queue.status->hard_stop_power -
+                     control_loops::shooter_queue.goal->shot_power) < 1.0) &&
+         control_loops::shooter_queue.status->ready;
+}
+
+bool ShootActor::DoneSetupShot() {
+  control_loops::shooter_queue.status.FetchAnother();
+  control_loops::claw_queue.status.FetchAnother();
+  // Make sure that both the shooter and claw have reached the necessary
+  // states.
+  if (ShooterIsReady() && ClawIsReady()) {
+    LOG(INFO, "Claw and Shooter ready for shooting.\n");
+    return true;
+  }
+
+  return false;
+}
+
+bool ShootActor::DonePreShotOpen() {
+  control_loops::claw_queue.status.FetchAnother();
+  if (control_loops::claw_queue.status->separation > kClawShootingSeparation) {
+    LOG(INFO, "Opened up enough to shoot.\n");
+    return true;
+  }
+  return false;
+}
+
+bool ShootActor::DoneShot() {
+  control_loops::shooter_queue.status.FetchAnother();
+  if (control_loops::shooter_queue.status->shots > previous_shots_) {
+    LOG(INFO, "Shot succeeded!\n");
+    return true;
+  }
+  return false;
+}
+
+::std::unique_ptr<ShootAction> MakeShootAction() {
+  return ::std::unique_ptr<ShootAction>(
+      new ShootAction(&::frc971::actors::shoot_action, 0.0));
+}
+
+}  // namespace actors
+}  // namespace frc971
diff --git a/y2014/actors/shoot_actor.h b/y2014/actors/shoot_actor.h
new file mode 100644
index 0000000..3adfe31
--- /dev/null
+++ b/y2014/actors/shoot_actor.h
@@ -0,0 +1,52 @@
+#ifndef Y2014_ACTORS_SHOOT_ACTOR_H_
+#define Y2014_ACTORS_SHOOT_ACTOR_H_
+
+#include <memory>
+
+#include "aos/common/actions/actor.h"
+#include "aos/common/actions/actions.h"
+
+#include "y2014/actors/shoot_action.q.h"
+
+namespace frc971 {
+namespace actors {
+
+class ShootActor
+    : public ::aos::common::actions::ActorBase<actors::ShootActionQueueGroup> {
+ public:
+  explicit ShootActor(actors::ShootActionQueueGroup* s);
+
+  // Actually execute the action of moving the claw and shooter into position
+  // and actually firing them.
+  bool RunAction(const double &params) override;
+  void InnerRunAction();
+
+  // calc an offset to our requested shot based on robot speed
+  double SpeedToAngleOffset(double speed);
+
+  static constexpr double kOffsetRadians = 0.4;
+  static constexpr double kClawShootingSeparation = 0.10;
+  static constexpr double kClawShootingSeparationGoal = 0.10;
+
+ protected:
+  // completed shot
+  bool DoneShot();
+  // ready for shot
+  bool DonePreShotOpen();
+  // in the right place
+  bool DoneSetupShot();
+
+  // to track when shot is complete
+  int previous_shots_;
+};
+
+typedef ::aos::common::actions::TypedAction<actors::ShootActionQueueGroup>
+    ShootAction;
+
+// Makes a new ShootActor action.
+::std::unique_ptr<ShootAction> MakeShootAction();
+
+}  // namespace actors
+}  // namespace frc971
+
+#endif  // Y2014_ACTORS_SHOOT_ACTOR_H_
diff --git a/y2014/actors/shoot_actor_main.cc b/y2014/actors/shoot_actor_main.cc
new file mode 100644
index 0000000..efa4377
--- /dev/null
+++ b/y2014/actors/shoot_actor_main.cc
@@ -0,0 +1,18 @@
+#include <stdio.h>
+
+#include "aos/linux_code/init.h"
+#include "y2014/actors/shoot_action.q.h"
+#include "y2014/actors/shoot_actor.h"
+
+using ::aos::time::Time;
+
+int main(int /*argc*/, char * /*argv*/[]) {
+  ::aos::Init();
+
+  frc971::actors::ShootActor shoot(&::frc971::actors::shoot_action);
+  shoot.Run();
+
+  ::aos::Cleanup();
+  return 0;
+}
+
diff --git a/y2014/autonomous/auto.cc b/y2014/autonomous/auto.cc
new file mode 100644
index 0000000..f3f3bee
--- /dev/null
+++ b/y2014/autonomous/auto.cc
@@ -0,0 +1,478 @@
+#include <stdio.h>
+
+#include <memory>
+
+#include "aos/common/util/phased_loop.h"
+#include "aos/common/time.h"
+#include "aos/common/util/trapezoid_profile.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/logging/queue_logging.h"
+
+#include "frc971/autonomous/auto.q.h"
+#include "y2014/constants.h"
+#include "y2014/control_loops/drivetrain/drivetrain.q.h"
+#include "y2014/control_loops/shooter/shooter.q.h"
+#include "y2014/control_loops/claw/claw.q.h"
+#include "frc971/actions/action_client.h"
+#include "frc971/actions/shoot_action.h"
+#include "frc971/actions/drivetrain_action.h"
+#include "frc971/queues/other_sensors.q.h"
+#include "y2014/queues/hot_goal.q.h"
+
+using ::aos::time::Time;
+
+namespace frc971 {
+namespace autonomous {
+
+namespace time = ::aos::time;
+
+static double left_initial_position, right_initial_position;
+
+bool ShouldExitAuto() {
+  ::frc971::autonomous::autonomous.FetchLatest();
+  bool ans = !::frc971::autonomous::autonomous->run_auto;
+  if (ans) {
+    LOG(INFO, "Time to exit auto mode\n");
+  }
+  return ans;
+}
+
+void StopDrivetrain() {
+  LOG(INFO, "Stopping the drivetrain\n");
+  control_loops::drivetrain_queue.goal.MakeWithBuilder()
+      .control_loop_driving(true)
+      .left_goal(left_initial_position)
+      .left_velocity_goal(0)
+      .right_goal(right_initial_position)
+      .right_velocity_goal(0)
+      .quickturn(false)
+      .Send();
+}
+
+void ResetDrivetrain() {
+  LOG(INFO, "resetting the drivetrain\n");
+  control_loops::drivetrain_queue.goal.MakeWithBuilder()
+      .control_loop_driving(false)
+      .highgear(false)
+      .steering(0.0)
+      .throttle(0.0)
+      .left_goal(left_initial_position)
+      .left_velocity_goal(0)
+      .right_goal(right_initial_position)
+      .right_velocity_goal(0)
+      .Send();
+}
+
+void WaitUntilDoneOrCanceled(
+    ::std::unique_ptr<aos::common::actions::Action> action) {
+  if (!action) {
+    LOG(ERROR, "No action, not waiting\n");
+    return;
+  }
+  while (true) {
+    // Poll the running bit and auto done bits.
+    ::aos::time::PhasedLoopXMS(5, 2500);
+    if (!action->Running() || ShouldExitAuto()) {
+      return;
+    }
+  }
+}
+
+void StepDrive(double distance, double theta) {
+  double left_goal = (left_initial_position + distance -
+                      theta * constants::GetValues().turn_width / 2.0);
+  double right_goal = (right_initial_position + distance +
+                       theta * constants::GetValues().turn_width / 2.0);
+  control_loops::drivetrain_queue.goal.MakeWithBuilder()
+      .control_loop_driving(true)
+      .left_goal(left_goal)
+      .right_goal(right_goal)
+      .left_velocity_goal(0.0)
+      .right_velocity_goal(0.0)
+      .Send();
+  left_initial_position = left_goal;
+  right_initial_position = right_goal;
+}
+
+void WaitUntilNear(double distance) {
+  while (true) {
+    if (ShouldExitAuto()) return;
+    control_loops::drivetrain_queue.status.FetchAnother();
+    double left_error = ::std::abs(
+        left_initial_position -
+        control_loops::drivetrain_queue.status->filtered_left_position);
+    double right_error = ::std::abs(
+        right_initial_position -
+        control_loops::drivetrain_queue.status->filtered_right_position);
+    const double kPositionThreshold = 0.05 + distance;
+    if (right_error < kPositionThreshold && left_error < kPositionThreshold) {
+      LOG(INFO, "At the goal\n");
+      return;
+    }
+  }
+}
+
+const ProfileParams kFastDrive = {2.0, 3.5};
+const ProfileParams kFastKnockDrive = {2.0, 3.0};
+const ProfileParams kStackingSecondDrive = {2.0, 1.5};
+const ProfileParams kFastTurn = {3.0, 10.0};
+const ProfileParams kStackingFirstTurn = {1.0, 1.0};
+const ProfileParams kStackingSecondTurn = {2.0, 6.0};
+const ProfileParams kComboTurn = {1.2, 8.0};
+const ProfileParams kRaceTurn = {4.0, 10.0};
+const ProfileParams kRaceDrive = {2.0, 2.0};
+const ProfileParams kRaceBackupDrive = {2.0, 5.0};
+
+::std::unique_ptr<::frc971::actors::DrivetrainAction> SetDriveGoal(
+    double distance, const ProfileParams drive_params, double theta = 0,
+    const ProfileParams &turn_params = kFastTurn) {
+  LOG(INFO, "Driving to %f\n", distance);
+
+  ::frc971::actors::DrivetrainActionParams params;
+  params.left_initial_position = left_initial_position;
+  params.right_initial_position = right_initial_position;
+  params.y_offset = distance;
+  params.theta_offset = theta;
+  params.maximum_turn_acceleration = turn_params.acceleration;
+  params.maximum_turn_velocity = turn_params.velocity;
+  params.maximum_velocity = drive_params.velocity;
+  params.maximum_acceleration = drive_params.acceleration;
+  auto drivetrain_action = actors::MakeDrivetrainAction(params);
+  drivetrain_action->Start();
+  left_initial_position +=
+      distance - theta * constants::GetValues().turn_width / 2.0;
+  right_initial_position +=
+      distance + theta * constants::GetValues().turn_width / 2.0;
+  return ::std::move(drivetrain_action);
+}
+
+void Shoot() {
+  // Shoot.
+  auto shoot_action = actions::MakeShootAction();
+  shoot_action->Start();
+  WaitUntilDoneOrCanceled(shoot_action.get());
+}
+
+void InitializeEncoders() {
+  control_loops::drivetrain_queue.status.FetchAnother();
+  left_initial_position =
+      control_loops::drivetrain_queue.status->filtered_left_position;
+  right_initial_position =
+      control_loops::drivetrain_queue.status->filtered_right_position;
+}
+
+void WaitUntilClawDone() {
+  while (true) {
+    // Poll the running bit and auto done bits.
+    // TODO(sensors): Fix this time.
+    ::aos::time::PhasedLoop10MS(5000);
+    control_loops::claw_queue_group.status.FetchLatest();
+    control_loops::claw_queue_group.goal.FetchLatest();
+    if (ShouldExitAuto()) {
+      return;
+    }
+    if (control_loops::claw_queue_group.status.get() == nullptr ||
+        control_loops::claw_queue_group.goal.get() == nullptr) {
+      continue;
+    }
+    bool ans =
+        control_loops::claw_queue_group.status->zeroed &&
+        (::std::abs(control_loops::claw_queue_group.status->bottom_velocity) <
+         1.0) &&
+        (::std::abs(control_loops::claw_queue_group.status->bottom -
+                    control_loops::claw_queue_group.goal->bottom_angle) <
+         0.10) &&
+        (::std::abs(control_loops::claw_queue_group.status->separation -
+                    control_loops::claw_queue_group.goal->separation_angle) <
+         0.4);
+    if (ans) {
+      return;
+    }
+    if (ShouldExitAuto()) return;
+  }
+}
+
+class HotGoalDecoder {
+ public:
+  HotGoalDecoder() {
+    ResetCounts();
+  }
+
+  void ResetCounts() {
+    hot_goal.FetchLatest();
+    if (hot_goal.get()) {
+      start_counts_ = *hot_goal;
+      LOG_STRUCT(INFO, "counts reset to", start_counts_);
+      start_counts_valid_ = true;
+    } else {
+      LOG(WARNING, "no hot goal message. ignoring\n");
+      start_counts_valid_ = false;
+    }
+  }
+
+  void Update(bool block = false) {
+    if (block) {
+      hot_goal.FetchAnother();
+    } else {
+      hot_goal.FetchLatest();
+    }
+    if (hot_goal.get()) LOG_STRUCT(INFO, "new counts", *hot_goal);
+  }
+
+  bool left_triggered() const {
+    if (!start_counts_valid_ || !hot_goal.get()) return false;
+    return (hot_goal->left_count - start_counts_.left_count) > kThreshold;
+  }
+
+  bool right_triggered() const {
+    if (!start_counts_valid_ || !hot_goal.get()) return false;
+    return (hot_goal->right_count - start_counts_.right_count) > kThreshold;
+  }
+
+  bool is_left() const {
+    if (!start_counts_valid_ || !hot_goal.get()) return false;
+    const uint64_t left_difference =
+        hot_goal->left_count - start_counts_.left_count;
+    const uint64_t right_difference =
+        hot_goal->right_count - start_counts_.right_count;
+    if (left_difference > kThreshold) {
+      if (right_difference > kThreshold) {
+        // We've seen a lot of both, so pick the one we've seen the most of.
+        return left_difference > right_difference;
+      } else {
+        // We've seen enough left but not enough right, so go with it.
+        return true;
+      }
+    } else {
+      // We haven't seen enough left, so it's not left.
+      return false;
+    }
+  }
+
+  bool is_right() const {
+    if (!start_counts_valid_ || !hot_goal.get()) return false;
+    const uint64_t left_difference =
+        hot_goal->left_count - start_counts_.left_count;
+    const uint64_t right_difference =
+        hot_goal->right_count - start_counts_.right_count;
+    if (right_difference > kThreshold) {
+      if (left_difference > kThreshold) {
+        // We've seen a lot of both, so pick the one we've seen the most of.
+        return right_difference > left_difference;
+      } else {
+        // We've seen enough right but not enough left, so go with it.
+        return true;
+      }
+    } else {
+      // We haven't seen enough right, so it's not right.
+      return false;
+    }
+  }
+
+ private:
+  static const uint64_t kThreshold = 5;
+
+  ::frc971::HotGoal start_counts_;
+  bool start_counts_valid_;
+};
+
+void HandleAuto() {
+  enum class AutoVersion : uint8_t {
+    kStraight,
+    kDoubleHot,
+    kSingleHot,
+  };
+
+  // The front of the robot is 1.854 meters from the wall
+  static const double kShootDistance = 3.15;
+  static const double kPickupDistance = 0.5;
+  static const double kTurnAngle = 0.3;
+
+  ::aos::time::Time start_time = ::aos::time::Time::Now();
+  LOG(INFO, "Handling auto mode\n");
+
+  AutoVersion auto_version;
+  ::frc971::sensors::auto_mode.FetchLatest();
+  if (!::frc971::sensors::auto_mode.get()) {
+    LOG(WARNING, "not sure which auto mode to use\n");
+    auto_version = AutoVersion::kStraight;
+  } else {
+    static const double kSelectorMin = 0.2, kSelectorMax = 4.4;
+
+    const double kSelectorStep = (kSelectorMax - kSelectorMin) / 3.0;
+    if (::frc971::sensors::auto_mode->voltage < kSelectorStep + kSelectorMin) {
+      auto_version = AutoVersion::kSingleHot;
+    } else if (::frc971::sensors::auto_mode->voltage <
+               2 * kSelectorStep + kSelectorMin) {
+      auto_version = AutoVersion::kStraight;
+    } else {
+      auto_version = AutoVersion::kDoubleHot;
+    }
+  }
+  LOG(INFO, "running auto %" PRIu8 "\n", static_cast<uint8_t>(auto_version));
+
+  const bool drive_slow_acceleration = auto_version == AutoVersion::kStraight;
+
+  HotGoalDecoder hot_goal_decoder;
+  // True for left, false for right.
+  bool first_shot_left, second_shot_left_default, second_shot_left;
+
+  ResetDrivetrain();
+
+  time::SleepFor(time::Time::InSeconds(0.1));
+  if (ShouldExitAuto()) return;
+  InitializeEncoders();
+
+  // Turn the claw on, keep it straight up until the ball has been grabbed.
+  LOG(INFO, "Claw going up at %f\n",
+      (::aos::time::Time::Now() - start_time).ToSeconds());
+  PositionClawVertically(12.0, 4.0);
+  SetShotPower(115.0);
+
+  // Wait for the ball to enter the claw.
+  time::SleepFor(time::Time::InSeconds(0.25));
+  if (ShouldExitAuto()) return;
+  LOG(INFO, "Readying claw for shot at %f\n",
+      (::aos::time::Time::Now() - start_time).ToSeconds());
+
+  {
+    if (ShouldExitAuto()) return;
+    // Drive to the goal.
+    auto drivetrain_action = SetDriveGoal(-kShootDistance,
+                                          drive_slow_acceleration, 2.5);
+    time::SleepFor(time::Time::InSeconds(0.75));
+    PositionClawForShot();
+    LOG(INFO, "Waiting until drivetrain is finished\n");
+    WaitUntilDoneOrCanceled(drivetrain_action.get());
+    if (ShouldExitAuto()) return;
+  }
+
+  hot_goal_decoder.Update();
+  if (hot_goal_decoder.is_left()) {
+    LOG(INFO, "first shot left\n");
+    first_shot_left = true;
+    second_shot_left_default = false;
+  } else if (hot_goal_decoder.is_right()) {
+    LOG(INFO, "first shot right\n");
+    first_shot_left = false;
+    second_shot_left_default = true;
+  } else {
+    LOG(INFO, "first shot defaulting left\n");
+    first_shot_left = true;
+    second_shot_left_default = true;
+  }
+  if (auto_version == AutoVersion::kDoubleHot) {
+    if (ShouldExitAuto()) return;
+    auto drivetrain_action =
+        SetDriveGoal(0, drive_slow_acceleration, 2,
+                     first_shot_left ? kTurnAngle : -kTurnAngle);
+    WaitUntilDoneOrCanceled(drivetrain_action.get());
+    if (ShouldExitAuto()) return;
+  } else if (auto_version == AutoVersion::kSingleHot) {
+    do {
+      // TODO(brians): Wait for next message with timeout or something.
+      ::aos::time::SleepFor(::aos::time::Time::InSeconds(0.003));
+      hot_goal_decoder.Update(false);
+      if (ShouldExitAuto()) return;
+    } while (!hot_goal_decoder.left_triggered() &&
+             (::aos::time::Time::Now() - start_time) <
+                 ::aos::time::Time::InSeconds(9));
+  } else if (auto_version == AutoVersion::kStraight) {
+    time::SleepFor(time::Time::InSeconds(0.4));
+  }
+
+  // Shoot.
+  LOG(INFO, "Shooting at %f\n",
+      (::aos::time::Time::Now() - start_time).ToSeconds());
+  Shoot();
+  time::SleepFor(time::Time::InSeconds(0.05));
+
+  if (auto_version == AutoVersion::kDoubleHot) {
+    if (ShouldExitAuto()) return;
+    auto drivetrain_action =
+        SetDriveGoal(0, drive_slow_acceleration, 2,
+                     first_shot_left ? -kTurnAngle : kTurnAngle);
+    WaitUntilDoneOrCanceled(drivetrain_action.get());
+    if (ShouldExitAuto()) return;
+  } else if (auto_version == AutoVersion::kSingleHot) {
+    LOG(INFO, "auto done at %f\n",
+        (::aos::time::Time::Now() - start_time).ToSeconds());
+    PositionClawVertically(0.0, 0.0);
+    return;
+  }
+
+  {
+    if (ShouldExitAuto()) return;
+    // Intake the new ball.
+    LOG(INFO, "Claw ready for intake at %f\n",
+        (::aos::time::Time::Now() - start_time).ToSeconds());
+    PositionClawBackIntake();
+    auto drivetrain_action =
+        SetDriveGoal(kShootDistance + kPickupDistance,
+                     drive_slow_acceleration, 2.5);
+    LOG(INFO, "Waiting until drivetrain is finished\n");
+    WaitUntilDoneOrCanceled(drivetrain_action.get());
+    if (ShouldExitAuto()) return;
+    LOG(INFO, "Wait for the claw at %f\n",
+        (::aos::time::Time::Now() - start_time).ToSeconds());
+    WaitUntilClawDone();
+    if (ShouldExitAuto()) return;
+  }
+
+  // Drive back.
+  {
+    LOG(INFO, "Driving back at %f\n",
+        (::aos::time::Time::Now() - start_time).ToSeconds());
+    auto drivetrain_action =
+        SetDriveGoal(-(kShootDistance + kPickupDistance),
+                     drive_slow_acceleration, 2.5);
+    time::SleepFor(time::Time::InSeconds(0.3));
+    hot_goal_decoder.ResetCounts();
+    if (ShouldExitAuto()) return;
+    PositionClawUpClosed();
+    WaitUntilClawDone();
+    if (ShouldExitAuto()) return;
+    PositionClawForShot();
+    LOG(INFO, "Waiting until drivetrain is finished\n");
+    WaitUntilDoneOrCanceled(drivetrain_action.get());
+    if (ShouldExitAuto()) return;
+    WaitUntilClawDone();
+    if (ShouldExitAuto()) return;
+  }
+
+  hot_goal_decoder.Update();
+  if (hot_goal_decoder.is_left()) {
+    LOG(INFO, "second shot left\n");
+    second_shot_left = true;
+  } else if (hot_goal_decoder.is_right()) {
+    LOG(INFO, "second shot right\n");
+    second_shot_left = false;
+  } else {
+    LOG(INFO, "second shot defaulting %s\n",
+        second_shot_left_default ? "left" : "right");
+    second_shot_left = second_shot_left_default;
+  }
+  if (auto_version == AutoVersion::kDoubleHot) {
+    if (ShouldExitAuto()) return;
+    auto drivetrain_action =
+        SetDriveGoal(0, drive_slow_acceleration, 2,
+                     second_shot_left ? kTurnAngle : -kTurnAngle);
+    WaitUntilDoneOrCanceled(drivetrain_action.get());
+    if (ShouldExitAuto()) return;
+  } else if (auto_version == AutoVersion::kStraight) {
+    time::SleepFor(time::Time::InSeconds(0.4));
+  }
+
+  LOG(INFO, "Shooting at %f\n",
+      (::aos::time::Time::Now() - start_time).ToSeconds());
+  // Shoot
+  Shoot();
+  if (ShouldExitAuto()) return;
+
+  // Get ready to zero when we come back up.
+  time::SleepFor(time::Time::InSeconds(0.05));
+  PositionClawVertically(0.0, 0.0);
+}
+
+}  // namespace autonomous
+}  // namespace frc971
diff --git a/y2014/autonomous/auto.h b/y2014/autonomous/auto.h
new file mode 100644
index 0000000..3e4885f
--- /dev/null
+++ b/y2014/autonomous/auto.h
@@ -0,0 +1,12 @@
+#ifndef Y2014_AUTONOMOUS_AUTO_H_
+#define Y2014_AUTONOMOUS_AUTO_H_
+
+namespace frc971 {
+namespace autonomous {
+
+void HandleAuto();
+
+}  // namespace autonomous
+}  // namespace frc971
+
+#endif  // Y2014_AUTONOMOUS_AUTO_H_
diff --git a/y2014/autonomous/auto_main.cc b/y2014/autonomous/auto_main.cc
new file mode 100644
index 0000000..3dbad2c
--- /dev/null
+++ b/y2014/autonomous/auto_main.cc
@@ -0,0 +1,42 @@
+#include <stdio.h>
+
+#include "aos/common/time.h"
+#include "aos/linux_code/init.h"
+#include "aos/common/logging/logging.h"
+#include "frc971/autonomous/auto.q.h"
+#include "y2014/autonomous/auto.h"
+
+using ::aos::time::Time;
+
+int main(int /*argc*/, char * /*argv*/[]) {
+  ::aos::Init();
+
+  LOG(INFO, "Auto main started\n");
+  ::frc971::autonomous::autonomous.FetchLatest();
+  while (!::frc971::autonomous::autonomous.get()) {
+    ::frc971::autonomous::autonomous.FetchNextBlocking();
+    LOG(INFO, "Got another auto packet\n");
+  }
+
+  while (true) {
+    while (!::frc971::autonomous::autonomous->run_auto) {
+      ::frc971::autonomous::autonomous.FetchNextBlocking();
+      LOG(INFO, "Got another auto packet\n");
+    }
+    LOG(INFO, "Starting auto mode\n");
+    ::aos::time::Time start_time = ::aos::time::Time::Now();
+    ::frc971::autonomous::HandleAuto();
+
+    ::aos::time::Time elapsed_time = ::aos::time::Time::Now() - start_time;
+    LOG(INFO, "Auto mode exited in %f, waiting for it to finish.\n",
+        elapsed_time.ToSeconds());
+    while (::frc971::autonomous::autonomous->run_auto) {
+      ::frc971::autonomous::autonomous.FetchNextBlocking();
+      LOG(INFO, "Got another auto packet\n");
+    }
+    LOG(INFO, "Waiting for auto to start back up.\n");
+  }
+  ::aos::Cleanup();
+  return 0;
+}
+
diff --git a/y2014/autonomous/autonomous.gyp b/y2014/autonomous/autonomous.gyp
new file mode 100644
index 0000000..d37d36b
--- /dev/null
+++ b/y2014/autonomous/autonomous.gyp
@@ -0,0 +1,44 @@
+{
+  'targets': [
+    {
+      'target_name': 'auto_lib',
+      'type': 'static_library',
+      'sources': [
+        'auto.cc',
+      ],
+      'dependencies': [
+        'auto_queue',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(DEPTH)/y2014/control_loops/drivetrain/drivetrain.gyp:drivetrain_loop',
+        '<(DEPTH)/y2014/control_loops/shooter/shooter.gyp:shooter_loop',
+        '<(DEPTH)/y2014/control_loops/claw/claw.gyp:claw_loop',
+        '<(DEPTH)/y2014/y2014.gyp:constants',
+        '<(AOS)/common/common.gyp:time',
+        '<(AOS)/common/util/util.gyp:phased_loop',
+        '<(AOS)/common/util/util.gyp:trapezoid_profile',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(DEPTH)/y2014/actions/actions.gyp:action_client',
+        '<(DEPTH)/y2014/actions/actions.gyp:shoot_action_lib',
+        '<(DEPTH)/y2014/actions/actions.gyp:drivetrain_action_lib',
+        '<(DEPTH)/y2014/queues/queues.gyp:queues',
+        '<(DEPTH)/y2014/queues/queues.gyp:hot_goal',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+      ],
+    },
+    {
+      'target_name': 'auto',
+      'type': 'executable',
+      'sources': [
+        'auto_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'auto_queue',
+        'auto_lib',
+      ],
+    },
+  ],
+}
diff --git a/y2014/constants.cc b/y2014/constants.cc
new file mode 100644
index 0000000..2c101c3
--- /dev/null
+++ b/y2014/constants.cc
@@ -0,0 +1,224 @@
+#include "y2014/constants.h"
+
+#include <math.h>
+#include <stdint.h>
+#include <inttypes.h>
+
+#include <map>
+
+#if __has_feature(address_sanitizer)
+#include "sanitizer/lsan_interface.h"
+#endif
+
+#include "aos/common/logging/logging.h"
+#include "aos/common/once.h"
+#include "aos/common/network/team_number.h"
+#include "aos/common/mutex.h"
+
+#include "y2014/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+#include "y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+
+#ifndef M_PI
+#define M_PI 3.14159265358979323846
+#endif
+
+namespace frc971 {
+namespace constants {
+namespace {
+
+const uint16_t kCompTeamNumber = 971;
+const uint16_t kPracticeTeamNumber = 9971;
+const uint16_t kRoboRioTeamNumber = 254;
+
+const double kCompDrivetrainEncoderRatio =
+    (18.0 / 50.0) /*output reduction*/ * (56.0 / 30.0) /*encoder gears*/;
+const double kCompLowGearRatio = 18.0 / 60.0 * 18.0 / 50.0;
+const double kCompHighGearRatio = 28.0 / 50.0 * 18.0 / 50.0;
+
+const double kPracticeDrivetrainEncoderRatio = kCompDrivetrainEncoderRatio;
+const double kPracticeLowGearRatio = kCompLowGearRatio;
+const double kPracticeHighGearRatio = kCompHighGearRatio;
+
+const ShifterHallEffect kCompRightDriveShifter{555, 657, 660, 560, 0.2, 0.7};
+const ShifterHallEffect kCompLeftDriveShifter{555, 660, 644, 552, 0.2, 0.7};
+
+const ShifterHallEffect kPracticeRightDriveShifter{2.95, 3.95, 3.95, 2.95, 0.2, 0.7};
+const ShifterHallEffect kPracticeLeftDriveShifter{2.95, 4.2, 3.95, 3.0, 0.2, 0.7};
+
+const double kRobotWidth = 25.0 / 100.0 * 2.54;
+
+const double shooter_zeroing_speed = 0.05;
+const double shooter_unload_speed = 0.08;
+
+// Smaller (more negative) = opening.
+const double kCompTopClawOffset = -0.120;
+
+const Values *DoGetValuesForTeam(uint16_t team) {
+  switch (team) {
+    case 1:  // for tests
+      return new Values{
+          kCompDrivetrainEncoderRatio,
+          kCompLowGearRatio,
+          kCompHighGearRatio,
+          kCompLeftDriveShifter,
+          kCompRightDriveShifter,
+          false,
+          0.5,
+          control_loops::MakeVelocityDrivetrainLoop,
+          control_loops::MakeDrivetrainLoop,
+          0.02, // drivetrain done delta
+          5.0, // drivetrain max speed
+
+          // ShooterLimits
+          {-0.00127, 0.298196, -0.0017, 0.305054, 0.0149098,
+           {-0.001778, 0.000762, 0, 0},
+           {-0.001778, 0.008906, 0, 0},
+           {0.006096, 0.026416, 0, 0},
+           shooter_zeroing_speed,
+           shooter_unload_speed
+          },
+          {0.5,
+           0.1,
+           0.1,
+           0.0,
+           1.57,
+           0.05,
+           1.5,
+           {0.0, 2.05, 0.02, 2.02, {-0.1, 0.05, -0.1, 0.05}, {1.0, 1.1, 1.0, 1.1}, {2.0, 2.1, 2.0, 2.1}},
+           {0.0, 2.05, 0.02, 2.02, {-0.1, 0.05, -0.1, 0.05}, {1.0, 1.1, 1.0, 1.1}, {2.0, 2.1, 2.0, 2.1}},
+           0.01,  // claw_unimportant_epsilon
+           0.9,   // start_fine_tune_pos
+           4.0,
+          },
+          {0.07, 0.15}, // shooter_action
+      };
+      break;
+    case kCompTeamNumber:
+      return new Values{
+          kCompDrivetrainEncoderRatio,
+          kCompLowGearRatio,
+          kCompHighGearRatio,
+          kCompLeftDriveShifter,
+          kCompRightDriveShifter,
+          false,
+          kRobotWidth,
+          control_loops::MakeVelocityDrivetrainLoop,
+          control_loops::MakeDrivetrainLoop,
+          0.02, // drivetrain done delta
+          5.0, // drivetrain max speed
+
+          // ShooterLimits
+          {-0.001041, 0.296019, -0.001488, 0.302717, 0.0149098,
+           {-0.002, 0.000446, -0.002, 0.000446},
+           {-0.002, 0.009078, -0.002, 0.009078},
+           {0.003870, 0.026194, 0.003869, 0.026343},
+           shooter_zeroing_speed,
+           shooter_unload_speed
+          },
+          {0.800000,
+           0.400000,
+           0.000000,
+           -1.220821,
+           1.822142,
+           -0.849484,
+           1.42309,
+           // 0.0371
+           {-3.3284, 2.0917, -3.1661, 1.95,
+             {-3.4, -3.02 + kCompTopClawOffset, -3.4, -2.9876 + kCompTopClawOffset},
+             {-0.1433 + kCompTopClawOffset, 0.0670 + kCompTopClawOffset, -0.1460 + kCompTopClawOffset, 0.0648 + kCompTopClawOffset},
+             {1.9952 + kCompTopClawOffset, 2.2, 1.9898 + kCompTopClawOffset, 2.2}},
+           {-2.453460, 3.082960, -2.453460, 3.082960,
+             {-2.6, -2.185752, -2.6, -2.184843},
+             {-0.322249, -0.053177, -0.332248, -0.059086},
+             {2.892065, 3.2, 2.888429, 3.2}},
+           0.040000,  // claw_unimportant_epsilon
+           -0.400000,   // start_fine_tune_pos
+           4.000000,
+          },
+          //TODO(james): Get realer numbers for shooter_action.
+          {0.07, 0.15}, // shooter_action
+      };
+      break;
+    case kPracticeTeamNumber:
+    case kRoboRioTeamNumber:
+      return new Values{
+          kPracticeDrivetrainEncoderRatio,
+          kPracticeLowGearRatio,
+          kPracticeHighGearRatio,
+          kPracticeLeftDriveShifter,
+          kPracticeRightDriveShifter,
+          false,
+          kRobotWidth,
+          control_loops::MakeVelocityDrivetrainLoop,
+          control_loops::MakeDrivetrainLoop,
+          0.02, // drivetrain done delta
+          5.0, // drivetrain max speed
+
+          // ShooterLimits
+          {-0.001042, 0.294084, -0.001935, 0.303460, 0.0138401,
+           {-0.002, 0.000446, -0.002, 0.000446},
+           {-0.002, 0.009078, -0.002, 0.009078},
+           {0.003869, 0.026194, 0.003869, 0.026194},
+           shooter_zeroing_speed,
+           shooter_unload_speed
+          },
+          {0.400000 * 2.0,
+          0.200000 * 2.0,
+          0.000000 * 2.0,
+          -0.762218 * 2.0,
+          1.767146,
+          -0.849484,
+          1.42308,
+          {-3.364758, 2.086668, -3.166136, 1.95,
+            {-1.7 * 2.0, -1.544662 * 2.0, -1.7 * 2.0, -1.547616 * 2.0},
+            {-0.130218 * 2.0, -0.019771 * 2.0, -0.132036 * 2.0, -0.018862 * 2.0},
+            {1.871684, 2.2, 1.86532, 2.2}},
+          {-2.451642, 3.107504, -2.273474, 2.750,
+            {-2.6, -2.176662, -2.6, -2.176662},
+            {-0.316796, -0.054088, -0.319978, -0.062723},
+            {2.894792, 3.2, 2.887974, 3.2}},
+          0.040000,  // claw_unimportant_epsilon
+          -0.400000,   // start_fine_tune_pos
+          4.000000,
+          },
+          //TODO(james): Get realer numbers for shooter_action.
+          {0.07, 0.15}, // shooter_action
+      };
+      break;
+    default:
+      LOG(FATAL, "unknown team #%" PRIu16 "\n", team);
+  }
+}
+
+const Values *DoGetValues() {
+  uint16_t team = ::aos::network::GetTeamNumber();
+  LOG(INFO, "creating a Constants for team %" PRIu16 "\n", team);
+  return DoGetValuesForTeam(team);
+}
+
+}  // namespace
+
+const Values &GetValues() {
+  static ::aos::Once<const Values> once(DoGetValues);
+  return *once.Get();
+}
+
+const Values &GetValuesForTeam(uint16_t team_number) {
+  static ::aos::Mutex mutex;
+  ::aos::MutexLocker locker(&mutex);
+
+  // IMPORTANT: This declaration has to stay after the mutex is locked to avoid
+  // race conditions.
+  static ::std::map<uint16_t, const Values *> values;
+
+  if (values.count(team_number) == 0) {
+    values[team_number] = DoGetValuesForTeam(team_number);
+#if __has_feature(address_sanitizer)
+    __lsan_ignore_object(values[team_number]);
+#endif
+  }
+  return *values[team_number];
+}
+
+}  // namespace constants
+}  // namespace frc971
diff --git a/y2014/constants.h b/y2014/constants.h
new file mode 100644
index 0000000..79ba826
--- /dev/null
+++ b/y2014/constants.h
@@ -0,0 +1,145 @@
+#ifndef Y2014_CONSTANTS_H_
+#define Y2014_CONSTANTS_H_
+
+#include <stdint.h>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/shifter_hall_effect.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.
+
+// Everything is in SI units (volts, radians, meters, seconds, etc).
+// Some of these values are related to the conversion between raw values
+// (encoder counts, voltage, etc) to scaled units (radians, meters, etc).
+
+// This structure contains current values for all of the things that change.
+struct Values {
+  // This is useful for representing the 2 sides of a hall effect sensor etc.
+  struct AnglePair {
+    // The angles for increasing values (posedge on lower, negedge on upper).
+    double lower_angle, upper_angle;
+    // The angles for decreasing values (negedge on lower, posedge on upper).
+    double lower_decreasing_angle, upper_decreasing_angle;
+  };
+
+  // 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;
+
+  double turn_width;
+
+  ::std::function<StateFeedbackLoop<2, 2, 2>()> make_v_drivetrain_loop;
+  ::std::function<StateFeedbackLoop<4, 2, 2>()> make_drivetrain_loop;
+
+  double drivetrain_done_distance;
+  double drivetrain_max_speed;
+
+  struct ZeroingConstants {
+    // The number of samples in the moving average filter.
+    int average_filter_size;
+    // The difference in scaled units between two index pulses.
+    double index_difference;
+    // The absolute position in scaled units of one of the index pulses.
+    double measured_index_position;
+    // Value between 0 and 1 which determines a fraction of the index_diff
+    // you want to use.
+    double allowable_encoder_error;
+  };
+
+  // Defines a range of motion for a subsystem.
+  // These are all absolute positions in scaled units.
+  struct Range {
+    double lower_limit;
+    double upper_limit;
+    double lower_hard_limit;
+    double upper_hard_limit;
+  };
+
+  struct Shooter {
+    double lower_limit;
+    double upper_limit;
+    double lower_hard_limit;
+    double upper_hard_limit;
+    // If the plunger is further back than this position, it is safe for the
+    // latch to be down.  Anything else would be considered a collision.
+    double latch_max_safe_position;
+    AnglePair plunger_back;
+    AnglePair pusher_distal;
+    AnglePair pusher_proximal;
+    double zeroing_speed;
+    double unload_speed;
+  };
+
+  Shooter shooter;
+
+  struct Claws {
+    double claw_zeroing_off_speed;
+    double claw_zeroing_speed;
+    double claw_zeroing_separation;
+
+    // claw separation that would be considered a collision
+    double claw_min_separation;
+    double claw_max_separation;
+
+    // We should never get closer/farther than these.
+    double soft_min_separation;
+    double soft_max_separation;
+
+    // Three hall effects are known as front, calib and back
+    typedef Values::AnglePair AnglePair;
+
+    struct Claw {
+      double lower_hard_limit;
+      double upper_hard_limit;
+      double lower_limit;
+      double upper_limit;
+      AnglePair front;
+      AnglePair calibration;
+      AnglePair back;
+    };
+
+    Claw upper_claw;
+    Claw lower_claw;
+
+    double claw_unimportant_epsilon;
+    double start_fine_tune_pos;
+    double max_zeroing_voltage;
+  };
+  Claws claw;
+
+  // Has all the constants for the ShootAction class.
+  struct ShooterAction {
+    // Minimum separation required between the claws in order to be able to
+    // shoot.
+    double claw_shooting_separation;
+
+    // Goal to send to the claw when opening it up in preparation for shooting;
+    // should be larger than claw_shooting_separation so that we can shoot
+    // promptly.
+    double claw_separation_goal;
+   };
+  ShooterAction shooter_action;
+};
+
+// Creates (once) a Values instance for ::aos::network::GetTeamNumber() and
+// returns a reference to it.
+const Values &GetValues();
+
+// Creates Values instances for each team number it is called with and returns
+// them.
+const Values &GetValuesForTeam(uint16_t team_number);
+
+}  // namespace constants
+}  // namespace frc971
+
+#endif  // Y2014_CONSTANTS_H_
diff --git a/y2014/control_loops/claw/claw.cc b/y2014/control_loops/claw/claw.cc
new file mode 100644
index 0000000..b2ac562
--- /dev/null
+++ b/y2014/control_loops/claw/claw.cc
@@ -0,0 +1,994 @@
+#include "y2014/control_loops/claw/claw.h"
+
+#include <algorithm>
+
+#include "aos/common/controls/control_loops.q.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/logging/queue_logging.h"
+#include "aos/common/logging/matrix_logging.h"
+#include "aos/common/commonmath.h"
+
+#include "y2014/constants.h"
+#include "y2014/control_loops/claw/claw_motor_plant.h"
+
+// Zeroing plan.
+// There are 2 types of zeros.  Enabled and disabled ones.
+// Disabled ones are only valid during auto mode, and can be used to speed up
+// the enabled zero process.  We need to re-zero during teleop in case the auto
+// zero was poor and causes us to miss all our shots.
+//
+// We need to be able to zero manually while disabled by moving the joint over
+// the zeros.
+// Zero on the down edge when disabled (gravity in the direction of motion)
+//
+// When enabled, zero on the up edge (gravity opposing the direction of motion)
+// The enabled sequence needs to work as follows.  We can crash the claw if we
+// bring them too close to each other or too far from each other.  The only safe
+// thing to do is to move them in unison.
+//
+// Start by moving them both towards the front of the bot to either find either
+// the middle hall effect on either jaw, or the front hall effect on the bottom
+// jaw.  Any edge that isn't the desired edge will provide an approximate edge
+// location that can be used for the fine tuning step.
+// Once an edge is found on the front claw, move back the other way with both
+// claws until an edge is found for the other claw.
+// Now that we have an approximate zero, we can robustify the limits to keep
+// both claws safe.  Then, we can move both claws to a position that is the
+// correct side of the zero and go zero.
+
+// Valid region plan.
+// Difference between the arms has a range, and the values of each arm has a
+// range.
+// If a claw runs up against a static limit, don't let the goal change outside
+// the limit.
+// If a claw runs up against a movable limit, move both claws outwards to get
+// out of the condition.
+
+namespace frc971 {
+namespace control_loops {
+
+static const double kZeroingVoltage = 4.0;
+static const double kMaxVoltage = 12.0;
+const double kRezeroThreshold = 0.07;
+
+ClawLimitedLoop::ClawLimitedLoop(StateFeedbackLoop<4, 2, 2> &&loop)
+    : StateFeedbackLoop<4, 2, 2>(::std::move(loop)),
+      uncapped_average_voltage_(0.0),
+      is_zeroing_(true),
+      U_Poly_((Eigen::Matrix<double, 4, 2>() << 1, 0,
+               -1, 0,
+               0, 1,
+               0, -1).finished(),
+              (Eigen::Matrix<double, 4, 1>() << kMaxVoltage, kMaxVoltage,
+               kMaxVoltage, kMaxVoltage).finished()),
+      U_Poly_zeroing_((Eigen::Matrix<double, 4, 2>() << 1, 0,
+               -1, 0,
+               0, 1,
+               0, -1).finished(),
+              (Eigen::Matrix<double, 4, 1>() <<
+               kZeroingVoltage, kZeroingVoltage,
+               kZeroingVoltage, kZeroingVoltage).finished()) {
+  ::aos::controls::HPolytope<0>::Init();
+}
+
+// Caps the voltage prioritizing reducing velocity error over reducing
+// positional error.
+// Uses the polytope libararies which we used to just use for the drivetrain.
+// Uses a region representing the maximum voltage and then transforms it such
+// that the points represent different amounts of positional error and
+// constrains the region such that, if at all possible, it will maintain its
+// current efforts to reduce velocity error.
+void ClawLimitedLoop::CapU() {
+  const Eigen::Matrix<double, 4, 1> error = R() - X_hat();
+
+  double u_top = U(1, 0);
+  double u_bottom = U(0, 0);
+
+  uncapped_average_voltage_ = (u_top + u_bottom) / 2;
+
+  double max_voltage = is_zeroing_ ? kZeroingVoltage : kMaxVoltage;
+
+  if (::std::abs(u_bottom) > max_voltage || ::std::abs(u_top) > max_voltage) {
+    LOG_MATRIX(DEBUG, "U at start", U());
+    // H * U <= k
+    // U = UPos + UVel
+    // H * (UPos + UVel) <= k
+    // H * UPos <= k - H * UVel
+
+    // Now, we can do a coordinate transformation and say the following.
+
+    // UPos = position_K * position_error
+    // (H * position_K) * position_error <= k - H * UVel
+
+    Eigen::Matrix<double, 2, 2> position_K;
+    position_K << K(0, 0), K(0, 1),
+                  K(1, 0), K(1, 1);
+    Eigen::Matrix<double, 2, 2> velocity_K;
+    velocity_K << K(0, 2), K(0, 3),
+                  K(1, 2), K(1, 3);
+
+    Eigen::Matrix<double, 2, 1> position_error;
+    position_error << error(0, 0), error(1, 0);
+    Eigen::Matrix<double, 2, 1> velocity_error;
+    velocity_error << error(2, 0), error(3, 0);
+    LOG_MATRIX(DEBUG, "error", error);
+
+    const auto &poly = is_zeroing_ ? U_Poly_zeroing_ : U_Poly_;
+    const Eigen::Matrix<double, 4, 2> pos_poly_H = poly.H() * position_K;
+    const Eigen::Matrix<double, 4, 1> pos_poly_k =
+        poly.k() - poly.H() * velocity_K * velocity_error;
+    const ::aos::controls::HPolytope<2> pos_poly(pos_poly_H, pos_poly_k);
+
+    Eigen::Matrix<double, 2, 1> adjusted_pos_error;
+    {
+      const auto &P = position_error;
+
+      // This line was at 45 degrees but is now at some angle steeper than the
+      // straight one between the points.
+      Eigen::Matrix<double, 1, 2> angle_45;
+      // If the top claw is above its soft upper limit, make the line actually
+      // 45 degrees to avoid smashing it into the limit in an attempt to fix the
+      // separation error faster than the bottom position one.
+      if (X_hat(0, 0) + X_hat(1, 0) >
+          constants::GetValues().claw.upper_claw.upper_limit) {
+        angle_45 << 1, 1;
+      } else {
+        // Fixing separation error half as fast as positional error works well
+        // because it means they both close evenly.
+        angle_45 << ::std::sqrt(3), 1;
+      }
+      Eigen::Matrix<double, 1, 2> L45_quadrant;
+      L45_quadrant << ::aos::sign(P(1, 0)), -::aos::sign(P(0, 0));
+      const auto L45 = L45_quadrant.cwiseProduct(angle_45);
+      const double w45 = 0;
+
+      Eigen::Matrix<double, 1, 2> LH;
+      if (::std::abs(P(0, 0)) > ::std::abs(P(1, 0))) {
+        LH << 0, 1;
+      } else {
+        LH << 1, 0;
+      }
+      const double wh = LH.dot(P);
+
+      Eigen::Matrix<double, 2, 2> standard;
+      standard << L45, LH;
+      Eigen::Matrix<double, 2, 1> W;
+      W << w45, wh;
+      const Eigen::Matrix<double, 2, 1> intersection = standard.inverse() * W;
+
+      bool is_inside_h;
+      const auto adjusted_pos_error_h =
+          DoCoerceGoal(pos_poly, LH, wh, position_error, &is_inside_h);
+      const auto adjusted_pos_error_45 =
+          DoCoerceGoal(pos_poly, L45, w45, intersection, nullptr);
+      if (pos_poly.IsInside(intersection)) {
+        adjusted_pos_error = adjusted_pos_error_h;
+      } else {
+        if (is_inside_h) {
+          if (adjusted_pos_error_h.norm() > adjusted_pos_error_45.norm()) {
+            adjusted_pos_error = adjusted_pos_error_h;
+          } else {
+            adjusted_pos_error = adjusted_pos_error_45;
+          }
+        } else {
+          adjusted_pos_error = adjusted_pos_error_45;
+        }
+      }
+    }
+
+    LOG_MATRIX(DEBUG, "adjusted_pos_error", adjusted_pos_error);
+    mutable_U() = velocity_K * velocity_error + position_K * adjusted_pos_error;
+    LOG_MATRIX(DEBUG, "U is now", U());
+
+    {
+      const auto values = constants::GetValues().claw;
+      if (top_known_) {
+        if (X_hat(0, 0) + X_hat(1, 0) > values.upper_claw.upper_limit && U(1, 0) > 0) {
+          LOG(WARNING, "upper claw too high and moving up\n");
+          mutable_U(1, 0) = 0;
+        } else if (X_hat(0, 0) + X_hat(1, 0) < values.upper_claw.lower_limit &&
+                   U(1, 0) < 0) {
+          LOG(WARNING, "upper claw too low and moving down\n");
+          mutable_U(1, 0) = 0;
+        }
+      }
+      if (bottom_known_) {
+        if (X_hat(0, 0) > values.lower_claw.upper_limit && U(0, 0) > 0) {
+          LOG(WARNING, "lower claw too high and moving up\n");
+          mutable_U(0, 0) = 0;
+        } else if (X_hat(0, 0) < values.lower_claw.lower_limit && U(0, 0) < 0) {
+          LOG(WARNING, "lower claw too low and moving down\n");
+          mutable_U(0, 0) = 0;
+        }
+      }
+    }
+  }
+}
+
+ZeroedStateFeedbackLoop::ZeroedStateFeedbackLoop(const char *name,
+                                                 ClawMotor *motor)
+    : offset_(0.0),
+      name_(name),
+      motor_(motor),
+      zeroing_state_(UNKNOWN_POSITION),
+      posedge_value_(0.0),
+      negedge_value_(0.0),
+      encoder_(0.0),
+      last_encoder_(0.0) {}
+
+void ZeroedStateFeedbackLoop::SetPositionValues(const HalfClawPosition &claw) {
+  front_.Update(claw.front);
+  calibration_.Update(claw.calibration);
+  back_.Update(claw.back);
+
+  bool any_sensor_triggered = any_triggered();
+  if (any_sensor_triggered && any_triggered_last_) {
+    // We are still on the hall effect and nothing has changed.
+    min_hall_effect_on_angle_ =
+        ::std::min(min_hall_effect_on_angle_, claw.position);
+    max_hall_effect_on_angle_ =
+        ::std::max(max_hall_effect_on_angle_, claw.position);
+  } else if (!any_sensor_triggered && !any_triggered_last_) {
+    // We are still off the hall effect and nothing has changed.
+    min_hall_effect_off_angle_ =
+        ::std::min(min_hall_effect_off_angle_, claw.position);
+    max_hall_effect_off_angle_ =
+        ::std::max(max_hall_effect_off_angle_, claw.position);
+  } else if (any_sensor_triggered && !any_triggered_last_) {
+    // Saw a posedge on the hall effect.  Reset the limits.
+    min_hall_effect_on_angle_ = ::std::min(claw.posedge_value, claw.position);
+    max_hall_effect_on_angle_ = ::std::max(claw.posedge_value, claw.position);
+  } else if (!any_sensor_triggered && any_triggered_last_) {
+    // Saw a negedge on the hall effect.  Reset the limits.
+    min_hall_effect_off_angle_ = ::std::min(claw.negedge_value, claw.position);
+    max_hall_effect_off_angle_ = ::std::max(claw.negedge_value, claw.position);
+  }
+
+  posedge_value_ = claw.posedge_value;
+  negedge_value_ = claw.negedge_value;
+  last_encoder_ = encoder_;
+  if (front().value() || calibration().value() || back().value()) {
+    last_on_encoder_ = encoder_;
+  } else {
+    last_off_encoder_ = encoder_;
+  }
+  encoder_ = claw.position;
+  any_triggered_last_ = any_sensor_triggered;
+}
+
+void ZeroedStateFeedbackLoop::Reset(const HalfClawPosition &claw) {
+  set_zeroing_state(ZeroedStateFeedbackLoop::UNKNOWN_POSITION);
+
+  front_.Reset(claw.front);
+  calibration_.Reset(claw.calibration);
+  back_.Reset(claw.back);
+  // close up the min and max edge positions as they are no longer valid and
+  // will be expanded in future iterations
+  min_hall_effect_on_angle_ = claw.position;
+  max_hall_effect_on_angle_ = claw.position;
+  min_hall_effect_off_angle_ = claw.position;
+  max_hall_effect_off_angle_ = claw.position;
+  any_triggered_last_ = any_triggered();
+}
+
+bool TopZeroedStateFeedbackLoop::SetCalibrationOnEdge(
+    const constants::Values::Claws::Claw &claw_values,
+    JointZeroingState zeroing_state) {
+  double edge_encoder;
+  double edge_angle;
+  if (GetPositionOfEdge(claw_values, &edge_encoder, &edge_angle)) {
+    LOG(INFO, "Calibration edge edge should be %f.\n", edge_angle);
+    SetCalibration(edge_encoder, edge_angle);
+    set_zeroing_state(zeroing_state);
+    return true;
+  }
+  return false;
+}
+
+void TopZeroedStateFeedbackLoop::HandleCalibrationError(
+    const constants::Values::Claws::Claw &claw_values) {
+  double edge_encoder;
+  double edge_angle;
+  if (GetPositionOfEdge(claw_values, &edge_encoder, &edge_angle)) {
+    const double calibration_error =
+        ComputeCalibrationChange(edge_encoder, edge_angle);
+    LOG(INFO, "Top calibration error is %f\n", calibration_error);
+    if (::std::abs(calibration_error) > kRezeroThreshold) {
+      LOG(WARNING, "rezeroing top\n");
+      SetCalibration(edge_encoder, edge_angle);
+      set_zeroing_state(ZeroedStateFeedbackLoop::UNKNOWN_POSITION);
+    }
+  }
+}
+
+
+void BottomZeroedStateFeedbackLoop::HandleCalibrationError(
+    const constants::Values::Claws::Claw &claw_values) {
+  double edge_encoder;
+  double edge_angle;
+  if (GetPositionOfEdge(claw_values, &edge_encoder, &edge_angle)) {
+    const double calibration_error =
+        ComputeCalibrationChange(edge_encoder, edge_angle);
+    LOG(INFO, "Bottom calibration error is %f\n", calibration_error);
+    if (::std::abs(calibration_error) > kRezeroThreshold) {
+      LOG(WARNING, "rezeroing bottom\n");
+      SetCalibration(edge_encoder, edge_angle);
+      set_zeroing_state(ZeroedStateFeedbackLoop::UNKNOWN_POSITION);
+    }
+  }
+}
+
+bool BottomZeroedStateFeedbackLoop::SetCalibrationOnEdge(
+    const constants::Values::Claws::Claw &claw_values,
+    JointZeroingState zeroing_state) {
+  double edge_encoder;
+  double edge_angle;
+  if (GetPositionOfEdge(claw_values, &edge_encoder, &edge_angle)) {
+    LOG(INFO, "Calibration edge.\n");
+    SetCalibration(edge_encoder, edge_angle);
+    set_zeroing_state(zeroing_state);
+    return true;
+  }
+  return false;
+}
+
+ClawMotor::ClawMotor(control_loops::ClawGroup *my_claw)
+    : aos::controls::ControlLoop<control_loops::ClawGroup>(my_claw),
+      has_top_claw_goal_(false),
+      top_claw_goal_(0.0),
+      top_claw_(this),
+      has_bottom_claw_goal_(false),
+      bottom_claw_goal_(0.0),
+      bottom_claw_(this),
+      claw_(MakeClawLoop()),
+      was_enabled_(false),
+      doing_calibration_fine_tune_(false),
+      capped_goal_(false),
+      mode_(UNKNOWN_LOCATION) {}
+
+const int ZeroedStateFeedbackLoop::kZeroingMaxVoltage;
+
+bool ZeroedStateFeedbackLoop::SawFilteredPosedge(
+    const HallEffectTracker &this_sensor, const HallEffectTracker &sensorA,
+    const HallEffectTracker &sensorB) {
+  if (posedge_filter_ == nullptr && this_sensor.posedge_count_changed() &&
+      !sensorA.posedge_count_changed() && !sensorB.posedge_count_changed() &&
+      this_sensor.value() && !this_sensor.last_value()) {
+    posedge_filter_ = &this_sensor;
+  } else if (posedge_filter_ == &this_sensor &&
+             !this_sensor.posedge_count_changed() &&
+             !sensorA.posedge_count_changed() &&
+             !sensorB.posedge_count_changed() && this_sensor.value()) {
+    posedge_filter_ = nullptr;
+    return true;
+  } else if (posedge_filter_ == &this_sensor) {
+    posedge_filter_ = nullptr;
+  }
+  return false;
+}
+
+bool ZeroedStateFeedbackLoop::SawFilteredNegedge(
+    const HallEffectTracker &this_sensor, const HallEffectTracker &sensorA,
+    const HallEffectTracker &sensorB) {
+  if (negedge_filter_ == nullptr && this_sensor.negedge_count_changed() &&
+      !sensorA.negedge_count_changed() && !sensorB.negedge_count_changed() &&
+      !this_sensor.value() && this_sensor.last_value()) {
+    negedge_filter_ = &this_sensor;
+  } else if (negedge_filter_ == &this_sensor &&
+             !this_sensor.negedge_count_changed() &&
+             !sensorA.negedge_count_changed() &&
+             !sensorB.negedge_count_changed() && !this_sensor.value()) {
+    negedge_filter_ = nullptr;
+    return true;
+  } else if (negedge_filter_ == &this_sensor) {
+    negedge_filter_ = nullptr;
+  }
+  return false;
+}
+
+bool ZeroedStateFeedbackLoop::DoGetPositionOfEdge(
+    const constants::Values::Claws::AnglePair &angles, double *edge_encoder,
+    double *edge_angle, const HallEffectTracker &this_sensor,
+    const HallEffectTracker &sensorA, const HallEffectTracker &sensorB,
+    const char *hall_effect_name) {
+  bool found_edge = false;
+
+  if (SawFilteredPosedge(this_sensor, sensorA, sensorB)) {
+    if (min_hall_effect_off_angle_ == max_hall_effect_off_angle_) {
+      LOG(WARNING, "%s: Uncertain which side, rejecting posedge\n", name_);
+    } else {
+      const double average_last_encoder =
+          (min_hall_effect_off_angle_ + max_hall_effect_off_angle_) / 2.0;
+      if (posedge_value_ < average_last_encoder) {
+        *edge_angle = angles.upper_decreasing_angle;
+        LOG(INFO, "%s Posedge upper of %s -> %f posedge: %f avg_encoder: %f\n",
+            name_, hall_effect_name, *edge_angle, posedge_value_,
+            average_last_encoder);
+      } else {
+        *edge_angle = angles.lower_angle;
+        LOG(INFO, "%s Posedge lower of %s -> %f posedge: %f avg_encoder: %f\n",
+            name_, hall_effect_name, *edge_angle, posedge_value_,
+            average_last_encoder);
+      }
+      *edge_encoder = posedge_value_;
+      found_edge = true;
+    }
+  }
+
+  if (SawFilteredNegedge(this_sensor, sensorA, sensorB)) {
+    if (min_hall_effect_on_angle_ == max_hall_effect_on_angle_) {
+      LOG(WARNING, "%s: Uncertain which side, rejecting negedge\n", name_);
+    } else {
+      const double average_last_encoder =
+          (min_hall_effect_on_angle_ + max_hall_effect_on_angle_) / 2.0;
+      if (negedge_value_ > average_last_encoder) {
+        *edge_angle = angles.upper_angle;
+        LOG(INFO, "%s Negedge upper of %s -> %f negedge: %f avg_encoder: %f\n",
+            name_, hall_effect_name, *edge_angle, negedge_value_,
+            average_last_encoder);
+      } else {
+        *edge_angle = angles.lower_decreasing_angle;
+        LOG(INFO, "%s Negedge lower of %s -> %f negedge: %f avg_encoder: %f\n",
+            name_, hall_effect_name, *edge_angle, negedge_value_,
+            average_last_encoder);
+      }
+      *edge_encoder = negedge_value_;
+      found_edge = true;
+    }
+  }
+
+  return found_edge;
+}
+
+bool ZeroedStateFeedbackLoop::GetPositionOfEdge(
+    const constants::Values::Claws::Claw &claw_values, double *edge_encoder,
+    double *edge_angle) {
+  if (DoGetPositionOfEdge(claw_values.front, edge_encoder, edge_angle, front_,
+                          calibration_, back_, "front")) {
+    return true;
+  }
+  if (DoGetPositionOfEdge(claw_values.calibration, edge_encoder, edge_angle,
+                          calibration_, front_, back_, "calibration")) {
+    return true;
+  }
+  if (DoGetPositionOfEdge(claw_values.back, edge_encoder, edge_angle, back_,
+                          calibration_, front_, "back")) {
+    return true;
+  }
+  return false;
+}
+
+void TopZeroedStateFeedbackLoop::SetCalibration(double edge_encoder,
+                                                double edge_angle) {
+  double old_offset = offset_;
+  offset_ = edge_angle - edge_encoder;
+  const double doffset = offset_ - old_offset;
+  motor_->ChangeTopOffset(doffset);
+}
+
+double TopZeroedStateFeedbackLoop::ComputeCalibrationChange(double edge_encoder,
+                                                            double edge_angle) {
+  const double offset = edge_angle - edge_encoder;
+  const double doffset = offset - offset_;
+  return doffset;
+}
+
+void BottomZeroedStateFeedbackLoop::SetCalibration(double edge_encoder,
+                                                   double edge_angle) {
+  double old_offset = offset_;
+  offset_ = edge_angle - edge_encoder;
+  const double doffset = offset_ - old_offset;
+  motor_->ChangeBottomOffset(doffset);
+}
+
+double BottomZeroedStateFeedbackLoop::ComputeCalibrationChange(
+    double edge_encoder, double edge_angle) {
+  const double offset = edge_angle - edge_encoder;
+  const double doffset = offset - offset_;
+  return doffset;
+}
+
+void ClawMotor::ChangeTopOffset(double doffset) {
+  claw_.ChangeTopOffset(doffset);
+  if (has_top_claw_goal_) {
+    top_claw_goal_ += doffset;
+  }
+}
+
+void ClawMotor::ChangeBottomOffset(double doffset) {
+  claw_.ChangeBottomOffset(doffset);
+  if (has_bottom_claw_goal_) {
+    bottom_claw_goal_ += doffset;
+  }
+}
+
+void ClawLimitedLoop::ChangeTopOffset(double doffset) {
+  mutable_Y()(1, 0) += doffset;
+  mutable_X_hat()(1, 0) += doffset;
+  LOG(INFO, "Changing top offset by %f\n", doffset);
+}
+void ClawLimitedLoop::ChangeBottomOffset(double doffset) {
+  mutable_Y()(0, 0) += doffset;
+  mutable_X_hat()(0, 0) += doffset;
+  mutable_X_hat()(1, 0) -= doffset;
+  LOG(INFO, "Changing bottom offset by %f\n", doffset);
+}
+
+void LimitClawGoal(double *bottom_goal, double *top_goal,
+                   const frc971::constants::Values &values) {
+  // first update position based on angle limit
+  const double separation = *top_goal - *bottom_goal;
+  if (separation > values.claw.soft_max_separation) {
+    LOG_STRUCT(DEBUG, "before", ClawPositionToLog(*top_goal, *bottom_goal));
+    const double dsep = (separation - values.claw.soft_max_separation) / 2.0;
+    *bottom_goal += dsep;
+    *top_goal -= dsep;
+    LOG_STRUCT(DEBUG, "after", ClawPositionToLog(*top_goal, *bottom_goal));
+  }
+  if (separation < values.claw.soft_min_separation) {
+    LOG_STRUCT(DEBUG, "before", ClawPositionToLog(*top_goal, *bottom_goal));
+    const double dsep = (separation - values.claw.soft_min_separation) / 2.0;
+    *bottom_goal += dsep;
+    *top_goal -= dsep;
+    LOG_STRUCT(DEBUG, "after", ClawPositionToLog(*top_goal, *bottom_goal));
+  }
+
+  // now move both goals in unison
+  if (*bottom_goal < values.claw.lower_claw.lower_limit) {
+    LOG_STRUCT(DEBUG, "before", ClawPositionToLog(*top_goal, *bottom_goal));
+    *top_goal += values.claw.lower_claw.lower_limit - *bottom_goal;
+    *bottom_goal = values.claw.lower_claw.lower_limit;
+    LOG_STRUCT(DEBUG, "after", ClawPositionToLog(*top_goal, *bottom_goal));
+  }
+  if (*bottom_goal > values.claw.lower_claw.upper_limit) {
+    LOG_STRUCT(DEBUG, "before", ClawPositionToLog(*top_goal, *bottom_goal));
+    *top_goal -= *bottom_goal - values.claw.lower_claw.upper_limit;
+    *bottom_goal = values.claw.lower_claw.upper_limit;
+    LOG_STRUCT(DEBUG, "after", ClawPositionToLog(*top_goal, *bottom_goal));
+  }
+
+  if (*top_goal < values.claw.upper_claw.lower_limit) {
+    LOG_STRUCT(DEBUG, "before", ClawPositionToLog(*top_goal, *bottom_goal));
+    *bottom_goal += values.claw.upper_claw.lower_limit - *top_goal;
+    *top_goal = values.claw.upper_claw.lower_limit;
+    LOG_STRUCT(DEBUG, "after", ClawPositionToLog(*top_goal, *bottom_goal));
+  }
+  if (*top_goal > values.claw.upper_claw.upper_limit) {
+    LOG_STRUCT(DEBUG, "before", ClawPositionToLog(*top_goal, *bottom_goal));
+    *bottom_goal -= *top_goal - values.claw.upper_claw.upper_limit;
+    *top_goal = values.claw.upper_claw.upper_limit;
+    LOG_STRUCT(DEBUG, "after", ClawPositionToLog(*top_goal, *bottom_goal));
+  }
+}
+
+bool ClawMotor::is_ready() const {
+  return (
+      (top_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED &&
+       bottom_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED) ||
+      (((::aos::joystick_state.get() == NULL)
+            ? true
+            : ::aos::joystick_state->autonomous) &&
+       ((top_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED ||
+         top_claw_.zeroing_state() ==
+             ZeroedStateFeedbackLoop::DISABLED_CALIBRATION) &&
+        (bottom_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED ||
+         bottom_claw_.zeroing_state() ==
+             ZeroedStateFeedbackLoop::DISABLED_CALIBRATION))));
+}
+
+bool ClawMotor::is_zeroing() const { return !is_ready(); }
+
+// Positive angle is up, and positive power is up.
+void ClawMotor::RunIteration(const control_loops::ClawGroup::Goal *goal,
+                             const control_loops::ClawGroup::Position *position,
+                             control_loops::ClawGroup::Output *output,
+                             control_loops::ClawGroup::Status *status) {
+  constexpr double dt = 0.01;
+
+  // Disable the motors now so that all early returns will return with the
+  // motors disabled.
+  if (output) {
+    output->top_claw_voltage = 0;
+    output->bottom_claw_voltage = 0;
+    output->intake_voltage = 0;
+    output->tusk_voltage = 0;
+  }
+
+  if (goal) {
+    if (::std::isnan(goal->bottom_angle) ||
+        ::std::isnan(goal->separation_angle) || ::std::isnan(goal->intake) ||
+        ::std::isnan(goal->centering)) {
+      return;
+    }
+  }
+
+  if (WasReset()) {
+    top_claw_.Reset(position->top);
+    bottom_claw_.Reset(position->bottom);
+  }
+
+  const frc971::constants::Values &values = constants::GetValues();
+
+  if (position) {
+    Eigen::Matrix<double, 2, 1> Y;
+    Y << position->bottom.position + bottom_claw_.offset(),
+        position->top.position + top_claw_.offset();
+    claw_.Correct(Y);
+
+    top_claw_.SetPositionValues(position->top);
+    bottom_claw_.SetPositionValues(position->bottom);
+
+    if (!has_top_claw_goal_) {
+      has_top_claw_goal_ = true;
+      top_claw_goal_ = top_claw_.absolute_position();
+      initial_separation_ =
+          top_claw_.absolute_position() - bottom_claw_.absolute_position();
+    }
+    if (!has_bottom_claw_goal_) {
+      has_bottom_claw_goal_ = true;
+      bottom_claw_goal_ = bottom_claw_.absolute_position();
+      initial_separation_ =
+          top_claw_.absolute_position() - bottom_claw_.absolute_position();
+    }
+    LOG_STRUCT(DEBUG, "absolute position",
+               ClawPositionToLog(top_claw_.absolute_position(),
+                                 bottom_claw_.absolute_position()));
+  }
+
+  bool autonomous, enabled;
+  if (::aos::joystick_state.get() == nullptr) {
+    autonomous = true;
+    enabled = false;
+  } else {
+    autonomous = ::aos::joystick_state->autonomous;
+    enabled = ::aos::joystick_state->enabled;
+  }
+
+  double bottom_claw_velocity_ = 0.0;
+  double top_claw_velocity_ = 0.0;
+
+  if (goal != NULL &&
+      ((top_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED &&
+        bottom_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED) ||
+       (autonomous &&
+        ((top_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED ||
+          top_claw_.zeroing_state() ==
+              ZeroedStateFeedbackLoop::DISABLED_CALIBRATION) &&
+         (bottom_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED ||
+          bottom_claw_.zeroing_state() ==
+              ZeroedStateFeedbackLoop::DISABLED_CALIBRATION))))) {
+    // Ready to use the claw.
+    // Limit the goals here.
+    bottom_claw_goal_ = goal->bottom_angle;
+    top_claw_goal_ = goal->bottom_angle + goal->separation_angle;
+    has_bottom_claw_goal_ = true;
+    has_top_claw_goal_ = true;
+    doing_calibration_fine_tune_ = false;
+    mode_ = READY;
+
+    bottom_claw_.HandleCalibrationError(values.claw.lower_claw);
+    top_claw_.HandleCalibrationError(values.claw.upper_claw);
+  } else if (top_claw_.zeroing_state() !=
+             ZeroedStateFeedbackLoop::UNKNOWN_POSITION &&
+             bottom_claw_.zeroing_state() !=
+             ZeroedStateFeedbackLoop::UNKNOWN_POSITION) {
+    // Time to fine tune the zero.
+    // Limit the goals here.
+    if (!enabled) {
+      // If we are disabled, start the fine tune process over again.
+      doing_calibration_fine_tune_ = false;
+    }
+    if (bottom_claw_.zeroing_state() != ZeroedStateFeedbackLoop::CALIBRATED) {
+      // always get the bottom claw to calibrated first
+      LOG(DEBUG, "Calibrating the bottom of the claw\n");
+      if (!doing_calibration_fine_tune_) {
+        if (::std::abs(bottom_absolute_position() -
+                       values.claw.start_fine_tune_pos) <
+            values.claw.claw_unimportant_epsilon) {
+          doing_calibration_fine_tune_ = true;
+          bottom_claw_goal_ += values.claw.claw_zeroing_speed * dt;
+          top_claw_velocity_ = bottom_claw_velocity_ =
+              values.claw.claw_zeroing_speed;
+          LOG(DEBUG, "Ready to fine tune the bottom\n");
+          mode_ = FINE_TUNE_BOTTOM;
+        } else {
+          // send bottom to zeroing start
+          bottom_claw_goal_ = values.claw.start_fine_tune_pos;
+          LOG(DEBUG, "Going to the start position for the bottom\n");
+          mode_ = PREP_FINE_TUNE_BOTTOM;
+        }
+      } else {
+        mode_ = FINE_TUNE_BOTTOM;
+        bottom_claw_goal_ += values.claw.claw_zeroing_speed * dt;
+        top_claw_velocity_ = bottom_claw_velocity_ =
+            values.claw.claw_zeroing_speed;
+        if (top_claw_.front_or_back_triggered() ||
+            bottom_claw_.front_or_back_triggered()) {
+          // We shouldn't hit a limit, but if we do, go back to the zeroing
+          // point and try again.
+          doing_calibration_fine_tune_ = false;
+          bottom_claw_goal_ = values.claw.start_fine_tune_pos;
+          top_claw_velocity_ = bottom_claw_velocity_ = 0.0;
+          LOG(DEBUG, "Found a limit, starting over.\n");
+          mode_ = PREP_FINE_TUNE_BOTTOM;
+        }
+
+        if (position && bottom_claw_.SawFilteredPosedge(
+                            bottom_claw_.calibration(), bottom_claw_.front(),
+                            bottom_claw_.back())) {
+          // do calibration
+          bottom_claw_.SetCalibration(
+              position->bottom.posedge_value,
+              values.claw.lower_claw.calibration.lower_angle);
+          bottom_claw_.set_zeroing_state(ZeroedStateFeedbackLoop::CALIBRATED);
+          // calibrated so we are done fine tuning bottom
+          doing_calibration_fine_tune_ = false;
+          LOG(DEBUG, "Calibrated the bottom correctly!\n");
+        } else if (bottom_claw_.calibration().last_value()) {
+          LOG(DEBUG, "Aborting bottom fine tune because sensor triggered\n");
+          doing_calibration_fine_tune_ = false;
+          bottom_claw_.set_zeroing_state(
+              ZeroedStateFeedbackLoop::UNKNOWN_POSITION);
+        } else {
+          LOG(DEBUG, "Fine tuning\n");
+        }
+      }
+      // now set the top claw to track
+
+      top_claw_goal_ = bottom_claw_goal_ + values.claw.claw_zeroing_separation;
+    } else {
+      // bottom claw must be calibrated, start on the top
+      if (!doing_calibration_fine_tune_) {
+        if (::std::abs(top_absolute_position() -
+                       values.claw.start_fine_tune_pos) <
+            values.claw.claw_unimportant_epsilon) {
+          doing_calibration_fine_tune_ = true;
+          top_claw_goal_ += values.claw.claw_zeroing_speed * dt;
+          top_claw_velocity_ = bottom_claw_velocity_ =
+              values.claw.claw_zeroing_speed;
+          LOG(DEBUG, "Ready to fine tune the top\n");
+          mode_ = FINE_TUNE_TOP;
+        } else {
+          // send top to zeroing start
+          top_claw_goal_ = values.claw.start_fine_tune_pos;
+          LOG(DEBUG, "Going to the start position for the top\n");
+          mode_ = PREP_FINE_TUNE_TOP;
+        }
+      } else {
+        mode_ = FINE_TUNE_TOP;
+        top_claw_goal_ += values.claw.claw_zeroing_speed * dt;
+        top_claw_velocity_ = bottom_claw_velocity_ =
+            values.claw.claw_zeroing_speed;
+        if (top_claw_.front_or_back_triggered() ||
+            bottom_claw_.front_or_back_triggered()) {
+          // this should not happen, but now we know it won't
+          doing_calibration_fine_tune_ = false;
+          top_claw_goal_ = values.claw.start_fine_tune_pos;
+          top_claw_velocity_ = bottom_claw_velocity_ = 0.0;
+          LOG(DEBUG, "Found a limit, starting over.\n");
+          mode_ = PREP_FINE_TUNE_TOP;
+        }
+
+        if (position &&
+            top_claw_.SawFilteredPosedge(top_claw_.calibration(),
+                                         top_claw_.front(), top_claw_.back())) {
+          // do calibration
+          top_claw_.SetCalibration(
+              position->top.posedge_value,
+              values.claw.upper_claw.calibration.lower_angle);
+          top_claw_.set_zeroing_state(ZeroedStateFeedbackLoop::CALIBRATED);
+          // calibrated so we are done fine tuning top
+          doing_calibration_fine_tune_ = false;
+          LOG(DEBUG, "Calibrated the top correctly!\n");
+        } else if (top_claw_.calibration().last_value()) {
+          LOG(DEBUG, "Aborting top fine tune because sensor triggered\n");
+          doing_calibration_fine_tune_ = false;
+          top_claw_.set_zeroing_state(
+              ZeroedStateFeedbackLoop::UNKNOWN_POSITION);
+        }
+      }
+      // now set the bottom claw to track
+      bottom_claw_goal_ = top_claw_goal_ - values.claw.claw_zeroing_separation;
+    }
+  } else {
+    doing_calibration_fine_tune_ = false;
+    if (!was_enabled_ && enabled) {
+      if (position) {
+        top_claw_goal_ = position->top.position + top_claw_.offset();
+        bottom_claw_goal_ = position->bottom.position + bottom_claw_.offset();
+        initial_separation_ =
+            position->top.position - position->bottom.position;
+      } else {
+        has_top_claw_goal_ = false;
+        has_bottom_claw_goal_ = false;
+      }
+    }
+
+    if ((bottom_claw_.zeroing_state() !=
+             ZeroedStateFeedbackLoop::UNKNOWN_POSITION ||
+         bottom_claw_.front().value() || top_claw_.front().value()) &&
+        !top_claw_.back().value() && !bottom_claw_.back().value()) {
+      if (enabled) {
+        // Time to slowly move back up to find any position to narrow down the
+        // zero.
+        top_claw_goal_ += values.claw.claw_zeroing_off_speed * dt;
+        bottom_claw_goal_ += values.claw.claw_zeroing_off_speed * dt;
+        top_claw_velocity_ = bottom_claw_velocity_ =
+            values.claw.claw_zeroing_off_speed;
+        LOG(DEBUG, "Bottom is known.\n");
+      }
+    } else {
+      // We don't know where either claw is.  Slowly start moving down to find
+      // any hall effect.
+      if (enabled) {
+        top_claw_goal_ -= values.claw.claw_zeroing_off_speed * dt;
+        bottom_claw_goal_ -= values.claw.claw_zeroing_off_speed * dt;
+        top_claw_velocity_ = bottom_claw_velocity_ =
+            -values.claw.claw_zeroing_off_speed;
+        LOG(DEBUG, "Both are unknown.\n");
+      }
+    }
+
+    if (position) {
+      if (enabled) {
+        top_claw_.SetCalibrationOnEdge(
+            values.claw.upper_claw,
+            ZeroedStateFeedbackLoop::APPROXIMATE_CALIBRATION);
+        bottom_claw_.SetCalibrationOnEdge(
+            values.claw.lower_claw,
+            ZeroedStateFeedbackLoop::APPROXIMATE_CALIBRATION);
+      } else {
+        // TODO(austin): Only calibrate on the predetermined edge.
+        // We might be able to just ignore this since the backlash is soooo
+        // low.
+        // :)
+        top_claw_.SetCalibrationOnEdge(
+            values.claw.upper_claw,
+            ZeroedStateFeedbackLoop::DISABLED_CALIBRATION);
+        bottom_claw_.SetCalibrationOnEdge(
+            values.claw.lower_claw,
+            ZeroedStateFeedbackLoop::DISABLED_CALIBRATION);
+      }
+    }
+    mode_ = UNKNOWN_LOCATION;
+  }
+
+  // Limit the goals if both claws have been (mostly) found.
+  if (mode_ != UNKNOWN_LOCATION) {
+    LimitClawGoal(&bottom_claw_goal_, &top_claw_goal_, values);
+  }
+
+  claw_.set_positions_known(
+      top_claw_.zeroing_state() != ZeroedStateFeedbackLoop::UNKNOWN_POSITION,
+      bottom_claw_.zeroing_state() !=
+          ZeroedStateFeedbackLoop::UNKNOWN_POSITION);
+  if (has_top_claw_goal_ && has_bottom_claw_goal_) {
+    claw_.mutable_R() << bottom_claw_goal_, top_claw_goal_ - bottom_claw_goal_,
+        bottom_claw_velocity_, top_claw_velocity_ - bottom_claw_velocity_;
+    LOG_MATRIX(DEBUG, "actual goal", claw_.R());
+
+    // Only cap power when one of the halves of the claw is moving slowly and
+    // could wind up.
+    claw_.set_is_zeroing(mode_ == UNKNOWN_LOCATION || mode_ == FINE_TUNE_TOP ||
+                         mode_ == FINE_TUNE_BOTTOM);
+    claw_.Update(output == nullptr);
+  } else {
+    claw_.Update(true);
+  }
+
+  capped_goal_ = false;
+  switch (mode_) {
+    case READY:
+    case PREP_FINE_TUNE_TOP:
+    case PREP_FINE_TUNE_BOTTOM:
+      break;
+    case FINE_TUNE_BOTTOM:
+    case FINE_TUNE_TOP:
+    case UNKNOWN_LOCATION: {
+      if (claw_.uncapped_average_voltage() > values.claw.max_zeroing_voltage) {
+        double dx_bot = (claw_.U_uncapped(0, 0) -
+                     values.claw.max_zeroing_voltage) /
+                    claw_.K(0, 0);
+        double dx_top = (claw_.U_uncapped(1, 0) -
+                     values.claw.max_zeroing_voltage) /
+                    claw_.K(0, 0);
+        double dx = ::std::max(dx_top, dx_bot);
+        bottom_claw_goal_ -= dx;
+        top_claw_goal_ -= dx;
+        Eigen::Matrix<double, 4, 1> R;
+        R << bottom_claw_goal_, top_claw_goal_ - bottom_claw_goal_, claw_.R(2, 0),
+            claw_.R(3, 0);
+        claw_.mutable_U() = claw_.K() * (R - claw_.X_hat());
+        capped_goal_ = true;
+        LOG(DEBUG, "Moving the goal by %f to prevent windup."
+            " Uncapped is %f, max is %f, difference is %f\n",
+            dx,
+            claw_.uncapped_average_voltage(), values.claw.max_zeroing_voltage,
+            (claw_.uncapped_average_voltage() -
+             values.claw.max_zeroing_voltage));
+      } else if (claw_.uncapped_average_voltage() <
+                 -values.claw.max_zeroing_voltage) {
+        double dx_bot = (claw_.U_uncapped(0, 0) +
+                     values.claw.max_zeroing_voltage) /
+                    claw_.K(0, 0);
+        double dx_top = (claw_.U_uncapped(1, 0) +
+                     values.claw.max_zeroing_voltage) /
+                    claw_.K(0, 0);
+        double dx = ::std::min(dx_top, dx_bot);
+        bottom_claw_goal_ -= dx;
+        top_claw_goal_ -= dx;
+        Eigen::Matrix<double, 4, 1> R;
+        R << bottom_claw_goal_, top_claw_goal_ - bottom_claw_goal_, claw_.R(2, 0),
+            claw_.R(3, 0);
+        claw_.mutable_U() = claw_.K() * (R - claw_.X_hat());
+        capped_goal_ = true;
+        LOG(DEBUG, "Moving the goal by %f to prevent windup\n", dx);
+      }
+    } break;
+  }
+
+  if (output) {
+    if (goal) {
+      //setup the intake
+      output->intake_voltage =
+          (goal->intake > 12.0) ? 12 : (goal->intake < -12.0) ? -12.0
+                                                              : goal->intake;
+      output->tusk_voltage = goal->centering;
+      output->tusk_voltage =
+          (goal->centering > 12.0) ? 12 : (goal->centering < -12.0)
+              ? -12.0
+              : goal->centering;
+    }
+    output->top_claw_voltage = claw_.U(1, 0);
+    output->bottom_claw_voltage = claw_.U(0, 0);
+
+    if (output->top_claw_voltage > kMaxVoltage) {
+      output->top_claw_voltage = kMaxVoltage;
+    } else if (output->top_claw_voltage < -kMaxVoltage) {
+      output->top_claw_voltage = -kMaxVoltage;
+    }
+
+    if (output->bottom_claw_voltage > kMaxVoltage) {
+      output->bottom_claw_voltage = kMaxVoltage;
+    } else if (output->bottom_claw_voltage < -kMaxVoltage) {
+      output->bottom_claw_voltage = -kMaxVoltage;
+    }
+  }
+
+  status->bottom = bottom_absolute_position();
+  status->separation = top_absolute_position() - bottom_absolute_position();
+  status->bottom_velocity = claw_.X_hat(2, 0);
+  status->separation_velocity = claw_.X_hat(3, 0);
+
+  if (goal) {
+    bool bottom_done =
+        ::std::abs(bottom_absolute_position() - goal->bottom_angle) < 0.020;
+    bool bottom_velocity_done = ::std::abs(status->bottom_velocity) < 0.2;
+    bool separation_done =
+        ::std::abs((top_absolute_position() - bottom_absolute_position()) -
+                   goal->separation_angle) < 0.020;
+    bool separation_done_with_ball =
+        ::std::abs((top_absolute_position() - bottom_absolute_position()) -
+                   goal->separation_angle) < 0.06;
+    status->done = is_ready() && separation_done && bottom_done && bottom_velocity_done;
+    status->done_with_ball =
+        is_ready() && separation_done_with_ball && bottom_done && bottom_velocity_done;
+  } else {
+    status->done = status->done_with_ball = false;
+  }
+
+  status->zeroed = is_ready();
+  status->zeroed_for_auto =
+      (top_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED ||
+       top_claw_.zeroing_state() ==
+           ZeroedStateFeedbackLoop::DISABLED_CALIBRATION) &&
+      (bottom_claw_.zeroing_state() == ZeroedStateFeedbackLoop::CALIBRATED ||
+       bottom_claw_.zeroing_state() ==
+           ZeroedStateFeedbackLoop::DISABLED_CALIBRATION);
+
+  was_enabled_ = enabled;
+}
+
+}  // namespace control_loops
+}  // namespace frc971
+
diff --git a/y2014/control_loops/claw/claw.gyp b/y2014/control_loops/claw/claw.gyp
new file mode 100644
index 0000000..40315ff
--- /dev/null
+++ b/y2014/control_loops/claw/claw.gyp
@@ -0,0 +1,99 @@
+{
+  'targets': [
+    {
+      'target_name': 'replay_claw',
+      'type': 'executable',
+      'variables': {
+        'no_rsync': 1,
+      },
+      'sources': [
+        'replay_claw.cc',
+      ],
+      'dependencies': [
+        'claw_queue',
+        '<(AOS)/common/controls/controls.gyp:replay_control_loop',
+        '<(AOS)/linux_code/linux_code.gyp:init',
+      ],
+    },
+    {
+      'target_name': 'claw_loop',
+      'type': 'static_library',
+      'sources': ['claw.q'],
+      'variables': {
+        'header_path': 'y2014/control_loops/claw',
+      },
+      'dependencies': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+      ],
+      'includes': ['../../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'claw_lib',
+      'type': 'static_library',
+      'sources': [
+        'claw.cc',
+        'claw_motor_plant.cc',
+      ],
+      'dependencies': [
+        'claw_loop',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(DEPTH)/y2014/y2014.gyp:constants',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(AOS)/common/controls/controls.gyp:polytope',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+        '<(AOS)/common/logging/logging.gyp:matrix_logging',
+      ],
+      'export_dependent_settings': [
+        'claw_loop',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(AOS)/common/controls/controls.gyp:polytope',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
+      ],
+    },
+    {
+      'target_name': 'claw_lib_test',
+      'type': 'executable',
+      'sources': [
+        'claw_lib_test.cc',
+      ],
+      'dependencies': [
+        '<(EXTERNALS):gtest',
+        'claw_loop',
+        'claw_lib',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(AOS)/common/controls/controls.gyp:control_loop_test',
+      ],
+    },
+    {
+      'target_name': 'claw_calibration',
+      'type': 'executable',
+      'sources': [
+        'claw_calibration.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'claw_loop',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(DEPTH)/y2014/y2014.gyp:constants',
+      ],
+    },
+    {
+      'target_name': 'claw',
+      'type': 'executable',
+      'sources': [
+        'claw_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'claw_lib',
+      ],
+    },
+  ],
+}
diff --git a/y2014/control_loops/claw/claw.h b/y2014/control_loops/claw/claw.h
new file mode 100644
index 0000000..c04a8fe
--- /dev/null
+++ b/y2014/control_loops/claw/claw.h
@@ -0,0 +1,267 @@
+#ifndef Y2014_CONTROL_LOOPS_CLAW_CLAW_H_
+#define Y2014_CONTROL_LOOPS_CLAW_CLAW_H_
+
+#include <memory>
+
+#include "aos/common/controls/control_loop.h"
+#include "aos/common/controls/polytope.h"
+#include "y2014/constants.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/coerce_goal.h"
+#include "y2014/control_loops/claw/claw.q.h"
+#include "y2014/control_loops/claw/claw_motor_plant.h"
+#include "frc971/control_loops/hall_effect_tracker.h"
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+class WindupClawTest;
+};
+
+// Note: Everything in this file assumes that there is a 1 cycle delay between
+// power being requested and it showing up at the motor.  It assumes that
+// X_hat(2, 1) is the voltage being applied as well.  It will go unstable if
+// that isn't true.
+
+class ClawLimitedLoop : public StateFeedbackLoop<4, 2, 2> {
+ public:
+  ClawLimitedLoop(StateFeedbackLoop<4, 2, 2> &&loop);
+  virtual void CapU();
+
+  void set_is_zeroing(bool is_zeroing) { is_zeroing_ = is_zeroing; }
+  void set_positions_known(bool top_known, bool bottom_known) {
+    top_known_ = top_known;
+    bottom_known_ = bottom_known;
+  }
+
+  void ChangeTopOffset(double doffset);
+  void ChangeBottomOffset(double doffset);
+
+  double uncapped_average_voltage() const { return uncapped_average_voltage_; }
+
+ private:
+  double uncapped_average_voltage_;
+  bool is_zeroing_;
+
+  bool top_known_ = false, bottom_known_ = false;
+
+  const ::aos::controls::HPolytope<2> U_Poly_, U_Poly_zeroing_;
+};
+
+class ClawMotor;
+
+// This class implements the CapU function correctly given all the extra
+// information that we know about from the wrist motor.
+// It does not have any zeroing logic in it, only logic to deal with a delta U
+// controller.
+class ZeroedStateFeedbackLoop {
+ public:
+  ZeroedStateFeedbackLoop(const char *name, ClawMotor *motor);
+
+  const static int kZeroingMaxVoltage = 5;
+
+  enum JointZeroingState {
+    // We don't know where the joint is at all.
+    UNKNOWN_POSITION,
+    // We have an approximate position for where the claw is using.
+    APPROXIMATE_CALIBRATION,
+    // We observed the calibration edge while disabled. This is good enough for
+    // autonomous mode.
+    DISABLED_CALIBRATION,
+    // Ready for use during teleop.
+    CALIBRATED
+  };
+
+  void set_zeroing_state(JointZeroingState zeroing_state) {
+    zeroing_state_ = zeroing_state;
+  }
+  JointZeroingState zeroing_state() const { return zeroing_state_; }
+
+  void SetPositionValues(const HalfClawPosition &claw);
+
+  void Reset(const HalfClawPosition &claw);
+
+  double absolute_position() const { return encoder() + offset(); }
+
+  const HallEffectTracker &front() const { return front_; }
+  const HallEffectTracker &calibration() const { return calibration_; }
+  const HallEffectTracker &back() const { return back_; }
+
+  bool any_hall_effect_changed() const {
+    return front().either_count_changed() ||
+           calibration().either_count_changed() ||
+           back().either_count_changed();
+  }
+  bool front_or_back_triggered() const {
+    return front().value() || back().value();
+  }
+  bool any_triggered() const {
+    return calibration().value() || front().value() || back().value();
+  }
+
+  double encoder() const { return encoder_; }
+  double last_encoder() const { return last_encoder_; }
+
+  double offset() const { return offset_; }
+
+  // Returns true if an edge was detected in the last cycle and then sets the
+  // edge_position to the absolute position of the edge.
+  bool GetPositionOfEdge(const constants::Values::Claws::Claw &claw,
+                         double *edge_encoder, double *edge_angle);
+
+  bool SawFilteredPosedge(const HallEffectTracker &this_sensor,
+                          const HallEffectTracker &sensorA,
+                          const HallEffectTracker &sensorB);
+
+  bool SawFilteredNegedge(const HallEffectTracker &this_sensor,
+                          const HallEffectTracker &sensorA,
+                          const HallEffectTracker &sensorB);
+
+#undef COUNT_SETTER_GETTER
+
+ protected:
+  // The accumulated voltage to apply to the motor.
+  double offset_;
+  const char *name_;
+
+  ClawMotor *motor_;
+
+  HallEffectTracker front_, calibration_, back_;
+
+  JointZeroingState zeroing_state_;
+  double posedge_value_;
+  double negedge_value_;
+  double min_hall_effect_on_angle_;
+  double max_hall_effect_on_angle_;
+  double min_hall_effect_off_angle_;
+  double max_hall_effect_off_angle_;
+  double encoder_;
+  double last_encoder_;
+  double last_on_encoder_;
+  double last_off_encoder_;
+  bool any_triggered_last_;
+
+  const HallEffectTracker* posedge_filter_ = nullptr;
+  const HallEffectTracker* negedge_filter_ = nullptr;
+
+ private:
+  // Does the edges of 1 sensor for GetPositionOfEdge.
+  bool DoGetPositionOfEdge(const constants::Values::Claws::AnglePair &angles,
+                           double *edge_encoder, double *edge_angle,
+                           const HallEffectTracker &sensor,
+                           const HallEffectTracker &sensorA,
+                           const HallEffectTracker &sensorB,
+                           const char *hall_effect_name);
+};
+
+class TopZeroedStateFeedbackLoop : public ZeroedStateFeedbackLoop {
+ public:
+  TopZeroedStateFeedbackLoop(ClawMotor *motor)
+      : ZeroedStateFeedbackLoop("top", motor) {}
+  // Sets the calibration offset given the absolute angle and the corresponding
+  // encoder value.
+  void SetCalibration(double edge_encoder, double edge_angle);
+
+  bool SetCalibrationOnEdge(const constants::Values::Claws::Claw &claw_values,
+                            JointZeroingState zeroing_state);
+  double ComputeCalibrationChange(double edge_encoder, double edge_angle);
+  void HandleCalibrationError(
+      const constants::Values::Claws::Claw &claw_values);
+};
+
+class BottomZeroedStateFeedbackLoop : public ZeroedStateFeedbackLoop {
+ public:
+  BottomZeroedStateFeedbackLoop(ClawMotor *motor)
+      : ZeroedStateFeedbackLoop("bottom", motor) {}
+  // Sets the calibration offset given the absolute angle and the corrisponding
+  // encoder value.
+  void SetCalibration(double edge_encoder, double edge_angle);
+
+  bool SetCalibrationOnEdge(const constants::Values::Claws::Claw &claw_values,
+                            JointZeroingState zeroing_state);
+  double ComputeCalibrationChange(double edge_encoder, double edge_angle);
+  void HandleCalibrationError(
+      const constants::Values::Claws::Claw &claw_values);
+};
+
+class ClawMotor : public aos::controls::ControlLoop<control_loops::ClawGroup> {
+ public:
+  explicit ClawMotor(control_loops::ClawGroup *my_claw =
+                         &control_loops::claw_queue_group);
+
+  // True if the state machine is ready.
+  bool capped_goal() const { return capped_goal_; }
+
+  double uncapped_average_voltage() const {
+    return claw_.uncapped_average_voltage();
+  }
+
+  // True if the claw is zeroing.
+  bool is_zeroing() const;
+
+  // True if the state machine is ready.
+  bool is_ready() const;
+
+  void ChangeTopOffset(double doffset);
+  void ChangeBottomOffset(double doffset);
+
+  enum CalibrationMode {
+    READY,
+    PREP_FINE_TUNE_TOP,
+    FINE_TUNE_TOP,
+    PREP_FINE_TUNE_BOTTOM,
+    FINE_TUNE_BOTTOM,
+    UNKNOWN_LOCATION
+  };
+
+  CalibrationMode mode() const { return mode_; }
+
+ protected:
+  virtual void RunIteration(const control_loops::ClawGroup::Goal *goal,
+                            const control_loops::ClawGroup::Position *position,
+                            control_loops::ClawGroup::Output *output,
+                            control_loops::ClawGroup::Status *status);
+
+  double top_absolute_position() const {
+    return claw_.X_hat(1, 0) + claw_.X_hat(0, 0);
+  }
+  double bottom_absolute_position() const { return claw_.X_hat(0, 0); }
+
+ private:
+  // Friend the test classes for acces to the internal state.
+  friend class testing::WindupClawTest;
+
+  // The zeroed joint to use.
+  bool has_top_claw_goal_;
+  double top_claw_goal_;
+  TopZeroedStateFeedbackLoop top_claw_;
+
+  bool has_bottom_claw_goal_;
+  double bottom_claw_goal_;
+  BottomZeroedStateFeedbackLoop bottom_claw_;
+
+  // The claw loop.
+  ClawLimitedLoop claw_;
+
+  bool was_enabled_;
+  bool doing_calibration_fine_tune_;
+
+  // The initial separation when disabled.  Used as the safe separation
+  // distance.
+  double initial_separation_;
+
+  bool capped_goal_;
+  CalibrationMode mode_;
+
+  DISALLOW_COPY_AND_ASSIGN(ClawMotor);
+};
+
+// Modifies the bottom and top goal such that they are within the limits and
+// their separation isn't too much or little.
+void LimitClawGoal(double *bottom_goal, double *top_goal,
+                   const frc971::constants::Values &values);
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // Y2014_CONTROL_LOOPS_CLAW_CLAW_H_
diff --git a/y2014/control_loops/claw/claw.q b/y2014/control_loops/claw/claw.q
new file mode 100644
index 0000000..860854b
--- /dev/null
+++ b/y2014/control_loops/claw/claw.q
@@ -0,0 +1,82 @@
+package frc971.control_loops;
+
+import "aos/common/controls/control_loops.q";
+import "frc971/control_loops/control_loops.q";
+
+struct HalfClawPosition {
+  // The current position of this half of the claw.
+  double position;
+
+  // The hall effect sensor at the front limit.
+  HallEffectStruct front;
+  // The hall effect sensor in the middle to use for real calibration.
+  HallEffectStruct calibration;
+  // The hall effect at the back limit.
+  HallEffectStruct back;
+
+  // The encoder value at the last posedge of any of the claw hall effect
+  // sensors (front, calibration, or back).
+  double posedge_value;
+  // The encoder value at the last negedge of any of the claw hall effect
+  // sensors (front, calibration, or back).
+  double negedge_value;
+};
+
+// All angles here are 0 vertical, positive "up" (aka backwards).
+queue_group ClawGroup {
+  implements aos.control_loops.ControlLoop;
+
+  message Goal {
+    // The angle of the bottom claw.
+    double bottom_angle;
+    // How much higher the top claw is.
+    double separation_angle;
+    // top claw intake roller
+    double intake;
+    // bottom claw tusk centering
+    double centering;
+  };
+
+  message Position {
+    // All the top claw information.
+    HalfClawPosition top;
+    // All the bottom claw information.
+    HalfClawPosition bottom;
+  };
+
+  message Output {
+    double intake_voltage;
+    double top_claw_voltage;
+    double bottom_claw_voltage;
+    double tusk_voltage;
+  };
+
+  message Status {
+    // True if zeroed enough for the current period (autonomous or teleop).
+    bool zeroed;
+    // True if zeroed as much as we will force during autonomous.
+    bool zeroed_for_auto;
+    // True if zeroed and within tolerance for separation and bottom angle.
+    bool done;
+    // True if zeroed and within tolerance for separation and bottom angle.
+    // seperation allowance much wider as a ball may be included
+    bool done_with_ball;
+    // Dump the values of the state matrix.
+    double bottom;
+    double bottom_velocity;
+    double separation;
+    double separation_velocity;
+  };
+
+  queue Goal goal;
+  queue Position position;
+  queue Output output;
+  queue Status status;
+};
+
+queue_group ClawGroup claw_queue_group;
+
+struct ClawPositionToLog {
+	double top;
+	double bottom;
+};
diff --git a/y2014/control_loops/claw/claw_calibration.cc b/y2014/control_loops/claw/claw_calibration.cc
new file mode 100644
index 0000000..de91d91
--- /dev/null
+++ b/y2014/control_loops/claw/claw_calibration.cc
@@ -0,0 +1,310 @@
+#include "y2014/control_loops/claw/claw.q.h"
+#include "frc971/control_loops/control_loops.q.h"
+
+#include "aos/linux_code/init.h"
+#include "y2014/constants.h"
+
+namespace frc971 {
+
+typedef constants::Values::Claws Claws;
+
+class Sensor {
+ public:
+  Sensor(const double start_position,
+         const HallEffectStruct &initial_hall_effect)
+      : start_position_(start_position),
+        last_hall_effect_(initial_hall_effect),
+        last_posedge_count_(initial_hall_effect.posedge_count),
+        last_negedge_count_(initial_hall_effect.negedge_count) {
+    last_on_min_position_ = start_position;
+    last_on_max_position_ = start_position;
+    last_off_min_position_ = start_position;
+    last_off_max_position_ = start_position;
+  }
+
+  bool DoGetPositionOfEdge(
+      const control_loops::HalfClawPosition &claw_position,
+      const HallEffectStruct &hall_effect, Claws::AnglePair *limits) {
+    bool print = false;
+
+    if (hall_effect.posedge_count != last_posedge_count_) {
+      const double avg_off_position = (last_off_min_position_ + last_off_max_position_) / 2.0;
+      if (claw_position.posedge_value < avg_off_position) {
+        printf("Posedge upper current %f posedge %f avg_off %f [%f, %f]\n",
+               claw_position.position, claw_position.posedge_value,
+               avg_off_position, last_off_min_position_,
+               last_off_max_position_);
+        limits->upper_decreasing_angle = claw_position.posedge_value - start_position_;
+      } else {
+        printf("Posedge lower current %f posedge %f avg_off %f [%f, %f]\n",
+               claw_position.position, claw_position.posedge_value,
+               avg_off_position, last_off_min_position_,
+               last_off_max_position_);
+        limits->lower_angle =
+            claw_position.posedge_value - start_position_;
+      }
+      print = true;
+    }
+    if (hall_effect.negedge_count != last_negedge_count_) {
+      const double avg_on_position = (last_on_min_position_ + last_on_max_position_) / 2.0;
+      if (claw_position.negedge_value > avg_on_position) {
+        printf("Negedge upper current %f negedge %f last_on %f [%f, %f]\n",
+               claw_position.position, claw_position.negedge_value,
+               avg_on_position, last_on_min_position_,
+               last_on_max_position_);
+        limits->upper_angle =
+            claw_position.negedge_value - start_position_;
+      } else {
+        printf("Negedge lower current %f negedge %f last_on %f [%f, %f]\n",
+               claw_position.position, claw_position.negedge_value,
+               avg_on_position, last_on_min_position_,
+               last_on_max_position_);
+        limits->lower_decreasing_angle = claw_position.negedge_value - start_position_;
+      }
+      print = true;
+    }
+
+    if (hall_effect.current) {
+      if (!last_hall_effect_.current) {
+        last_on_min_position_ = last_on_max_position_ = claw_position.position;
+      } else {
+        last_on_min_position_ =
+            ::std::min(claw_position.position, last_on_min_position_);
+        last_on_max_position_ =
+            ::std::max(claw_position.position, last_on_max_position_);
+      }
+    } else {
+      if (last_hall_effect_.current) {
+        last_off_min_position_ = last_off_max_position_ = claw_position.position;
+      } else {
+        last_off_min_position_ =
+            ::std::min(claw_position.position, last_off_min_position_);
+        last_off_max_position_ =
+            ::std::max(claw_position.position, last_off_max_position_);
+      }
+    }
+
+    last_hall_effect_ = hall_effect;
+    last_posedge_count_ = hall_effect.posedge_count;
+    last_negedge_count_ = hall_effect.negedge_count;
+
+    return print;
+  }
+
+ private:
+  const double start_position_;
+  HallEffectStruct last_hall_effect_;
+  int32_t last_posedge_count_;
+  int32_t last_negedge_count_;
+  double last_on_min_position_;
+  double last_off_min_position_;
+  double last_on_max_position_;
+  double last_off_max_position_;
+};
+
+class ClawSensors {
+ public:
+  ClawSensors(const double start_position,
+              const control_loops::HalfClawPosition &initial_claw_position)
+      : start_position_(start_position),
+        front_(start_position, initial_claw_position.front),
+        calibration_(start_position, initial_claw_position.calibration),
+        back_(start_position, initial_claw_position.back) {}
+
+  bool GetPositionOfEdge(const control_loops::HalfClawPosition &claw_position,
+                         Claws::Claw *claw) {
+
+    bool print = false;
+    if (front_.DoGetPositionOfEdge(claw_position,
+                                   claw_position.front, &claw->front)) {
+      print = true;
+    } else if (calibration_.DoGetPositionOfEdge(claw_position,
+                                                claw_position.calibration,
+                                                &claw->calibration)) {
+      print = true;
+    } else if (back_.DoGetPositionOfEdge(claw_position,
+                                         claw_position.back, &claw->back)) {
+      print = true;
+    }
+
+    double position = claw_position.position - start_position_;
+
+    if (position > claw->upper_limit) {
+      claw->upper_hard_limit = claw->upper_limit = position;
+      print = true;
+    }
+    if (position < claw->lower_limit) {
+      claw->lower_hard_limit = claw->lower_limit = position;
+      print = true;
+    }
+    return print;
+  }
+
+ private:
+  const double start_position_;
+  Sensor front_;
+  Sensor calibration_;
+  Sensor back_;
+};
+
+int Main() {
+  control_loops::claw_queue_group.position.FetchNextBlocking();
+
+  const double top_start_position =
+      control_loops::claw_queue_group.position->top.position;
+  const double bottom_start_position =
+      control_loops::claw_queue_group.position->bottom.position;
+
+  ClawSensors top(top_start_position,
+                  control_loops::claw_queue_group.position->top);
+  ClawSensors bottom(bottom_start_position,
+                     control_loops::claw_queue_group.position->bottom);
+
+  Claws limits;
+
+  limits.claw_zeroing_off_speed = 0.5;
+  limits.claw_zeroing_speed = 0.1;
+  limits.claw_zeroing_separation = 0.1;
+
+  // claw separation that would be considered a collision
+  limits.claw_min_separation = 0.0;
+  limits.claw_max_separation = 0.0;
+
+  // We should never get closer/farther than these.
+  limits.soft_min_separation = 0.0;
+  limits.soft_max_separation = 0.0;
+
+  limits.upper_claw.lower_hard_limit = 0.0;
+  limits.upper_claw.upper_hard_limit = 0.0;
+  limits.upper_claw.lower_limit = 0.0;
+  limits.upper_claw.upper_limit = 0.0;
+  limits.upper_claw.front.lower_angle = 0.0;
+  limits.upper_claw.front.upper_angle = 0.0;
+  limits.upper_claw.front.lower_decreasing_angle = 0.0;
+  limits.upper_claw.front.upper_decreasing_angle = 0.0;
+  limits.upper_claw.calibration.lower_angle = 0.0;
+  limits.upper_claw.calibration.upper_angle = 0.0;
+  limits.upper_claw.calibration.lower_decreasing_angle = 0.0;
+  limits.upper_claw.calibration.upper_decreasing_angle = 0.0;
+  limits.upper_claw.back.lower_angle = 0.0;
+  limits.upper_claw.back.upper_angle = 0.0;
+  limits.upper_claw.back.lower_decreasing_angle = 0.0;
+  limits.upper_claw.back.upper_decreasing_angle = 0.0;
+
+  limits.lower_claw.lower_hard_limit = 0.0;
+  limits.lower_claw.upper_hard_limit = 0.0;
+  limits.lower_claw.lower_limit = 0.0;
+  limits.lower_claw.upper_limit = 0.0;
+  limits.lower_claw.front.lower_angle = 0.0;
+  limits.lower_claw.front.upper_angle = 0.0;
+  limits.lower_claw.front.lower_decreasing_angle = 0.0;
+  limits.lower_claw.front.upper_decreasing_angle = 0.0;
+  limits.lower_claw.calibration.lower_angle = 0.0;
+  limits.lower_claw.calibration.upper_angle = 0.0;
+  limits.lower_claw.calibration.lower_decreasing_angle = 0.0;
+  limits.lower_claw.calibration.upper_decreasing_angle = 0.0;
+  limits.lower_claw.back.lower_angle = 0.0;
+  limits.lower_claw.back.upper_angle = 0.0;
+  limits.lower_claw.back.lower_decreasing_angle = 0.0;
+  limits.lower_claw.back.upper_decreasing_angle = 0.0;
+
+  limits.claw_unimportant_epsilon = 0.01;
+  limits.start_fine_tune_pos = -0.2;
+  limits.max_zeroing_voltage = 4.0;
+
+  control_loops::ClawGroup::Position last_position =
+      *control_loops::claw_queue_group.position;
+
+  while (true) {
+    control_loops::claw_queue_group.position.FetchNextBlocking();
+    bool print = false;
+    if (top.GetPositionOfEdge(control_loops::claw_queue_group.position->top,
+                              &limits.upper_claw)) {
+      print = true;
+      printf("Got an edge on the upper claw\n");
+    }
+    if (bottom.GetPositionOfEdge(
+            control_loops::claw_queue_group.position->bottom,
+            &limits.lower_claw)) {
+      print = true;
+      printf("Got an edge on the lower claw\n");
+    }
+    const double top_position =
+        control_loops::claw_queue_group.position->top.position -
+        top_start_position;
+    const double bottom_position =
+        control_loops::claw_queue_group.position->bottom.position -
+        bottom_start_position;
+    const double separation = top_position - bottom_position;
+    if (separation > limits.claw_max_separation) {
+      limits.soft_max_separation = limits.claw_max_separation = separation;
+      print = true;
+    }
+    if (separation < limits.claw_min_separation) {
+      limits.soft_min_separation = limits.claw_min_separation = separation;
+      print = true;
+    }
+
+    if (print) {
+      printf("{%f,\n", limits.claw_zeroing_off_speed);
+      printf("%f,\n", limits.claw_zeroing_speed);
+      printf("%f,\n", limits.claw_zeroing_separation);
+      printf("%f,\n", limits.claw_min_separation);
+      printf("%f,\n", limits.claw_max_separation);
+      printf("%f,\n", limits.soft_min_separation);
+      printf("%f,\n", limits.soft_max_separation);
+      printf(
+          "{%f, %f, %f, %f, {%f, %f, %f, %f}, {%f, %f, %f, %f}, {%f, %f, %f, "
+          "%f}},\n",
+          limits.upper_claw.lower_hard_limit,
+          limits.upper_claw.upper_hard_limit, limits.upper_claw.lower_limit,
+          limits.upper_claw.upper_limit, limits.upper_claw.front.lower_angle,
+          limits.upper_claw.front.upper_angle,
+          limits.upper_claw.front.lower_decreasing_angle,
+          limits.upper_claw.front.upper_decreasing_angle,
+          limits.upper_claw.calibration.lower_angle,
+          limits.upper_claw.calibration.upper_angle,
+          limits.upper_claw.calibration.lower_decreasing_angle,
+          limits.upper_claw.calibration.upper_decreasing_angle,
+          limits.upper_claw.back.lower_angle,
+          limits.upper_claw.back.upper_angle,
+          limits.upper_claw.back.lower_decreasing_angle,
+          limits.upper_claw.back.upper_decreasing_angle);
+
+      printf(
+          "{%f, %f, %f, %f, {%f, %f, %f, %f}, {%f, %f, %f, %f}, {%f, %f, %f, "
+          "%f}},\n",
+          limits.lower_claw.lower_hard_limit,
+          limits.lower_claw.upper_hard_limit, limits.lower_claw.lower_limit,
+          limits.lower_claw.upper_limit, limits.lower_claw.front.lower_angle,
+          limits.lower_claw.front.upper_angle,
+          limits.lower_claw.front.lower_decreasing_angle,
+          limits.lower_claw.front.upper_decreasing_angle,
+          limits.lower_claw.calibration.lower_angle,
+          limits.lower_claw.calibration.upper_angle,
+          limits.lower_claw.calibration.lower_decreasing_angle,
+          limits.lower_claw.calibration.upper_decreasing_angle,
+          limits.lower_claw.back.lower_angle,
+          limits.lower_claw.back.upper_angle,
+          limits.lower_claw.back.lower_decreasing_angle,
+          limits.lower_claw.back.upper_decreasing_angle);
+      printf("%f,  // claw_unimportant_epsilon\n",
+             limits.claw_unimportant_epsilon);
+      printf("%f,   // start_fine_tune_pos\n", limits.start_fine_tune_pos);
+      printf("%f,\n", limits.max_zeroing_voltage);
+      printf("}\n");
+    }
+
+    last_position = *control_loops::claw_queue_group.position;
+  }
+  return 0;
+}
+
+}  // namespace frc971
+
+int main() {
+  ::aos::Init();
+  int returnvalue = ::frc971::Main();
+  ::aos::Cleanup();
+  return returnvalue;
+}
diff --git a/y2014/control_loops/claw/claw_lib_test.cc b/y2014/control_loops/claw/claw_lib_test.cc
new file mode 100644
index 0000000..b98a1bb
--- /dev/null
+++ b/y2014/control_loops/claw/claw_lib_test.cc
@@ -0,0 +1,634 @@
+#include <unistd.h>
+
+#include <memory>
+
+#include "aos/common/network/team_number.h"
+#include "aos/common/controls/control_loop_test.h"
+
+#include "y2014/control_loops/claw/claw.q.h"
+#include "y2014/control_loops/claw/claw.h"
+#include "y2014/constants.h"
+#include "y2014/control_loops/claw/claw_motor_plant.h"
+
+#include "gtest/gtest.h"
+
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+
+typedef enum {
+	TOP_CLAW = 0,
+	BOTTOM_CLAW,
+
+	CLAW_COUNT
+} ClawType;
+
+class TeamNumberEnvironment : public ::testing::Environment {
+ public:
+  // Override this to define how to set up the environment.
+  virtual void SetUp() { aos::network::OverrideTeamNumber(1); }
+};
+
+::testing::Environment* const team_number_env =
+    ::testing::AddGlobalTestEnvironment(new TeamNumberEnvironment);
+
+// Class which simulates the wrist and sends out queue messages containing the
+// position.
+class ClawMotorSimulation {
+ public:
+  // Constructs a motor simulation.  initial_position is the inital angle of the
+  // wrist, which will be treated as 0 by the encoder.
+  ClawMotorSimulation(double initial_top_position,
+                      double initial_bottom_position)
+      : claw_plant_(new StateFeedbackPlant<4, 2, 2>(MakeClawPlant())),
+        claw_queue_group(".frc971.control_loops.claw_queue_group", 0x9f1a99dd,
+                         ".frc971.control_loops.claw_queue_group.goal",
+                         ".frc971.control_loops.claw_queue_group.position",
+                         ".frc971.control_loops.claw_queue_group.output",
+                         ".frc971.control_loops.claw_queue_group.status") {
+    Reinitialize(initial_top_position, initial_bottom_position);
+  }
+
+  void Reinitialize(double initial_top_position,
+                    double initial_bottom_position) {
+    LOG(INFO, "Reinitializing to {top: %f, bottom: %f}\n", initial_top_position,
+        initial_bottom_position);
+    claw_plant_->mutable_X(0, 0) = initial_bottom_position;
+    claw_plant_->mutable_X(1, 0) = initial_top_position - initial_bottom_position;
+    claw_plant_->mutable_X(2, 0) = 0.0;
+    claw_plant_->mutable_X(3, 0) = 0.0;
+    claw_plant_->mutable_Y() = claw_plant_->C() * claw_plant_->X();
+
+    ReinitializePartial(TOP_CLAW, initial_top_position);
+    ReinitializePartial(BOTTOM_CLAW, initial_bottom_position);
+    last_position_.Zero();
+    SetPhysicalSensors(&last_position_);
+  }
+
+  // Returns the absolute angle of the wrist.
+  double GetAbsolutePosition(ClawType type) const {
+    if (type == TOP_CLAW) {
+      return claw_plant_->Y(1, 0);
+    } else {
+      return claw_plant_->Y(0, 0);
+    }
+  }
+
+  // Returns the adjusted angle of the wrist.
+  double GetPosition(ClawType type) const {
+    return GetAbsolutePosition(type) - initial_position_[type];
+  }
+
+  // Makes sure pos is inside range (exclusive)
+  bool CheckRange(double pos, const constants::Values::Claws::AnglePair &pair) {
+    // Note: If the >= and <= signs are used, then the there exists a case
+    // where the wrist starts precisely on the edge and because initial
+    // position and the *edge_value_ are the same, then the comparison
+    // in ZeroedStateFeedbackLoop::DoGetPositionOfEdge will return that
+    // the lower, rather than upper, edge of the hall effect was passed.
+    return (pos > pair.lower_angle && pos < pair.upper_angle);
+  }
+
+  void SetHallEffect(double pos,
+                     const constants::Values::Claws::AnglePair &pair,
+                     HallEffectStruct *hall_effect) {
+    hall_effect->current = CheckRange(pos, pair);
+  }
+
+  void SetClawHallEffects(double pos,
+                          const constants::Values::Claws::Claw &claw,
+                          control_loops::HalfClawPosition *half_claw) {
+    SetHallEffect(pos, claw.front, &half_claw->front);
+    SetHallEffect(pos, claw.calibration, &half_claw->calibration);
+    SetHallEffect(pos, claw.back, &half_claw->back);
+  }
+
+  // Sets the values of the physical sensors that can be directly observed
+  // (encoder, hall effect).
+  void SetPhysicalSensors(control_loops::ClawGroup::Position *position) {
+    position->top.position = GetPosition(TOP_CLAW);
+    position->bottom.position = GetPosition(BOTTOM_CLAW);
+
+    double pos[2] = {GetAbsolutePosition(TOP_CLAW),
+                     GetAbsolutePosition(BOTTOM_CLAW)};
+    LOG(DEBUG, "Physical claws are at {top: %f, bottom: %f}\n", pos[TOP_CLAW],
+        pos[BOTTOM_CLAW]);
+
+    const frc971::constants::Values& values = constants::GetValues();
+
+    // Signal that each hall effect sensor has been triggered if it is within
+    // the correct range.
+    SetClawHallEffects(pos[TOP_CLAW], values.claw.upper_claw, &position->top);
+    SetClawHallEffects(pos[BOTTOM_CLAW], values.claw.lower_claw,
+                       &position->bottom);
+  }
+
+  void UpdateHallEffect(double angle,
+                        double last_angle,
+                        double initial_position,
+                        double *posedge_value,
+                        double *negedge_value,
+                        HallEffectStruct *position,
+                        const HallEffectStruct &last_position,
+                        const constants::Values::Claws::AnglePair &pair,
+                        const char *claw_name, const char *hall_effect_name) {
+    if (position->current && !last_position.current) {
+      ++position->posedge_count;
+
+      if (last_angle < pair.lower_angle) {
+        LOG(DEBUG, "%s: Positive lower edge on %s hall effect\n", claw_name,
+            hall_effect_name);
+        *posedge_value = pair.lower_angle - initial_position;
+      } else {
+        LOG(DEBUG, "%s: Positive upper edge on %s hall effect\n", claw_name,
+            hall_effect_name);
+        *posedge_value = pair.upper_angle - initial_position;
+      }
+    }
+    if (!position->current && last_position.current) {
+      ++position->negedge_count;
+
+      if (angle < pair.lower_angle) {
+        LOG(DEBUG, "%s: Negative lower edge on %s hall effect\n", claw_name,
+            hall_effect_name);
+        *negedge_value = pair.lower_angle - initial_position;
+      } else {
+        LOG(DEBUG, "%s: Negative upper edge on %s hall effect\n", claw_name,
+            hall_effect_name);
+        *negedge_value = pair.upper_angle - initial_position;
+      }
+    }
+  }
+
+  void UpdateClawHallEffects(
+      control_loops::HalfClawPosition *position,
+      const control_loops::HalfClawPosition &last_position,
+      const constants::Values::Claws::Claw &claw, double initial_position,
+      const char *claw_name) {
+    UpdateHallEffect(position->position + initial_position,
+                     last_position.position + initial_position,
+                     initial_position, &position->posedge_value,
+                     &position->negedge_value, &position->front,
+                     last_position.front, claw.front, claw_name, "front");
+    UpdateHallEffect(position->position + initial_position,
+                     last_position.position + initial_position,
+                     initial_position, &position->posedge_value,
+                     &position->negedge_value, &position->calibration,
+                     last_position.calibration, claw.calibration, claw_name,
+                     "calibration");
+    UpdateHallEffect(position->position + initial_position,
+                     last_position.position + initial_position,
+                     initial_position, &position->posedge_value,
+                     &position->negedge_value, &position->back,
+                     last_position.back, claw.back, claw_name, "back");
+  }
+
+  // Sends out the position queue messages.
+  void SendPositionMessage() {
+    ::aos::ScopedMessagePtr<control_loops::ClawGroup::Position> position =
+        claw_queue_group.position.MakeMessage();
+
+    // Initialize all the counters to their previous values.
+    *position = last_position_;
+
+    SetPhysicalSensors(position.get());
+
+    const frc971::constants::Values& values = constants::GetValues();
+
+    UpdateClawHallEffects(&position->top, last_position_.top,
+                          values.claw.upper_claw, initial_position_[TOP_CLAW],
+                          "Top");
+    UpdateClawHallEffects(&position->bottom, last_position_.bottom,
+                          values.claw.lower_claw,
+                          initial_position_[BOTTOM_CLAW], "Bottom");
+
+    // Only set calibration if it changed last cycle.  Calibration starts out
+    // with a value of 0.
+    last_position_ = *position;
+    position.Send();
+  }
+
+  // Simulates the claw moving for one timestep.
+  void Simulate() {
+    const frc971::constants::Values& v = constants::GetValues();
+    EXPECT_TRUE(claw_queue_group.output.FetchLatest());
+
+    claw_plant_->mutable_U() << claw_queue_group.output->bottom_claw_voltage,
+        claw_queue_group.output->top_claw_voltage;
+    claw_plant_->Update();
+
+    // Check that the claw is within the limits.
+    EXPECT_GE(v.claw.upper_claw.upper_limit, claw_plant_->Y(0, 0));
+    EXPECT_LE(v.claw.upper_claw.lower_hard_limit, claw_plant_->Y(0, 0));
+
+    EXPECT_GE(v.claw.lower_claw.upper_hard_limit, claw_plant_->Y(1, 0));
+    EXPECT_LE(v.claw.lower_claw.lower_hard_limit, claw_plant_->Y(1, 0));
+
+    EXPECT_LE(claw_plant_->Y(1, 0) - claw_plant_->Y(0, 0),
+              v.claw.claw_max_separation);
+    EXPECT_GE(claw_plant_->Y(1, 0) - claw_plant_->Y(0, 0),
+              v.claw.claw_min_separation);
+  }
+  // The whole claw.
+  ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> claw_plant_;
+
+ private:
+  // Resets the plant so that it starts at initial_position.
+  void ReinitializePartial(ClawType type, double initial_position) {
+    initial_position_[type] = initial_position;
+  }
+
+  ClawGroup claw_queue_group;
+  double initial_position_[CLAW_COUNT];
+
+  control_loops::ClawGroup::Position last_position_;
+};
+
+
+class ClawTest : public ::aos::testing::ControlLoopTest {
+ protected:
+  // Create a new instance of the test queue so that it invalidates the queue
+  // that it points to.  Otherwise, we will have a pointer to shared memory that
+  // is no longer valid.
+  ClawGroup claw_queue_group;
+
+  // Create a loop and simulation plant.
+  ClawMotor claw_motor_;
+  ClawMotorSimulation claw_motor_plant_;
+
+  // Minimum amount of acceptable separation between the top and bottom of the
+  // claw.
+  double min_separation_;
+
+  ClawTest()
+      : claw_queue_group(".frc971.control_loops.claw_queue_group", 0x9f1a99dd,
+                         ".frc971.control_loops.claw_queue_group.goal",
+                         ".frc971.control_loops.claw_queue_group.position",
+                         ".frc971.control_loops.claw_queue_group.output",
+                         ".frc971.control_loops.claw_queue_group.status"),
+        claw_motor_(&claw_queue_group),
+        claw_motor_plant_(0.4, 0.2),
+        min_separation_(constants::GetValues().claw.claw_min_separation) {
+  }
+
+  void VerifyNearGoal() {
+    claw_queue_group.goal.FetchLatest();
+    claw_queue_group.position.FetchLatest();
+    double bottom = claw_motor_plant_.GetAbsolutePosition(BOTTOM_CLAW);
+    double separation =
+        claw_motor_plant_.GetAbsolutePosition(TOP_CLAW) - bottom;
+    EXPECT_NEAR(claw_queue_group.goal->bottom_angle, bottom, 1e-4);
+    EXPECT_NEAR(claw_queue_group.goal->separation_angle, separation, 1e-4);
+    EXPECT_LE(min_separation_, separation);
+  }
+};
+
+TEST_F(ClawTest, HandlesNAN) {
+  claw_queue_group.goal.MakeWithBuilder()
+      .bottom_angle(::std::nan(""))
+      .separation_angle(::std::nan(""))
+      .Send();
+  for (int i = 0; i < 500; ++i) {
+    claw_motor_plant_.SendPositionMessage();
+    claw_motor_.Iterate();
+    claw_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+}
+
+// Tests that the wrist zeros correctly and goes to a position.
+TEST_F(ClawTest, ZerosCorrectly) {
+  claw_queue_group.goal.MakeWithBuilder()
+      .bottom_angle(0.1)
+      .separation_angle(0.2)
+      .Send();
+  for (int i = 0; i < 500; ++i) {
+    claw_motor_plant_.SendPositionMessage();
+    claw_motor_.Iterate();
+    claw_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  VerifyNearGoal();
+}
+
+// Tests that the wrist zeros correctly and goes to a position.
+TEST_F(ClawTest, LimitClawGoal) {
+  frc971::constants::Values values;
+  values.claw.claw_min_separation = -2.0;
+  values.claw.claw_max_separation = 1.0;
+  values.claw.soft_min_separation = -2.0;
+  values.claw.soft_max_separation = 1.0;
+  values.claw.upper_claw.lower_limit = -5.0;
+  values.claw.upper_claw.upper_limit = 7.5;
+  values.claw.lower_claw.lower_limit = -5.5;
+  values.claw.lower_claw.upper_limit = 8.0;
+
+  double bottom_goal = 0.0;
+  double top_goal = 0.0;
+
+  LimitClawGoal(&bottom_goal, &top_goal, values);
+  EXPECT_NEAR(0.0, bottom_goal, 1e-4);
+  EXPECT_NEAR(0.0, top_goal, 1e-4);
+
+  bottom_goal = 0.0;
+  top_goal = -4.0;
+
+  LimitClawGoal(&bottom_goal, &top_goal, values);
+  EXPECT_NEAR(-1.0, bottom_goal, 1e-4);
+  EXPECT_NEAR(-3.0, top_goal, 1e-4);
+
+  bottom_goal = 0.0;
+  top_goal = 4.0;
+
+  LimitClawGoal(&bottom_goal, &top_goal, values);
+  EXPECT_NEAR(1.5, bottom_goal, 1e-4);
+  EXPECT_NEAR(2.5, top_goal, 1e-4);
+
+  bottom_goal = -10.0;
+  top_goal = -9.5;
+
+  LimitClawGoal(&bottom_goal, &top_goal, values);
+  EXPECT_NEAR(-5.5, bottom_goal, 1e-4);
+  EXPECT_NEAR(-5.0, top_goal, 1e-4);
+
+  bottom_goal = -20.0;
+  top_goal = -4.0;
+
+  LimitClawGoal(&bottom_goal, &top_goal, values);
+  EXPECT_NEAR(-5.5, bottom_goal, 1e-4);
+  EXPECT_NEAR(-4.5, top_goal, 1e-4);
+
+  bottom_goal = -20.0;
+  top_goal = -4.0;
+
+  LimitClawGoal(&bottom_goal, &top_goal, values);
+  EXPECT_NEAR(-5.5, bottom_goal, 1e-4);
+  EXPECT_NEAR(-4.5, top_goal, 1e-4);
+
+  bottom_goal = -5.0;
+  top_goal = -10.0;
+
+  LimitClawGoal(&bottom_goal, &top_goal, values);
+  EXPECT_NEAR(-3.0, bottom_goal, 1e-4);
+  EXPECT_NEAR(-5.0, top_goal, 1e-4);
+
+  bottom_goal = 10.0;
+  top_goal = 9.0;
+
+  LimitClawGoal(&bottom_goal, &top_goal, values);
+  EXPECT_NEAR(8.0, bottom_goal, 1e-4);
+  EXPECT_NEAR(7.0, top_goal, 1e-4);
+
+  bottom_goal = 8.0;
+  top_goal = 9.0;
+
+  LimitClawGoal(&bottom_goal, &top_goal, values);
+  EXPECT_NEAR(6.5, bottom_goal, 1e-4);
+  EXPECT_NEAR(7.5, top_goal, 1e-4);
+}
+
+
+class ZeroingClawTest
+    : public ClawTest,
+      public ::testing::WithParamInterface< ::std::pair<double, double>> {};
+
+// Tests that the wrist zeros correctly starting on the hall effect sensor.
+TEST_P(ZeroingClawTest, ParameterizedZero) {
+  claw_motor_plant_.Reinitialize(GetParam().first, GetParam().second);
+
+  claw_queue_group.goal.MakeWithBuilder()
+      .bottom_angle(0.1)
+      .separation_angle(0.2)
+      .Send();
+  for (int i = 0; i < 700; ++i) {
+    claw_motor_plant_.SendPositionMessage();
+    claw_motor_.Iterate();
+    claw_motor_plant_.Simulate();
+
+    SimulateTimestep(true);
+  }
+  VerifyNearGoal();
+}
+
+// Tests that missing positions are correctly handled.
+TEST_P(ZeroingClawTest, HandleMissingPosition) {
+  claw_motor_plant_.Reinitialize(GetParam().first, GetParam().second);
+
+  claw_queue_group.goal.MakeWithBuilder()
+      .bottom_angle(0.1)
+      .separation_angle(0.2)
+      .Send();
+  for (int i = 0; i < 700; ++i) {
+    if (i % 23) {
+      claw_motor_plant_.SendPositionMessage();
+    }
+    claw_motor_.Iterate();
+    claw_motor_plant_.Simulate();
+
+    SimulateTimestep(true);
+  }
+  VerifyNearGoal();
+}
+
+INSTANTIATE_TEST_CASE_P(ZeroingClawTest, ZeroingClawTest,
+                        ::testing::Values(::std::make_pair(0.04, 0.02),
+                                          ::std::make_pair(0.2, 0.1),
+                                          ::std::make_pair(0.3, 0.2),
+                                          ::std::make_pair(0.4, 0.3),
+                                          ::std::make_pair(0.5, 0.4),
+                                          ::std::make_pair(0.6, 0.5),
+                                          ::std::make_pair(0.7, 0.6),
+                                          ::std::make_pair(0.8, 0.7),
+                                          ::std::make_pair(0.9, 0.8),
+                                          ::std::make_pair(1.0, 0.9),
+                                          ::std::make_pair(1.1, 1.0),
+                                          ::std::make_pair(1.15, 1.05),
+                                          ::std::make_pair(1.05, 0.95),
+                                          ::std::make_pair(1.2, 1.1),
+                                          ::std::make_pair(1.3, 1.2),
+                                          ::std::make_pair(1.4, 1.3),
+                                          ::std::make_pair(1.5, 1.4),
+                                          ::std::make_pair(1.6, 1.5),
+                                          ::std::make_pair(1.7, 1.6),
+                                          ::std::make_pair(1.8, 1.7),
+                                          ::std::make_pair(2.015, 2.01)
+));
+
+/*
+// Tests that loosing the encoder for a second triggers a re-zero.
+TEST_F(ClawTest, RezeroWithMissingPos) {
+  claw_queue_group.goal.MakeWithBuilder()
+      .bottom_angle(0.1)
+      .separation_angle(0.2)
+      .Send();
+  for (int i = 0; i < 800; ++i) {
+    // After 3 seconds, simulate the encoder going missing.
+    // This should trigger a re-zero.  To make sure it works, change the goal as
+    // well.
+    if (i < 300 || i > 400) {
+      claw_motor_plant_.SendPositionMessage();
+    } else {
+      if (i > 310) {
+        // Should be re-zeroing now.
+        EXPECT_TRUE(claw_motor_.is_uninitialized());
+      }
+      claw_queue_group.goal.MakeWithBuilder()
+          .bottom_angle(0.2)
+          .separation_angle(0.2)
+          .Send();
+    }
+    if (i == 410) {
+      EXPECT_TRUE(claw_motor_.is_zeroing());
+      // TODO(austin): Expose if the top and bototm is zeroing through
+      // functions.
+      // EXPECT_TRUE(bottom_claw_motor_.is_zeroing());
+    }
+
+    claw_motor_.Iterate();
+    claw_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  VerifyNearGoal();
+}
+
+// Tests that disabling while zeroing sends the state machine into the
+// uninitialized state.
+TEST_F(ClawTest, DisableGoesUninitialized) {
+  claw_queue_group.goal.MakeWithBuilder()
+      .bottom_angle(0.1)
+      .separation_angle(0.2)
+      .Send();
+  for (int i = 0; i < 800; ++i) {
+    claw_motor_plant_.SendPositionMessage();
+    // After 0.5 seconds, disable the robot.
+    if (i > 50 && i < 200) {
+      SimulateTimestep(false);
+      if (i > 100) {
+        // Give the loop a couple cycled to get the message and then verify that
+        // it is in the correct state.
+        EXPECT_TRUE(claw_motor_.is_uninitialized());
+        // When disabled, we should be applying 0 power.
+        EXPECT_TRUE(claw_queue_group.output.FetchLatest());
+        EXPECT_EQ(0, claw_queue_group.output->top_claw_voltage);
+        EXPECT_EQ(0, claw_queue_group.output->bottom_claw_voltage);
+      }
+    } else {
+      SimulateTimestep(true);
+    }
+    if (i == 202) {
+      // Verify that we are zeroing after the bot gets enabled again.
+      EXPECT_TRUE(wrist_motor_.is_zeroing());
+      // TODO(austin): Expose if the top and bottom is zeroing through
+      // functions.
+    }
+
+    claw_motor_.Iterate();
+    claw_motor_plant_.Simulate();
+  }
+  VerifyNearGoal();
+}
+*/
+
+class WindupClawTest : public ClawTest {
+ protected:
+  void TestWindup(ClawMotor::CalibrationMode mode, int start_time, double offset) {
+    int capped_count = 0;
+    const frc971::constants::Values& values = constants::GetValues();
+    bool kicked = false;
+    bool measured = false;
+    for (int i = 0; i < 700; ++i) {
+      claw_motor_plant_.SendPositionMessage();
+      if (i >= start_time && mode == claw_motor_.mode() && !kicked) {
+        EXPECT_EQ(mode, claw_motor_.mode());
+        // Move the zeroing position far away and verify that it gets moved
+        // back.
+        claw_motor_.top_claw_goal_ += offset;
+        claw_motor_.bottom_claw_goal_ += offset;
+        kicked = true;
+      } else {
+        if (kicked && !measured) {
+          measured = true;
+          EXPECT_EQ(mode, claw_motor_.mode());
+
+          Eigen::Matrix<double, 4, 1> R;
+          R << claw_motor_.bottom_claw_goal_,
+              claw_motor_.top_claw_goal_ - claw_motor_.bottom_claw_goal_, 0.0,
+              0.0;
+          Eigen::Matrix<double, 2, 1> uncapped_voltage =
+              claw_motor_.claw_.K() * (R - claw_motor_.claw_.X_hat());
+          // Use a factor of 1.8 because so long as it isn't actually running
+          // away, the CapU function will deal with getting the actual output
+          // down.
+          EXPECT_LT(::std::abs(uncapped_voltage(0, 0)),
+                    values.claw.max_zeroing_voltage * 1.8);
+          EXPECT_LT(::std::abs(uncapped_voltage(1, 0)),
+                    values.claw.max_zeroing_voltage * 1.8);
+        }
+      }
+      if (claw_motor_.mode() == mode) {
+        if (claw_motor_.capped_goal()) {
+          ++capped_count;
+          // The cycle after we kick the zero position is the only cycle during
+          // which we should expect to see a high uncapped power during zeroing.
+          ASSERT_LT(values.claw.max_zeroing_voltage,
+                    ::std::abs(claw_motor_.uncapped_average_voltage()));
+        } else {
+          ASSERT_GT(values.claw.max_zeroing_voltage,
+                    ::std::abs(claw_motor_.uncapped_average_voltage()));
+        }
+      }
+
+      claw_motor_.Iterate();
+      claw_motor_plant_.Simulate();
+      SimulateTimestep(true);
+    }
+    EXPECT_TRUE(kicked);
+    EXPECT_TRUE(measured);
+    EXPECT_LE(1, capped_count);
+    EXPECT_GE(3, capped_count);
+  }
+};
+
+// Tests that the wrist can't get too far away from the zeroing position if the
+// zeroing position is saturating the goal.
+TEST_F(WindupClawTest, NoWindupPositive) {
+  claw_queue_group.goal.MakeWithBuilder()
+      .bottom_angle(0.1)
+      .separation_angle(0.2)
+      .Send();
+
+  TestWindup(ClawMotor::UNKNOWN_LOCATION, 100, 971.0);
+
+  VerifyNearGoal();
+}
+
+// Tests that the wrist can't get too far away from the zeroing position if the
+// zeroing position is saturating the goal.
+TEST_F(WindupClawTest, NoWindupNegative) {
+  claw_queue_group.goal.MakeWithBuilder()
+      .bottom_angle(0.1)
+      .separation_angle(0.2)
+      .Send();
+
+  TestWindup(ClawMotor::UNKNOWN_LOCATION, 100, -971.0);
+
+  VerifyNearGoal();
+}
+
+// Tests that the wrist can't get too far away from the zeroing position if the
+// zeroing position is saturating the goal.
+TEST_F(WindupClawTest, NoWindupNegativeFineTune) {
+  claw_queue_group.goal.MakeWithBuilder()
+      .bottom_angle(0.1)
+      .separation_angle(0.2)
+      .Send();
+
+  TestWindup(ClawMotor::FINE_TUNE_BOTTOM, 200, -971.0);
+
+  VerifyNearGoal();
+}
+
+}  // namespace testing
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/claw/claw_main.cc b/y2014/control_loops/claw/claw_main.cc
new file mode 100644
index 0000000..e573d6f
--- /dev/null
+++ b/y2014/control_loops/claw/claw_main.cc
@@ -0,0 +1,11 @@
+#include "y2014/control_loops/claw/claw.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+  ::aos::Init();
+  frc971::control_loops::ClawMotor claw;
+  claw.Run();
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2014/control_loops/claw/claw_motor_plant.cc b/y2014/control_loops/claw/claw_motor_plant.cc
new file mode 100644
index 0000000..acba8d0
--- /dev/null
+++ b/y2014/control_loops/claw/claw_motor_plant.cc
@@ -0,0 +1,49 @@
+#include "y2014/control_loops/claw/claw_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeClawPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.0, 0.00909331035298, 0.0, 0.0, 1.0, -6.04514323962e-05, 0.00903285892058, 0.0, 0.0, 0.824315642255, 0.0, 0.0, 0.0, -0.0112975266368, 0.813018115618;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 0.000352527133889, 0.0, -0.000352527133889, 0.000376031064118, 0.0683072794628, 0.0, -0.0683072794628, 0.0726998350615;
+  Eigen::Matrix<double, 2, 4> C;
+  C << 1, 0, 0, 0, 1, 1, 0, 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> MakeClawController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.72431564225, 2.70472958703e-16, -1.72431564225, 1.71301811562, 65.9456997026, 1.03478906105e-14, -65.9456997026, 64.4642687194;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 106.138028875, 0.0, 4.20012492658, 0.0, 99.5038407367, 99.7251230882, 3.77683310096, 3.78980738032;
+  Eigen::Matrix<double, 4, 4> A_inv;
+  A_inv << 1.0, 0.0, -0.0110313451387, 0.0, 0.0, 1.0, -7.89348747778e-05, -0.0111102800135, 0.0, 0.0, 1.21312753118, 0.0, 0.0, 0.0, 0.016857361889, 1.22998489307;
+  return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeClawPlantCoefficients());
+}
+
+StateFeedbackPlant<4, 2, 2> MakeClawPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>> plants(1);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeClawPlantCoefficients()));
+  return StateFeedbackPlant<4, 2, 2>(&plants);
+}
+
+StateFeedbackLoop<4, 2, 2> MakeClawLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<4, 2, 2>>> controllers(1);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeClawController()));
+  return StateFeedbackLoop<4, 2, 2>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/claw/claw_motor_plant.h b/y2014/control_loops/claw/claw_motor_plant.h
new file mode 100644
index 0000000..c7de33a
--- /dev/null
+++ b/y2014/control_loops/claw/claw_motor_plant.h
@@ -0,0 +1,22 @@
+#ifndef Y2014_CONTROL_LOOPS_CLAW_CLAW_MOTOR_PLANT_H_
+#define Y2014_CONTROL_LOOPS_CLAW_CLAW_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+static constexpr double kClawMomentOfInertiaRatio = 0.933333;
+
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeClawPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeClawController();
+
+StateFeedbackPlant<4, 2, 2> MakeClawPlant();
+
+StateFeedbackLoop<4, 2, 2> MakeClawLoop();
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // Y2014_CONTROL_LOOPS_CLAW_CLAW_MOTOR_PLANT_H_
diff --git a/y2014/control_loops/claw/replay_claw.cc b/y2014/control_loops/claw/replay_claw.cc
new file mode 100644
index 0000000..70d881c
--- /dev/null
+++ b/y2014/control_loops/claw/replay_claw.cc
@@ -0,0 +1,24 @@
+#include "aos/common/controls/replay_control_loop.h"
+#include "aos/linux_code/init.h"
+
+#include "y2014/control_loops/claw/claw.q.h"
+
+// Reads one or more log files and sends out all the queue messages (in the
+// correct order and at the correct time) to feed a "live" claw process.
+
+int main(int argc, char **argv) {
+  if (argc <= 1) {
+    fprintf(stderr, "Need at least one file to replay!\n");
+    return EXIT_FAILURE;
+  }
+
+  ::aos::InitNRT();
+
+  ::aos::controls::ControlLoopReplayer<::frc971::control_loops::ClawQueue>
+      replayer(&::frc971::control_loops::claw_queue, "claw");
+  for (int i = 1; i < argc; ++i) {
+    replayer.ProcessFile(argv[i]);
+  }
+
+  ::aos::Cleanup();
+}
diff --git a/y2014/control_loops/drivetrain/drivetrain.cc b/y2014/control_loops/drivetrain/drivetrain.cc
new file mode 100644
index 0000000..ecb8ed2
--- /dev/null
+++ b/y2014/control_loops/drivetrain/drivetrain.cc
@@ -0,0 +1,775 @@
+#include "y2014/control_loops/drivetrain/drivetrain.h"
+
+#include <stdio.h>
+#include <sched.h>
+#include <cmath>
+#include <memory>
+#include "Eigen/Dense"
+
+#include "aos/common/logging/logging.h"
+#include "aos/common/controls/polytope.h"
+#include "aos/common/commonmath.h"
+#include "aos/common/logging/queue_logging.h"
+#include "aos/common/logging/matrix_logging.h"
+
+#include "y2014/constants.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/coerce_goal.h"
+#include "y2014/control_loops/drivetrain/polydrivetrain_cim_plant.h"
+#include "y2014/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/queues/gyro.q.h"
+#include "frc971/shifter_hall_effect.h"
+
+// A consistent way to mark code that goes away without shifters. It's still
+// here because we will have shifters again in the future.
+#define HAVE_SHIFTERS 1
+
+using frc971::sensors::gyro_reading;
+
+namespace frc971 {
+namespace control_loops {
+
+class DrivetrainMotorsSS {
+ public:
+  class LimitedDrivetrainLoop : public StateFeedbackLoop<4, 2, 2> {
+   public:
+    LimitedDrivetrainLoop(StateFeedbackLoop<4, 2, 2> &&loop)
+        : StateFeedbackLoop<4, 2, 2>(::std::move(loop)),
+        U_Poly_((Eigen::Matrix<double, 4, 2>() << 1, 0,
+                 -1, 0,
+                 0, 1,
+                 0, -1).finished(),
+                (Eigen::Matrix<double, 4, 1>() << 12.0, 12.0,
+                 12.0, 12.0).finished()) {
+      ::aos::controls::HPolytope<0>::Init();
+      T << 1, -1, 1, 1;
+      T_inverse = T.inverse();
+    }
+
+    bool output_was_capped() const {
+      return output_was_capped_;
+    }
+
+   private:
+    virtual void CapU() {
+      const Eigen::Matrix<double, 4, 1> error = R() - X_hat();
+
+      if (::std::abs(U(0, 0)) > 12.0 || ::std::abs(U(1, 0)) > 12.0) {
+        mutable_U() =
+            U() * 12.0 / ::std::max(::std::abs(U(0, 0)), ::std::abs(U(1, 0)));
+        LOG_MATRIX(DEBUG, "U is now", U());
+        // TODO(Austin): Figure out why the polytope stuff wasn't working and
+        // remove this hack.
+        output_was_capped_ = true;
+        return;
+
+        LOG_MATRIX(DEBUG, "U at start", U());
+        LOG_MATRIX(DEBUG, "R at start", R());
+        LOG_MATRIX(DEBUG, "Xhat at start", X_hat());
+
+        Eigen::Matrix<double, 2, 2> position_K;
+        position_K << K(0, 0), K(0, 2),
+                   K(1, 0), K(1, 2);
+        Eigen::Matrix<double, 2, 2> velocity_K;
+        velocity_K << K(0, 1), K(0, 3),
+                   K(1, 1), K(1, 3);
+
+        Eigen::Matrix<double, 2, 1> position_error;
+        position_error << error(0, 0), error(2, 0);
+        const auto drive_error = T_inverse * position_error;
+        Eigen::Matrix<double, 2, 1> velocity_error;
+        velocity_error << error(1, 0), error(3, 0);
+        LOG_MATRIX(DEBUG, "error", error);
+
+        const auto &poly = U_Poly_;
+        const Eigen::Matrix<double, 4, 2> pos_poly_H =
+            poly.H() * position_K * T;
+        const Eigen::Matrix<double, 4, 1> pos_poly_k =
+            poly.k() - poly.H() * velocity_K * velocity_error;
+        const ::aos::controls::HPolytope<2> pos_poly(pos_poly_H, pos_poly_k);
+
+        Eigen::Matrix<double, 2, 1> adjusted_pos_error;
+        {
+          const auto &P = drive_error;
+
+          Eigen::Matrix<double, 1, 2> L45;
+          L45 << ::aos::sign(P(1, 0)), -::aos::sign(P(0, 0));
+          const double w45 = 0;
+
+          Eigen::Matrix<double, 1, 2> LH;
+          if (::std::abs(P(0, 0)) > ::std::abs(P(1, 0))) {
+            LH << 0, 1;
+          } else {
+            LH << 1, 0;
+          }
+          const double wh = LH.dot(P);
+
+          Eigen::Matrix<double, 2, 2> standard;
+          standard << L45, LH;
+          Eigen::Matrix<double, 2, 1> W;
+          W << w45, wh;
+          const Eigen::Matrix<double, 2, 1> intersection =
+              standard.inverse() * W;
+
+          bool is_inside_h;
+          const auto adjusted_pos_error_h =
+              DoCoerceGoal(pos_poly, LH, wh, drive_error, &is_inside_h);
+          const auto adjusted_pos_error_45 =
+              DoCoerceGoal(pos_poly, L45, w45, intersection, nullptr);
+          if (pos_poly.IsInside(intersection)) {
+            adjusted_pos_error = adjusted_pos_error_h;
+          } else {
+            if (is_inside_h) {
+              if (adjusted_pos_error_h.norm() > adjusted_pos_error_45.norm()) {
+                adjusted_pos_error = adjusted_pos_error_h;
+              } else {
+                adjusted_pos_error = adjusted_pos_error_45;
+              }
+            } else {
+              adjusted_pos_error = adjusted_pos_error_45;
+            }
+          }
+        }
+
+        LOG_MATRIX(DEBUG, "adjusted_pos_error", adjusted_pos_error);
+        mutable_U() =
+            velocity_K * velocity_error + position_K * T * adjusted_pos_error;
+        LOG_MATRIX(DEBUG, "U is now", U());
+      } else {
+        output_was_capped_ = false;
+      }
+    }
+
+    const ::aos::controls::HPolytope<2> U_Poly_;
+    Eigen::Matrix<double, 2, 2> T, T_inverse;
+    bool output_was_capped_ = false;;
+  };
+
+  DrivetrainMotorsSS()
+      : loop_(new LimitedDrivetrainLoop(
+            constants::GetValues().make_drivetrain_loop())),
+        filtered_offset_(0.0),
+        gyro_(0.0),
+        left_goal_(0.0),
+        right_goal_(0.0),
+        raw_left_(0.0),
+        raw_right_(0.0) {
+    // Low gear on both.
+    loop_->set_controller_index(0);
+  }
+
+  void SetGoal(double left, double left_velocity, double right,
+               double right_velocity) {
+    left_goal_ = left;
+    right_goal_ = right;
+    loop_->mutable_R() << left, left_velocity, right, right_velocity;
+  }
+  void SetRawPosition(double left, double right) {
+    raw_right_ = right;
+    raw_left_ = left;
+    Eigen::Matrix<double, 2, 1> Y;
+    Y << left + filtered_offset_, right - filtered_offset_;
+    loop_->Correct(Y);
+  }
+  void SetPosition(double left, double right, double gyro) {
+    // Decay the offset quickly because this gyro is great.
+    const double offset =
+        (right - left - gyro * constants::GetValues().turn_width) / 2.0;
+    filtered_offset_ = 0.25 * offset + 0.75 * filtered_offset_;
+    gyro_ = gyro;
+    SetRawPosition(left, right);
+  }
+
+  void SetExternalMotors(double left_voltage, double right_voltage) {
+    loop_->mutable_U() << left_voltage, right_voltage;
+  }
+
+  void Update(bool stop_motors, bool enable_control_loop) {
+    if (enable_control_loop) {
+      loop_->Update(stop_motors);
+    } else {
+      if (stop_motors) {
+        loop_->mutable_U().setZero();
+        loop_->mutable_U_uncapped().setZero();
+      }
+      loop_->UpdateObserver();
+    }
+    ::Eigen::Matrix<double, 4, 1> E = loop_->R() - loop_->X_hat();
+    LOG_MATRIX(DEBUG, "E", E);
+  }
+
+  double GetEstimatedRobotSpeed() const {
+    // lets just call the average of left and right velocities close enough
+    return (loop_->X_hat(1, 0) + loop_->X_hat(3, 0)) / 2;
+  }
+
+  double GetEstimatedLeftEncoder() const {
+    return loop_->X_hat(0, 0);
+  }
+
+  double GetEstimatedRightEncoder() const {
+    return loop_->X_hat(2, 0);
+  }
+
+  bool OutputWasCapped() const {
+    return loop_->output_was_capped();
+  }
+
+  void SendMotors(DrivetrainQueue::Output *output) const {
+    if (output) {
+      output->left_voltage = loop_->U(0, 0);
+      output->right_voltage = loop_->U(1, 0);
+      output->left_high = false;
+      output->right_high = false;
+    }
+  }
+
+  const LimitedDrivetrainLoop &loop() const { return *loop_; }
+
+ private:
+  ::std::unique_ptr<LimitedDrivetrainLoop> loop_;
+
+  double filtered_offset_;
+  double gyro_;
+  double left_goal_;
+  double right_goal_;
+  double raw_left_;
+  double raw_right_;
+};
+
+class PolyDrivetrain {
+ public:
+
+  enum Gear {
+    HIGH,
+    LOW,
+    SHIFTING_UP,
+    SHIFTING_DOWN
+  };
+  // Stall Torque in N m
+  static constexpr double kStallTorque = 2.42;
+  // Stall Current in Amps
+  static constexpr double kStallCurrent = 133.0;
+  // Free Speed in RPM. Used number from last year.
+  static constexpr double kFreeSpeed = 4650.0;
+  // Free Current in Amps
+  static constexpr double kFreeCurrent = 2.7;
+  // Moment of inertia of the drivetrain in kg m^2
+  // Just borrowed from last year.
+  static constexpr double J = 6.4;
+  // Mass of the robot, in kg.
+  static constexpr double m = 68.0;
+  // 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())),
+        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(const constants::ShifterHallEffect &hall_effect,
+                           double shifter_position, double velocity) {
+    // TODO(austin): G_high, G_low and kWheelRadius
+    const double avg_hall_effect =
+        (hall_effect.clear_high + hall_effect.clear_low) / 2.0;
+
+    if (shifter_position > avg_hall_effect) {
+      return velocity / constants::GetValues().high_gear_ratio / kWheelRadius;
+    } else {
+      return velocity / constants::GetValues().low_gear_ratio / kWheelRadius;
+    }
+  }
+
+  Gear ComputeGear(const constants::ShifterHallEffect &hall_effect,
+                   double velocity, Gear current) {
+    const double low_omega = MotorSpeed(hall_effect, 0.0, ::std::abs(velocity));
+    const double high_omega =
+        MotorSpeed(hall_effect, 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 auto &values = constants::GetValues();
+      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(values.left_drive, current_left_velocity, left_gear_);
+      Gear right_requested =
+          ComputeGear(values.right_drive, 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 DrivetrainQueue::Position *position) {
+    const auto &values = constants::GetValues();
+    if (position == NULL) {
+      ++stale_count_;
+    } else {
+      last_position_ = position_;
+      position_ = *position;
+      position_time_delta_ = (stale_count_ + 1) * 0.01;
+      stale_count_ = 0;
+    }
+
+#if HAVE_SHIFTERS
+    if (position) {
+      GearLogging gear_logging;
+      // Switch to the correct controller.
+      const double left_middle_shifter_position =
+          (values.left_drive.clear_high + values.left_drive.clear_low) / 2.0;
+      const double right_middle_shifter_position =
+          (values.right_drive.clear_high + values.right_drive.clear_low) / 2.0;
+
+      if (position->left_shifter_position < left_middle_shifter_position ||
+          left_gear_ == LOW) {
+        if (position->right_shifter_position < right_middle_shifter_position ||
+            right_gear_ == LOW) {
+          gear_logging.left_loop_high = false;
+          gear_logging.right_loop_high = false;
+          loop_->set_controller_index(gear_logging.controller_index = 0);
+        } else {
+          gear_logging.left_loop_high = false;
+          gear_logging.right_loop_high = true;
+          loop_->set_controller_index(gear_logging.controller_index = 1);
+        }
+      } else {
+        if (position->right_shifter_position < right_middle_shifter_position ||
+            right_gear_ == LOW) {
+          gear_logging.left_loop_high = true;
+          gear_logging.right_loop_high = false;
+          loop_->set_controller_index(gear_logging.controller_index = 2);
+        } else {
+          gear_logging.left_loop_high = true;
+          gear_logging.right_loop_high = true;
+          loop_->set_controller_index(gear_logging.controller_index = 3);
+        }
+      }
+
+      // TODO(austin): Constants.
+      if (position->left_shifter_position > values.left_drive.clear_high && left_gear_ == SHIFTING_UP) {
+        left_gear_ = HIGH;
+      }
+      if (position->left_shifter_position < values.left_drive.clear_low && left_gear_ == SHIFTING_DOWN) {
+        left_gear_ = LOW;
+      }
+      if (position->right_shifter_position > values.right_drive.clear_high && right_gear_ == SHIFTING_UP) {
+        right_gear_ = HIGH;
+      }
+      if (position->right_shifter_position < values.right_drive.clear_low && right_gear_ == SHIFTING_DOWN) {
+        right_gear_ = LOW;
+      }
+
+      gear_logging.left_state = left_gear_;
+      gear_logging.right_state = right_gear_;
+      LOG_STRUCT(DEBUG, "state", gear_logging);
+    }
+#else
+    (void) values;
+#endif
+  }
+
+  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() {
+    const auto &values = constants::GetValues();
+    // TODO(austin): Observer for the current velocity instead of difference
+    // calculations.
+    ++counter_;
+#if HAVE_SHIFTERS
+    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(values.left_drive, position_.left_shifter_position,
+                   current_left_velocity);
+    const double right_motor_speed =
+        MotorSpeed(values.right_drive, position_.right_shifter_position,
+                   current_right_velocity);
+
+    {
+      CIMLogging logging;
+
+      // Reset the CIM model to the current conditions to be ready for when we
+      // shift.
+      if (IsInGear(left_gear_)) {
+        logging.left_in_gear = true;
+      } else {
+        logging.left_in_gear = false;
+      }
+      logging.left_motor_speed = left_motor_speed;
+      logging.left_velocity = current_left_velocity;
+      if (IsInGear(right_gear_)) {
+        logging.right_in_gear = true;
+      } else {
+        logging.right_in_gear = false;
+      }
+      logging.right_motor_speed = right_motor_speed;
+      logging.right_velocity = current_right_velocity;
+
+      LOG_STRUCT(DEBUG, "currently", logging);
+    }
+#else
+    (void) values;
+#endif
+
+#if HAVE_SHIFTERS
+    if (IsInGear(left_gear_) && IsInGear(right_gear_)) {
+#else
+    {
+#endif
+      // 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_->mutable_R() << left_velocity, right_velocity;
+
+      if (!quickturn_) {
+        // K * R = w
+        Eigen::Matrix<double, 1, 2> equality_k;
+        equality_k << 1 + sign_svel, -(1 - sign_svel);
+        const double equality_w = 0.0;
+
+        // Construct a constraint on R by manipulating the constraint on U
+        ::aos::controls::HPolytope<2> R_poly = ::aos::controls::HPolytope<2>(
+            U_Poly_.H() * (loop_->K() + FF),
+            U_Poly_.k() + U_Poly_.H() * loop_->K() * loop_->X_hat());
+
+        // Limit R back inside the box.
+        loop_->mutable_R() =
+            CoerceGoal(R_poly, equality_k, equality_w, loop_->R());
+      }
+
+      const Eigen::Matrix<double, 2, 1> FF_volts = FF * loop_->R();
+      const Eigen::Matrix<double, 2, 1> U_ideal =
+          loop_->K() * (loop_->R() - loop_->X_hat()) + FF_volts;
+
+      for (int i = 0; i < 2; i++) {
+        loop_->mutable_U()[i] = ::aos::Clip(U_ideal[i], -12, 12);
+      }
+
+      // TODO(austin): Model this better.
+      // TODO(austin): Feed back?
+      loop_->mutable_X_hat() =
+          loop_->A() * loop_->X_hat() + loop_->B() * loop_->U();
+#if HAVE_SHIFTERS
+    } else {
+      // Any motor is not in gear.  Speed match.
+      ::Eigen::Matrix<double, 1, 1> R_left;
+      ::Eigen::Matrix<double, 1, 1> R_right;
+      R_left(0, 0) = left_motor_speed;
+      R_right(0, 0) = right_motor_speed;
+
+      const double wiggle =
+          (static_cast<double>((counter_ % 20) / 10) - 0.5) * 5.0;
+
+      loop_->mutable_U(0, 0) = ::aos::Clip(
+          (R_left / Kv)(0, 0) + (IsInGear(left_gear_) ? 0 : wiggle),
+          -12.0, 12.0);
+      loop_->mutable_U(1, 0) = ::aos::Clip(
+          (R_right / Kv)(0, 0) + (IsInGear(right_gear_) ? 0 : wiggle),
+          -12.0, 12.0);
+      loop_->mutable_U() *= 12.0 / ::aos::robot_state->voltage_battery;
+#endif
+    }
+  }
+
+  void SendMotors(DrivetrainQueue::Output *output) {
+    if (output != NULL) {
+      output->left_voltage = loop_->U(0, 0);
+      output->right_voltage = loop_->U(1, 0);
+      output->left_high = left_gear_ == HIGH || left_gear_ == SHIFTING_UP;
+      output->right_high = right_gear_ == HIGH || right_gear_ == SHIFTING_UP;
+    }
+  }
+
+ private:
+  const ::aos::controls::HPolytope<2> U_Poly_;
+
+  ::std::unique_ptr<StateFeedbackLoop<2, 2, 2>> loop_;
+
+  const double ttrust_;
+  double wheel_;
+  double throttle_;
+  bool quickturn_;
+  int stale_count_;
+  double position_time_delta_;
+  Gear left_gear_;
+  Gear right_gear_;
+  DrivetrainQueue::Position last_position_;
+  DrivetrainQueue::Position position_;
+  int counter_;
+};
+constexpr double PolyDrivetrain::kStallTorque;
+constexpr double PolyDrivetrain::kStallCurrent;
+constexpr double PolyDrivetrain::kFreeSpeed;
+constexpr double PolyDrivetrain::kFreeCurrent;
+constexpr double PolyDrivetrain::J;
+constexpr double PolyDrivetrain::m;
+constexpr double PolyDrivetrain::rb;
+constexpr double PolyDrivetrain::kWheelRadius;
+constexpr double PolyDrivetrain::kR;
+constexpr double PolyDrivetrain::Kv;
+constexpr double PolyDrivetrain::Kt;
+
+
+void DrivetrainLoop::RunIteration(const DrivetrainQueue::Goal *goal,
+                                  const DrivetrainQueue::Position *position,
+                                  DrivetrainQueue::Output *output,
+                                  DrivetrainQueue::Status * status) {
+  // TODO(aschuh): These should be members of the class.
+  static DrivetrainMotorsSS dt_closedloop;
+  static PolyDrivetrain dt_openloop;
+
+  bool bad_pos = false;
+  if (position == nullptr) {
+    LOG_INTERVAL(no_position_);
+    bad_pos = true;
+  }
+  no_position_.Print();
+
+  bool control_loop_driving = false;
+  if (goal) {
+    double wheel = goal->steering;
+    double throttle = goal->throttle;
+    bool quickturn = goal->quickturn;
+#if HAVE_SHIFTERS
+    bool highgear = goal->highgear;
+#endif
+
+    control_loop_driving = goal->control_loop_driving;
+    double left_goal = goal->left_goal;
+    double right_goal = goal->right_goal;
+
+    dt_closedloop.SetGoal(left_goal, goal->left_velocity_goal, right_goal,
+                          goal->right_velocity_goal);
+#if HAVE_SHIFTERS
+    dt_openloop.SetGoal(wheel, throttle, quickturn, highgear);
+#else
+    dt_openloop.SetGoal(wheel, throttle, quickturn, false);
+#endif
+  }
+
+  if (!bad_pos) {
+    const double left_encoder = position->left_encoder;
+    const double right_encoder = position->right_encoder;
+    if (gyro_reading.FetchLatest()) {
+      LOG_STRUCT(DEBUG, "using", *gyro_reading.get());
+      dt_closedloop.SetPosition(left_encoder, right_encoder,
+                                gyro_reading->angle);
+    } else {
+      dt_closedloop.SetRawPosition(left_encoder, right_encoder);
+    }
+  }
+  dt_openloop.SetPosition(position);
+  dt_openloop.Update();
+
+  if (control_loop_driving) {
+    dt_closedloop.Update(output == NULL, true);
+    dt_closedloop.SendMotors(output);
+  } else {
+    dt_openloop.SendMotors(output);
+    if (output) {
+      dt_closedloop.SetExternalMotors(output->left_voltage,
+                                      output->right_voltage);
+    }
+    dt_closedloop.Update(output == NULL, false);
+  }
+
+  // set the output status of the control loop state
+  if (status) {
+    bool done = false;
+    if (goal) {
+      done = ((::std::abs(goal->left_goal -
+                          dt_closedloop.GetEstimatedLeftEncoder()) <
+               constants::GetValues().drivetrain_done_distance) &&
+              (::std::abs(goal->right_goal -
+                          dt_closedloop.GetEstimatedRightEncoder()) <
+               constants::GetValues().drivetrain_done_distance));
+    }
+    status->is_done = done;
+    status->robot_speed = dt_closedloop.GetEstimatedRobotSpeed();
+    status->filtered_left_position = dt_closedloop.GetEstimatedLeftEncoder();
+    status->filtered_right_position = dt_closedloop.GetEstimatedRightEncoder();
+
+    status->filtered_left_velocity = dt_closedloop.loop().X_hat(1, 0);
+    status->filtered_right_velocity = dt_closedloop.loop().X_hat(3, 0);
+    status->output_was_capped = dt_closedloop.OutputWasCapped();
+    status->uncapped_left_voltage = dt_closedloop.loop().U_uncapped(0, 0);
+    status->uncapped_right_voltage = dt_closedloop.loop().U_uncapped(1, 0);
+  }
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/drivetrain/drivetrain.gyp b/y2014/control_loops/drivetrain/drivetrain.gyp
new file mode 100644
index 0000000..ffe4337
--- /dev/null
+++ b/y2014/control_loops/drivetrain/drivetrain.gyp
@@ -0,0 +1,103 @@
+{
+  'targets': [
+    {
+      'target_name': 'replay_drivetrain',
+      'type': 'executable',
+      'variables': {
+        'no_rsync': 1,
+      },
+      'sources': [
+        'replay_drivetrain.cc',
+      ],
+      'dependencies': [
+        'drivetrain_queue',
+        '<(AOS)/common/controls/controls.gyp:replay_control_loop',
+        '<(AOS)/linux_code/linux_code.gyp:init',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_queue',
+      'type': 'static_library',
+      'sources': ['drivetrain.q'],
+      'variables': {
+        'header_path': 'y2014/control_loops/drivetrain',
+      },
+      'dependencies': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+      ],
+      'includes': ['../../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'polydrivetrain_plants',
+      'type': 'static_library',
+      'sources': [
+        'polydrivetrain_dog_motor_plant.cc',
+        'drivetrain_dog_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',
+        'polydrivetrain_cim_plant.cc',
+      ],
+      'dependencies': [
+        'drivetrain_queue',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(DEPTH)/y2014/y2014.gyp:constants',
+        '<(AOS)/common/controls/controls.gyp:polytope',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
+        '<(DEPTH)/frc971/queues/queues.gyp:gyro',
+        '<(AOS)/common/util/util.gyp:log_interval',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+        '<(AOS)/common/logging/logging.gyp:matrix_logging',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:polytope',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        'drivetrain_queue',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_lib_test',
+      'type': 'executable',
+      'sources': [
+        'drivetrain_lib_test.cc',
+      ],
+      'dependencies': [
+        '<(EXTERNALS):gtest',
+        'drivetrain_queue',
+        'drivetrain_lib',
+        '<(AOS)/common/controls/controls.gyp:control_loop_test',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(DEPTH)/frc971/queues/queues.gyp:gyro',
+        '<(AOS)/common/common.gyp:queues',
+      ],
+    },
+    {
+      'target_name': 'drivetrain',
+      'type': 'executable',
+      'sources': [
+        'drivetrain_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'drivetrain_lib',
+        'drivetrain_queue',
+      ],
+    },
+  ],
+}
diff --git a/y2014/control_loops/drivetrain/drivetrain.h b/y2014/control_loops/drivetrain/drivetrain.h
new file mode 100644
index 0000000..87e6362
--- /dev/null
+++ b/y2014/control_loops/drivetrain/drivetrain.h
@@ -0,0 +1,43 @@
+#ifndef Y2014_CONTROL_LOOPS_DRIVETRAIN_H_
+#define Y2014_CONTROL_LOOPS_DRIVETRAIN_H_
+
+#include "Eigen/Dense"
+
+#include "aos/common/controls/polytope.h"
+#include "aos/common/controls/control_loop.h"
+#include "aos/common/controls/polytope.h"
+#include "y2014/control_loops/drivetrain/drivetrain.q.h"
+#include "aos/common/util/log_interval.h"
+
+namespace frc971 {
+namespace control_loops {
+
+class DrivetrainLoop
+    : public aos::controls::ControlLoop<control_loops::DrivetrainQueue> {
+ public:
+  // Constructs a control loop which can take a Drivetrain or defaults to the
+  // drivetrain at frc971::control_loops::drivetrain
+  explicit DrivetrainLoop(control_loops::DrivetrainQueue *my_drivetrain =
+                              &control_loops::drivetrain_queue)
+      : aos::controls::ControlLoop<control_loops::DrivetrainQueue>(
+            my_drivetrain) {
+    ::aos::controls::HPolytope<0>::Init();
+  }
+
+ protected:
+  // Executes one cycle of the control loop.
+  virtual void RunIteration(
+      const control_loops::DrivetrainQueue::Goal *goal,
+      const control_loops::DrivetrainQueue::Position *position,
+      control_loops::DrivetrainQueue::Output *output,
+      control_loops::DrivetrainQueue::Status *status);
+
+  typedef ::aos::util::SimpleLogInterval SimpleLogInterval;
+  SimpleLogInterval no_position_ = SimpleLogInterval(
+      ::aos::time::Time::InSeconds(0.25), WARNING, "no position");
+};
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // Y2014_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/y2014/control_loops/drivetrain/drivetrain.q b/y2014/control_loops/drivetrain/drivetrain.q
new file mode 100644
index 0000000..872efec
--- /dev/null
+++ b/y2014/control_loops/drivetrain/drivetrain.q
@@ -0,0 +1,71 @@
+package frc971.control_loops;
+
+import "aos/common/controls/control_loops.q";
+
+struct GearLogging {
+  int8_t controller_index;
+  bool left_loop_high;
+  bool right_loop_high;
+  int8_t left_state;
+  int8_t right_state;
+};
+
+struct CIMLogging {
+  bool left_in_gear;
+  bool right_in_gear;
+  double left_motor_speed;
+  double right_motor_speed;
+  double left_velocity;
+  double right_velocity;
+};
+
+queue_group DrivetrainQueue {
+  implements aos.control_loops.ControlLoop;
+
+  message Goal {
+    double steering;
+    double throttle;
+    bool highgear;
+    bool quickturn;
+    bool control_loop_driving;
+    double left_goal;
+    double left_velocity_goal;
+    double right_goal;
+    double right_velocity_goal;
+  };
+
+  message Position {
+    double left_encoder;
+    double right_encoder;
+    double left_shifter_position;
+    double right_shifter_position;
+  };
+
+  message Output {
+    double left_voltage;
+    double right_voltage;
+    bool left_high;
+    bool right_high;
+  };
+
+  message Status {
+    double robot_speed;
+    double filtered_left_position;
+    double filtered_right_position;
+    double filtered_left_velocity;
+    double filtered_right_velocity;
+
+    double uncapped_left_voltage;
+    double uncapped_right_voltage;
+    bool output_was_capped;
+
+    bool is_done;
+  };
+
+  queue Goal goal;
+  queue Position position;
+  queue Output output;
+  queue Status status;
+};
+
+queue_group DrivetrainQueue drivetrain_queue;
diff --git a/y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.cc b/y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
new file mode 100644
index 0000000..2bb5c94
--- /dev/null
+++ b/y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
@@ -0,0 +1,133 @@
+#include "y2014/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> MakeDrivetrainLowLowPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.00860955515291, 0.0, 0.000228184998733, 0.0, 0.735841675858, 0.0, 0.0410810558113, 0.0, 0.000228184998733, 1.0, 0.00860955515291, 0.0, 0.0410810558113, 0.0, 0.735841675858;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 0.000272244648044, -4.46778919705e-05, 0.0517213538779, -0.00804353916233, -4.46778919705e-05, 0.000272244648044, -0.00804353916233, 0.0517213538779;
+  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);
+}
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowHighPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.00860667098456, 0.0, 7.04111872002e-05, 0.0, 0.735048848179, 0.0, 0.0131811893199, 0.0, 0.000245343870066, 1.0, 0.00957169266049, 0.0, 0.045929121897, 0.0, 0.915703853642;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 0.000272809358971, -2.57343985847e-05, 0.0518765869984, -0.00481755802263, -4.80375440247e-05, 0.00015654091672, -0.00899277497558, 0.0308091755839;
+  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);
+}
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighLowPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.00957169266049, 0.0, 0.000245343870066, 0.0, 0.915703853642, 0.0, 0.045929121897, 0.0, 7.04111872002e-05, 1.0, 0.00860667098456, 0.0, 0.0131811893199, 0.0, 0.735048848179;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 0.00015654091672, -4.80375440247e-05, 0.0308091755839, -0.00899277497558, -2.57343985847e-05, 0.000272809358971, -0.00481755802263, 0.0518765869984;
+  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);
+}
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighHighPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.00957076892085, 0.0, 7.56192087769e-05, 0.0, 0.915439806567, 0.0, 0.0146814193986, 0.0, 7.56192087769e-05, 1.0, 0.00957076892085, 0.0, 0.0146814193986, 0.0, 0.915439806567;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 0.000156878531877, -2.76378646165e-05, 0.0309056814511, -0.00536587314624, -2.76378646165e-05, 0.000156878531877, -0.00536587314624, 0.0309056814511;
+  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> MakeDrivetrainLowLowController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.03584167586, 0.0410810558113, 17.1117704011, 3.22861251708, 0.0410810558113, 1.03584167586, 3.22861251708, 17.1117704011;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 128.210620632, 6.93828382074, 5.11036686771, 0.729493080206, 5.1103668677, 0.729493080206, 128.210620632, 6.93828382074;
+  Eigen::Matrix<double, 4, 4> A_inv;
+  A_inv << 1.0, -0.0117194973377, 0.0, 0.000344183176608, 0.0, 1.36323698074, 0.0, -0.0761076958907, 0.0, 0.000344183176608, 1.0, -0.0117194973377, 0.0, -0.0761076958907, 0.0, 1.36323698074;
+  return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainLowLowPlantCoefficients());
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowHighController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.02891982345, 0.0143715516939, 16.6997472571, 1.23741823594, 0.0143715516939, 1.22183287838, 2.40440177527, 33.5403677132;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 127.841025245, 6.90618982868, -2.11442482189, 0.171361719101, 11.257083857, 1.47190974842, 138.457761234, 11.0770574926;
+  Eigen::Matrix<double, 4, 4> A_inv;
+  A_inv << 1.0, -0.011714710309, 0.0, 9.17355833725e-05, 0.0, 1.36167854796, 0.0, -0.0196008159867, 0.0, 0.00031964754384, 1.0, -0.0104574267731, 0.0, -0.0682979543713, 0.0, 1.09303924439;
+  return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainLowHighPlantCoefficients());
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighLowController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.21584032636, 0.045928553155, 33.3376290177, 4.12652814156, 0.045928553155, 1.03491237546, 2.45838080322, 16.967272239;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 138.457761234, 11.0770574926, 11.257083857, 1.47190974842, -2.1144248219, 0.171361719101, 127.841025245, 6.90618982868;
+  Eigen::Matrix<double, 4, 4> A_inv;
+  A_inv << 1.0, -0.0104574267731, 0.0, 0.00031964754384, 0.0, 1.09303924439, 0.0, -0.0682979543713, 0.0, 9.17355833725e-05, 1.0, -0.011714710309, 0.0, -0.0196008159867, 0.0, 1.36167854796;
+  return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainHighLowPlantCoefficients());
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighHighController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.21543980657, 0.0146814193986, 33.1557840927, 1.47278696694, 0.0146814193986, 1.21543980657, 1.47278696694, 33.1557840927;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 138.52410152, 11.0779399816, 3.96842371774, 0.882728086516, 3.96842371774, 0.882728086517, 138.52410152, 11.0779399816;
+  Eigen::Matrix<double, 4, 4> A_inv;
+  A_inv << 1.0, -0.010456196092, 0.0, 8.50876166887e-05, 0.0, 1.0926521463, 0.0, -0.0175234726538, 0.0, 8.50876166887e-05, 1.0, -0.010456196092, 0.0, -0.0175234726538, 0.0, 1.0926521463;
+  return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainHighHighPlantCoefficients());
+}
+
+StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>> plants(4);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainLowLowPlantCoefficients()));
+  plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainLowHighPlantCoefficients()));
+  plants[2] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainHighLowPlantCoefficients()));
+  plants[3] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainHighHighPlantCoefficients()));
+  return StateFeedbackPlant<4, 2, 2>(&plants);
+}
+
+StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<4, 2, 2>>> controllers(4);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainLowLowController()));
+  controllers[1] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainLowHighController()));
+  controllers[2] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainHighLowController()));
+  controllers[3] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainHighHighController()));
+  return StateFeedbackLoop<4, 2, 2>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.h b/y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.h
new file mode 100644
index 0000000..64498dd
--- /dev/null
+++ b/y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.h
@@ -0,0 +1,32 @@
+#ifndef Y2014_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
+#define Y2014_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> MakeDrivetrainLowLowPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowLowController();
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowHighPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowHighController();
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighLowPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighLowController();
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighHighPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighHighController();
+
+StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant();
+
+StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop();
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // Y2014_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/y2014/control_loops/drivetrain/drivetrain_lib_test.cc b/y2014/control_loops/drivetrain/drivetrain_lib_test.cc
new file mode 100644
index 0000000..e9291d8
--- /dev/null
+++ b/y2014/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -0,0 +1,297 @@
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/network/team_number.h"
+#include "aos/common/queue_testutils.h"
+#include "aos/common/controls/polytope.h"
+#include "aos/common/controls/control_loop_test.h"
+
+#include "y2014/control_loops/drivetrain/drivetrain.q.h"
+#include "y2014/control_loops/drivetrain/drivetrain.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/coerce_goal.h"
+#include "y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "frc971/queues/gyro.q.h"
+
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+
+class Environment : public ::testing::Environment {
+ public:
+  virtual ~Environment() {}
+  // how to set up the environment.
+  virtual void SetUp() {
+    aos::controls::HPolytope<0>::Init();
+  }
+};
+::testing::Environment* const holder_env =
+  ::testing::AddGlobalTestEnvironment(new Environment);
+
+class TeamNumberEnvironment : public ::testing::Environment {
+ public:
+  // Override this to define how to set up the environment.
+  virtual void SetUp() { aos::network::OverrideTeamNumber(971); }
+};
+
+::testing::Environment* const team_number_env =
+    ::testing::AddGlobalTestEnvironment(new TeamNumberEnvironment);
+
+// Class which simulates the drivetrain and sends out queue messages containing
+// the position.
+class DrivetrainSimulation {
+ public:
+  // Constructs a motor simulation.
+  // TODO(aschuh) Do we want to test the clutch one too?
+  DrivetrainSimulation()
+      : drivetrain_plant_(
+            new StateFeedbackPlant<4, 2, 2>(MakeDrivetrainPlant())),
+        my_drivetrain_queue_(".frc971.control_loops.drivetrain",
+                       0x8a8dde77, ".frc971.control_loops.drivetrain.goal",
+                       ".frc971.control_loops.drivetrain.position",
+                       ".frc971.control_loops.drivetrain.output",
+                       ".frc971.control_loops.drivetrain.status") {
+    Reinitialize();
+  }
+
+  // Resets the plant.
+  void Reinitialize() {
+    drivetrain_plant_->mutable_X(0, 0) = 0.0;
+    drivetrain_plant_->mutable_X(1, 0) = 0.0;
+    drivetrain_plant_->mutable_Y() =
+        drivetrain_plant_->C() * drivetrain_plant_->X();
+    last_left_position_ = drivetrain_plant_->Y(0, 0);
+    last_right_position_ = drivetrain_plant_->Y(1, 0);
+  }
+
+  // Returns the position of the drivetrain.
+  double GetLeftPosition() const { return drivetrain_plant_->Y(0, 0); }
+  double GetRightPosition() const { return drivetrain_plant_->Y(1, 0); }
+
+  // Sends out the position queue messages.
+  void SendPositionMessage() {
+    const double left_encoder = GetLeftPosition();
+    const double right_encoder = GetRightPosition();
+
+    ::aos::ScopedMessagePtr<control_loops::DrivetrainQueue::Position> position =
+        my_drivetrain_queue_.position.MakeMessage();
+    position->left_encoder = left_encoder;
+    position->right_encoder = right_encoder;
+    position.Send();
+  }
+
+  // Simulates the drivetrain moving for one timestep.
+  void Simulate() {
+    last_left_position_ = drivetrain_plant_->Y(0, 0);
+    last_right_position_ = drivetrain_plant_->Y(1, 0);
+    EXPECT_TRUE(my_drivetrain_queue_.output.FetchLatest());
+    drivetrain_plant_->mutable_U() << my_drivetrain_queue_.output->left_voltage,
+        my_drivetrain_queue_.output->right_voltage;
+    drivetrain_plant_->Update();
+  }
+
+  ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> drivetrain_plant_;
+ private:
+  DrivetrainQueue my_drivetrain_queue_;
+  double last_left_position_;
+  double last_right_position_;
+};
+
+class DrivetrainTest : public ::aos::testing::ControlLoopTest {
+ protected:
+  // Create a new instance of the test queue so that it invalidates the queue
+  // that it points to.  Otherwise, we will have a pointer to shared memory that
+  // is no longer valid.
+  DrivetrainQueue my_drivetrain_queue_;
+
+  // Create a loop and simulation plant.
+  DrivetrainLoop drivetrain_motor_;
+  DrivetrainSimulation drivetrain_motor_plant_;
+
+  DrivetrainTest() : my_drivetrain_queue_(".frc971.control_loops.drivetrain",
+                               0x8a8dde77,
+                               ".frc971.control_loops.drivetrain.goal",
+                               ".frc971.control_loops.drivetrain.position",
+                               ".frc971.control_loops.drivetrain.output",
+                               ".frc971.control_loops.drivetrain.status"),
+                drivetrain_motor_(&my_drivetrain_queue_),
+                drivetrain_motor_plant_() {
+    ::frc971::sensors::gyro_reading.Clear();
+  }
+
+  void VerifyNearGoal() {
+    my_drivetrain_queue_.goal.FetchLatest();
+    my_drivetrain_queue_.position.FetchLatest();
+    EXPECT_NEAR(my_drivetrain_queue_.goal->left_goal,
+                drivetrain_motor_plant_.GetLeftPosition(),
+                1e-2);
+    EXPECT_NEAR(my_drivetrain_queue_.goal->right_goal,
+                drivetrain_motor_plant_.GetRightPosition(),
+                1e-2);
+  }
+
+  virtual ~DrivetrainTest() {
+    ::frc971::sensors::gyro_reading.Clear();
+  }
+};
+
+// Tests that the drivetrain converges on a goal.
+TEST_F(DrivetrainTest, ConvergesCorrectly) {
+  my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
+      .left_goal(-1.0)
+      .right_goal(1.0).Send();
+  for (int i = 0; i < 200; ++i) {
+    drivetrain_motor_plant_.SendPositionMessage();
+    drivetrain_motor_.Iterate();
+    drivetrain_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  VerifyNearGoal();
+}
+
+// Tests that it survives disabling.
+TEST_F(DrivetrainTest, SurvivesDisabling) {
+  my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
+      .left_goal(-1.0)
+      .right_goal(1.0).Send();
+  for (int i = 0; i < 500; ++i) {
+    drivetrain_motor_plant_.SendPositionMessage();
+    drivetrain_motor_.Iterate();
+    drivetrain_motor_plant_.Simulate();
+    if (i > 20 && i < 200) {
+      SimulateTimestep(false);
+    } else {
+      SimulateTimestep(true);
+    }
+  }
+  VerifyNearGoal();
+}
+
+// Tests that never having a goal doesn't break.
+TEST_F(DrivetrainTest, NoGoalStart) {
+  for (int i = 0; i < 20; ++i) {
+    drivetrain_motor_plant_.SendPositionMessage();
+    drivetrain_motor_.Iterate();
+    drivetrain_motor_plant_.Simulate();
+  }
+}
+
+// Tests that never having a goal, but having driver's station messages, doesn't
+// break.
+TEST_F(DrivetrainTest, NoGoalWithRobotState) {
+  for (int i = 0; i < 20; ++i) {
+    drivetrain_motor_plant_.SendPositionMessage();
+    drivetrain_motor_.Iterate();
+    drivetrain_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+}
+
+::aos::controls::HPolytope<2> MakeBox(double x1_min, double x1_max,
+                                      double x2_min, double x2_max) {
+  Eigen::Matrix<double, 4, 2> box_H;
+  box_H << /*[[*/ 1.0, 0.0 /*]*/,
+            /*[*/-1.0, 0.0 /*]*/,
+            /*[*/ 0.0, 1.0 /*]*/,
+            /*[*/ 0.0,-1.0 /*]]*/;
+  Eigen::Matrix<double, 4, 1> box_k;
+  box_k << /*[[*/ x1_max /*]*/,
+            /*[*/-x1_min /*]*/,
+            /*[*/ x2_max /*]*/,
+            /*[*/-x2_min /*]]*/;
+  ::aos::controls::HPolytope<2> t_poly(box_H, box_k);
+  return t_poly;
+}
+
+class CoerceGoalTest : public ::testing::Test {
+ public:
+  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
+};
+
+// WHOOOHH!
+TEST_F(CoerceGoalTest, Inside) {
+  ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << /*[[*/ 1, -1 /*]]*/;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << /*[[*/ 1.5, 1.5 /*]]*/;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(R(0, 0), output(0, 0));
+  EXPECT_EQ(R(1, 0), output(1, 0));
+}
+
+TEST_F(CoerceGoalTest, Outside_Inside_Intersect) {
+  ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << 1, -1;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << 5, 5;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(2.0, output(0, 0));
+  EXPECT_EQ(2.0, output(1, 0));
+}
+
+TEST_F(CoerceGoalTest, Outside_Inside_no_Intersect) {
+  ::aos::controls::HPolytope<2> box = MakeBox(3, 4, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << 1, -1;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << 5, 5;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(3.0, output(0, 0));
+  EXPECT_EQ(2.0, output(1, 0));
+}
+
+TEST_F(CoerceGoalTest, Middle_Of_Edge) {
+  ::aos::controls::HPolytope<2> box = MakeBox(0, 4, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << -1, 1;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << 5, 5;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(2.0, output(0, 0));
+  EXPECT_EQ(2.0, output(1, 0));
+}
+
+TEST_F(CoerceGoalTest, PerpendicularLine) {
+  ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << 1, 1;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << 5, 5;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(1.0, output(0, 0));
+  EXPECT_EQ(1.0, output(1, 0));
+}
+
+}  // namespace testing
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/drivetrain/drivetrain_main.cc b/y2014/control_loops/drivetrain/drivetrain_main.cc
new file mode 100644
index 0000000..9a2ebe1
--- /dev/null
+++ b/y2014/control_loops/drivetrain/drivetrain_main.cc
@@ -0,0 +1,11 @@
+#include "y2014/control_loops/drivetrain/drivetrain.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+  ::aos::Init();
+  frc971::control_loops::DrivetrainLoop drivetrain;
+  drivetrain.Run();
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2014/control_loops/drivetrain/polydrivetrain_cim_plant.cc b/y2014/control_loops/drivetrain/polydrivetrain_cim_plant.cc
new file mode 100644
index 0000000..0ee9a7a
--- /dev/null
+++ b/y2014/control_loops/drivetrain/polydrivetrain_cim_plant.cc
@@ -0,0 +1,49 @@
+#include "y2014/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;
+  Eigen::Matrix<double, 1, 1> A_inv;
+  A_inv << 1.62723978514;
+  return StateFeedbackController<1, 1, 1>(L, K, A_inv, MakeCIMPlantCoefficients());
+}
+
+StateFeedbackPlant<1, 1, 1> MakeCIMPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>> plants(1);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>(new StateFeedbackPlantCoefficients<1, 1, 1>(MakeCIMPlantCoefficients()));
+  return StateFeedbackPlant<1, 1, 1>(&plants);
+}
+
+StateFeedbackLoop<1, 1, 1> MakeCIMLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<1, 1, 1>>> controllers(1);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<1, 1, 1>>(new StateFeedbackController<1, 1, 1>(MakeCIMController()));
+  return StateFeedbackLoop<1, 1, 1>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/drivetrain/polydrivetrain_cim_plant.h b/y2014/control_loops/drivetrain/polydrivetrain_cim_plant.h
new file mode 100644
index 0000000..62af188
--- /dev/null
+++ b/y2014/control_loops/drivetrain/polydrivetrain_cim_plant.h
@@ -0,0 +1,20 @@
+#ifndef Y2014_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
+#define Y2014_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  // Y2014_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
diff --git a/y2014/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc b/y2014/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
new file mode 100644
index 0000000..a7d80ce
--- /dev/null
+++ b/y2014/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
@@ -0,0 +1,133 @@
+#include "y2014/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> MakeVelocityDrivetrainLowLowPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.735841675858, 0.0410810558113, 0.0410810558113, 0.735841675858;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0517213538779, -0.00804353916233, -0.00804353916233, 0.0517213538779;
+  Eigen::Matrix<double, 2, 2> C;
+  C << 1.0, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0.0, 0.0, 0.0, 0.0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.735048848179, 0.0131811893199, 0.045929121897, 0.915703853642;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0518765869984, -0.00481755802263, -0.00899277497558, 0.0308091755839;
+  Eigen::Matrix<double, 2, 2> C;
+  C << 1.0, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0.0, 0.0, 0.0, 0.0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.915703853642, 0.045929121897, 0.0131811893199, 0.735048848179;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0308091755839, -0.00899277497558, -0.00481755802263, 0.0518765869984;
+  Eigen::Matrix<double, 2, 2> C;
+  C << 1.0, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0.0, 0.0, 0.0, 0.0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.915439806567, 0.0146814193986, 0.0146814193986, 0.915439806567;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0309056814511, -0.00536587314624, -0.00536587314624, 0.0309056814511;
+  Eigen::Matrix<double, 2, 2> C;
+  C << 1.0, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0.0, 0.0, 0.0, 0.0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.715841675858, 0.0410810558113, 0.0410810558113, 0.715841675858;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 2.81809403994, 1.23253744933, 1.23253744933, 2.81809403994;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.36323698074, -0.0761076958907, -0.0761076958907, 1.36323698074;
+  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.715885457343, 0.0459077351335, 0.0459077351335, 0.894867244478;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 2.81810038978, 1.23928174475, 2.31332592354, 10.6088017388;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.36167854796, -0.0196008159867, -0.0682979543713, 1.09303924439;
+  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowHighPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.902328849033, 0.014581304798, 0.014581304798, 0.708423852788;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 10.6088017388, 2.31332592354, 1.23928174475, 2.81810038978;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.09303924439, -0.0682979543713, -0.0196008159867, 1.36167854796;
+  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.895439806567, 0.0146814193986, 0.0146814193986, 0.895439806567;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 10.6088022944, 2.31694961514, 2.31694961514, 10.6088022944;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.0926521463, -0.0175234726538, -0.0175234726538, 1.0926521463;
+  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighHighPlantCoefficients());
+}
+
+StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>> plants(4);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowLowPlantCoefficients()));
+  plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowHighPlantCoefficients()));
+  plants[2] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighLowPlantCoefficients()));
+  plants[3] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighHighPlantCoefficients()));
+  return StateFeedbackPlant<2, 2, 2>(&plants);
+}
+
+StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<2, 2, 2>>> controllers(4);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowLowController()));
+  controllers[1] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowHighController()));
+  controllers[2] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighLowController()));
+  controllers[3] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighHighController()));
+  return StateFeedbackLoop<2, 2, 2>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h b/y2014/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
new file mode 100644
index 0000000..dfac7be
--- /dev/null
+++ b/y2014/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
@@ -0,0 +1,32 @@
+#ifndef Y2014_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
+#define Y2014_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> MakeVelocityDrivetrainLowLowPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController();
+
+StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant();
+
+StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop();
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // Y2014_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/y2014/control_loops/drivetrain/replay_drivetrain.cc b/y2014/control_loops/drivetrain/replay_drivetrain.cc
new file mode 100644
index 0000000..26209fa
--- /dev/null
+++ b/y2014/control_loops/drivetrain/replay_drivetrain.cc
@@ -0,0 +1,24 @@
+#include "aos/common/controls/replay_control_loop.h"
+#include "aos/linux_code/init.h"
+
+#include "y2014/control_loops/drivetrain/drivetrain.q.h"
+
+// Reads one or more log files and sends out all the queue messages (in the
+// correct order and at the correct time) to feed a "live" drivetrain process.
+
+int main(int argc, char **argv) {
+  if (argc <= 1) {
+    fprintf(stderr, "Need at least one file to replay!\n");
+    return EXIT_FAILURE;
+  }
+
+  ::aos::InitNRT();
+
+  ::aos::controls::ControlLoopReplayer<::frc971::control_loops::DrivetrainQueue>
+      replayer(&::frc971::control_loops::drivetrain_queue, "drivetrain");
+  for (int i = 1; i < argc; ++i) {
+    replayer.ProcessFile(argv[i]);
+  }
+
+  ::aos::Cleanup();
+}
diff --git a/y2014/control_loops/python/arm.py b/y2014/control_loops/python/arm.py
new file mode 100755
index 0000000..e17990a
--- /dev/null
+++ b/y2014/control_loops/python/arm.py
@@ -0,0 +1,409 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import polytope
+import polydrivetrain
+import numpy
+import math
+import sys
+import matplotlib
+from matplotlib import pylab
+
+
+class Arm(control_loop.ControlLoop):
+  def __init__(self, name="Arm", mass=None):
+    super(Arm, self).__init__(name)
+    # Stall Torque in N m
+    self.stall_torque = 0.476
+    # Stall Current in Amps
+    self.stall_current = 80.730
+    # Free Speed in RPM
+    self.free_speed = 13906.0
+    # Free Current in Amps
+    self.free_current = 5.820
+    # Mass of the arm
+    if mass is None:
+      self.mass = 13.0
+    else:
+      self.mass = mass
+
+    # Resistance of the motor
+    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
+    # Gear ratio
+    self.G = (44.0 / 12.0) * (54.0 / 14.0) * (54.0 / 14.0) * (44.0 / 20.0) * (72.0 / 16.0)
+    # Fridge arm length
+    self.r = 32 * 0.0254
+    # Control loop time step
+    self.dt = 0.005
+
+    # Arm moment of inertia
+    self.J = self.r * self.mass
+
+    # Arm left/right spring constant (N*m / radian)
+    self.spring = 100.0
+
+    # State is [average position, average velocity,
+    #           position difference/2, velocity difference/2]
+    # Position difference is 1 - 2
+    # Input is [Voltage 1, Voltage 2]
+
+    self.C1 = self.spring / (self.J * 0.5)
+    self.C2 = self.Kt * self.G / (self.J * 0.5 * self.R)
+    self.C3 = self.G * self.G * self.Kt / (self.R  * self.J * 0.5 * self.Kv)
+
+    self.A_continuous = numpy.matrix(
+        [[0, 1, 0, 0],
+         [0, -self.C3, 0, 0],
+         [0, 0, 0, 1],
+         [0, 0, -self.C1 * 2.0, -self.C3]])
+
+    print 'Full speed is', self.C2 / self.C3 * 12.0
+
+    print 'Stall arm difference is', 12.0 * self.C2 / self.C1
+    print 'Stall arm difference first principles is', self.stall_torque * self.G / self.spring
+
+    print '5 degrees of arm error is', self.spring / self.r * (math.pi * 5.0 / 180.0)
+
+    # Start with the unmodified input
+    self.B_continuous = numpy.matrix(
+        [[0, 0],
+         [self.C2 / 2.0, self.C2 / 2.0],
+         [0, 0],
+         [self.C2 / 2.0, -self.C2 / 2.0]])
+
+    self.C = numpy.matrix([[1, 0, 1, 0],
+                           [1, 0, -1, 0]])
+    self.D = numpy.matrix([[0, 0],
+                           [0, 0]])
+
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    controlability = controls.ctrb(self.A, self.B);
+    print 'Rank of augmented controlability matrix.', numpy.linalg.matrix_rank(
+        controlability)
+
+    q_pos = 0.02
+    q_vel = 0.300
+    q_pos_diff = 0.005
+    q_vel_diff = 0.13
+    self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
+                           [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
+                           [0.0, 0.0, (1.0 / (q_pos_diff ** 2.0)), 0.0],
+                           [0.0, 0.0, 0.0, (1.0 / (q_vel_diff ** 2.0))]])
+
+    self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
+                           [0.0, 1.0 / (12.0 ** 2.0)]])
+    self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+    print 'Controller'
+    print self.K
+
+    print 'Controller Poles'
+    print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+    self.rpl = 0.20
+    self.ipl = 0.05
+    self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+                             self.rpl + 1j * self.ipl,
+                             self.rpl - 1j * self.ipl,
+                             self.rpl - 1j * self.ipl])
+
+    # The box formed by U_min and U_max must encompass all possible values,
+    # or else Austin's code gets angry.
+    self.U_max = numpy.matrix([[12.0], [12.0]])
+    self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
+    print 'Observer (Converted to a KF)', numpy.linalg.inv(self.A) * self.L
+
+    self.InitializeState()
+
+
+class IntegralArm(Arm):
+  def __init__(self, name="IntegralArm", mass=None):
+    super(IntegralArm, self).__init__(name=name, mass=mass)
+
+    self.A_continuous_unaugmented = self.A_continuous
+    self.A_continuous = numpy.matrix(numpy.zeros((5, 5)))
+    self.A_continuous[0:4, 0:4] = self.A_continuous_unaugmented
+    self.A_continuous[1, 4] = self.C2
+
+    # Start with the unmodified input
+    self.B_continuous_unaugmented = self.B_continuous
+    self.B_continuous = numpy.matrix(numpy.zeros((5, 2)))
+    self.B_continuous[0:4, 0:2] = self.B_continuous_unaugmented
+
+    self.C_unaugmented = self.C
+    self.C = numpy.matrix(numpy.zeros((2, 5)))
+    self.C[0:2, 0:4] = self.C_unaugmented
+
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+    print 'A cont', self.A_continuous
+    print 'B cont', self.B_continuous
+    print 'A discrete', self.A
+
+    q_pos = 0.08
+    q_vel = 0.40
+
+    q_pos_diff = 0.08
+    q_vel_diff = 0.40
+    q_voltage = 6.0
+    self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0],
+                           [0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0],
+                           [0.0, 0.0, (q_pos_diff ** 2.0), 0.0, 0.0],
+                           [0.0, 0.0, 0.0, (q_vel_diff ** 2.0), 0.0],
+                           [0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0)]])
+
+    r_volts = 0.05
+    self.R = numpy.matrix([[(r_volts ** 2.0), 0.0],
+                           [0.0, (r_volts ** 2.0)]])
+
+    self.KalmanGain, self.Q_steady = controls.kalman(
+        A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+    self.U_max = numpy.matrix([[12.0], [12.0]])
+    self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
+    self.K_unaugmented = self.K
+    self.K = numpy.matrix(numpy.zeros((2, 5)));
+    self.K[0:2, 0:4] = self.K_unaugmented
+    self.K[0, 4] = 1;
+    self.K[1, 4] = 1;
+    print 'Kal', self.KalmanGain
+    self.L = self.A * self.KalmanGain
+
+    self.InitializeState()
+
+
+def CapU(U):
+  if U[0, 0] - U[1, 0] > 24:
+    return numpy.matrix([[12], [-12]])
+  elif U[0, 0] - U[1, 0] < -24:
+    return numpy.matrix([[-12], [12]])
+  else:
+    max_u = max(U[0, 0], U[1, 0])
+    min_u = min(U[0, 0], U[1, 0])
+    if max_u > 12:
+      return U - (max_u - 12)
+    if min_u < -12:
+      return U - (min_u + 12)
+    return U
+
+
+def run_test(arm, initial_X, goal, max_separation_error=0.01,
+             show_graph=True, iterations=200, controller_arm=None,
+             observer_arm=None):
+  """Runs the arm plant with an initial condition and goal.
+
+    The tests themselves are not terribly sophisticated; I just test for
+    whether the goal has been reached and whether the separation goes
+    outside of the initial and goal values by more than max_separation_error.
+    Prints out something for a failure of either condition and returns
+    False if tests fail.
+    Args:
+      arm: arm object to use.
+      initial_X: starting state.
+      goal: goal state.
+      show_graph: Whether or not to display a graph showing the changing
+           states and voltages.
+      iterations: Number of timesteps to run the model for.
+      controller_arm: arm object to get K from, or None if we should
+          use arm.
+      observer_arm: arm object to use for the observer, or None if we should
+          use the actual state.
+  """
+
+  arm.X = initial_X
+
+  if controller_arm is None:
+    controller_arm = arm
+
+  if observer_arm is not None:
+    observer_arm.X_hat = initial_X + 0.01
+    observer_arm.X_hat = initial_X
+
+  # Various lists for graphing things.
+  t = []
+  x_avg = []
+  x_sep = []
+  x_hat_avg = []
+  x_hat_sep = []
+  v_avg = []
+  v_sep = []
+  u_left = []
+  u_right = []
+
+  sep_plot_gain = 100.0
+
+  for i in xrange(iterations):
+    X_hat = arm.X
+    if observer_arm is not None:
+      X_hat = observer_arm.X_hat
+      x_hat_avg.append(observer_arm.X_hat[0, 0])
+      x_hat_sep.append(observer_arm.X_hat[2, 0] * sep_plot_gain)
+    U = controller_arm.K * (goal - X_hat)
+    U = CapU(U)
+    x_avg.append(arm.X[0, 0])
+    v_avg.append(arm.X[1, 0])
+    x_sep.append(arm.X[2, 0] * sep_plot_gain)
+    v_sep.append(arm.X[3, 0])
+    if observer_arm is not None:
+      observer_arm.PredictObserver(U)
+    arm.Update(U)
+    if observer_arm is not None:
+      observer_arm.Y = arm.Y
+      observer_arm.CorrectObserver(U)
+
+    t.append(i * arm.dt)
+    u_left.append(U[0, 0])
+    u_right.append(U[1, 0])
+
+  print numpy.linalg.inv(arm.A)
+  print "delta time is ", arm.dt
+  print "Velocity at t=0 is ", x_avg[0], v_avg[0], x_sep[0], v_sep[0]
+  print "Velocity at t=1+dt is ", x_avg[1], v_avg[1], x_sep[1], v_sep[1]
+
+  if show_graph:
+    pylab.subplot(2, 1, 1)
+    pylab.plot(t, x_avg, label='x avg')
+    pylab.plot(t, x_sep, label='x sep')
+    if observer_arm is not None:
+      pylab.plot(t, x_hat_avg, label='x_hat avg')
+      pylab.plot(t, x_hat_sep, label='x_hat sep')
+    pylab.legend()
+
+    pylab.subplot(2, 1, 2)
+    pylab.plot(t, u_left, label='u left')
+    pylab.plot(t, u_right, label='u right')
+    pylab.legend()
+    pylab.show()
+
+
+def run_integral_test(arm, initial_X, goal, observer_arm, disturbance,
+                      max_separation_error=0.01, show_graph=True,
+                      iterations=400):
+  """Runs the integral control arm plant with an initial condition and goal.
+
+    The tests themselves are not terribly sophisticated; I just test for
+    whether the goal has been reached and whether the separation goes
+    outside of the initial and goal values by more than max_separation_error.
+    Prints out something for a failure of either condition and returns
+    False if tests fail.
+    Args:
+      arm: arm object to use.
+      initial_X: starting state.
+      goal: goal state.
+      observer_arm: arm object to use for the observer.
+      show_graph: Whether or not to display a graph showing the changing
+           states and voltages.
+      iterations: Number of timesteps to run the model for.
+      disturbance: Voltage missmatch between controller and model.
+  """
+
+  arm.X = initial_X
+
+  # Various lists for graphing things.
+  t = []
+  x_avg = []
+  x_sep = []
+  x_hat_avg = []
+  x_hat_sep = []
+  v_avg = []
+  v_sep = []
+  u_left = []
+  u_right = []
+  u_error = []
+
+  sep_plot_gain = 100.0
+
+  unaugmented_goal = goal
+  goal = numpy.matrix(numpy.zeros((5, 1)))
+  goal[0:4, 0] = unaugmented_goal
+
+  for i in xrange(iterations):
+    X_hat = observer_arm.X_hat[0:4]
+
+    x_hat_avg.append(observer_arm.X_hat[0, 0])
+    x_hat_sep.append(observer_arm.X_hat[2, 0] * sep_plot_gain)
+
+    U = observer_arm.K * (goal - observer_arm.X_hat)
+    u_error.append(observer_arm.X_hat[4,0])
+    U = CapU(U)
+    x_avg.append(arm.X[0, 0])
+    v_avg.append(arm.X[1, 0])
+    x_sep.append(arm.X[2, 0] * sep_plot_gain)
+    v_sep.append(arm.X[3, 0])
+
+    observer_arm.PredictObserver(U)
+
+    arm.Update(U + disturbance)
+    observer_arm.Y = arm.Y
+    observer_arm.CorrectObserver(U)
+
+    t.append(i * arm.dt)
+    u_left.append(U[0, 0])
+    u_right.append(U[1, 0])
+
+  print 'End is', observer_arm.X_hat[4, 0]
+
+  if show_graph:
+    pylab.subplot(2, 1, 1)
+    pylab.plot(t, x_avg, label='x avg')
+    pylab.plot(t, x_sep, label='x sep')
+    if observer_arm is not None:
+      pylab.plot(t, x_hat_avg, label='x_hat avg')
+      pylab.plot(t, x_hat_sep, label='x_hat sep')
+    pylab.legend()
+
+    pylab.subplot(2, 1, 2)
+    pylab.plot(t, u_left, label='u left')
+    pylab.plot(t, u_right, label='u right')
+    pylab.plot(t, u_error, label='u error')
+    pylab.legend()
+    pylab.show()
+
+
+def main(argv):
+  loaded_mass = 25
+  #loaded_mass = 0
+  arm = Arm(mass=13 + loaded_mass)
+  #arm_controller = Arm(mass=13 + 15)
+  #observer_arm = Arm(mass=13 + 15)
+  #observer_arm = None
+
+  integral_arm = IntegralArm(mass=13 + loaded_mass)
+  integral_arm.X_hat[0, 0] += 0.02
+  integral_arm.X_hat[2, 0] += 0.02
+  integral_arm.X_hat[4] = 0
+
+  # Test moving the arm with constant separation.
+  initial_X = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+  R = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+  run_integral_test(arm, initial_X, R, integral_arm, disturbance=2)
+
+  # Write the generated constants out to a file.
+  if len(argv) != 5:
+    print "Expected .h file name and .cc file name for the arm and augmented arm."
+  else:
+    arm = Arm("Arm", mass=13)
+    loop_writer = control_loop.ControlLoopWriter("Arm", [arm])
+    if argv[1][-3:] == '.cc':
+      loop_writer.Write(argv[2], argv[1])
+    else:
+      loop_writer.Write(argv[1], argv[2])
+
+    integral_arm = IntegralArm("IntegralArm", mass=13)
+    loop_writer = control_loop.ControlLoopWriter("IntegralArm", [integral_arm])
+    if argv[3][-3:] == '.cc':
+      loop_writer.Write(argv[4], argv[3])
+    else:
+      loop_writer.Write(argv[3], argv[4])
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/y2014/control_loops/python/claw.py b/y2014/control_loops/python/claw.py
new file mode 100755
index 0000000..b5ea6a1
--- /dev/null
+++ b/y2014/control_loops/python/claw.py
@@ -0,0 +1,491 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import polytope
+import polydrivetrain
+import numpy
+import sys
+from matplotlib import pylab
+
+class Claw(control_loop.ControlLoop):
+  def __init__(self, name="RawClaw"):
+    super(Claw, self).__init__(name)
+    # 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 = 5500.0
+    # Free Current in Amps
+    self.free_current = 2.7
+    # Moment of inertia of the claw in kg m^2
+    self.J_top = 2.8
+    self.J_bottom = 3.0
+
+    # Resistance of the motor
+    self.R = 12.0 / self.stall_current
+    # Motor velocity constant
+    self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
+               (13.5 - self.R * self.free_current))
+    # Torque constant
+    self.Kt = self.stall_torque / self.stall_current
+    # Gear ratio
+    self.G = 14.0 / 48.0 * 18.0 / 32.0 * 18.0 / 66.0 * 12.0 / 60.0
+    # Control loop time step
+    self.dt = 0.01
+
+    # State is [bottom position, bottom velocity, top - bottom position,
+    #           top - bottom velocity]
+    # Input is [bottom power, top power - bottom power * J_top / J_bottom]
+    # Motor time constants. difference_bottom refers to the constant for how the
+    # bottom velocity affects the difference of the top and bottom velocities.
+    self.common_motor_constant = -self.Kt / self.Kv / (self.G * self.G * self.R)
+    self.bottom_bottom = self.common_motor_constant / self.J_bottom
+    self.difference_bottom = -self.common_motor_constant * (1 / self.J_bottom
+                                                        - 1 / self.J_top)
+    self.difference_difference = self.common_motor_constant / self.J_top
+    # State feedback matrices
+
+    self.A_continuous = numpy.matrix(
+        [[0, 0, 1, 0],
+         [0, 0, 0, 1],
+         [0, 0, self.bottom_bottom, 0],
+         [0, 0, self.difference_bottom, self.difference_difference]])
+
+    self.A_bottom_cont = numpy.matrix(
+        [[0, 1],
+         [0, self.bottom_bottom]])
+
+    self.A_diff_cont = numpy.matrix(
+        [[0, 1],
+         [0, self.difference_difference]])
+
+    self.motor_feedforward = self.Kt / (self.G * self.R)
+    self.motor_feedforward_bottom = self.motor_feedforward / self.J_bottom
+    self.motor_feedforward_difference = self.motor_feedforward / self.J_top
+    self.motor_feedforward_difference_bottom = (
+        self.motor_feedforward * (1 / self.J_bottom - 1 / self.J_top))
+    self.B_continuous = numpy.matrix(
+        [[0, 0],
+         [0, 0],
+         [self.motor_feedforward_bottom, 0],
+         [-self.motor_feedforward_bottom, self.motor_feedforward_difference]])
+
+    print "Cont X_ss", self.motor_feedforward / -self.common_motor_constant
+
+    self.B_bottom_cont = numpy.matrix(
+        [[0],
+         [self.motor_feedforward_bottom]])
+
+    self.B_diff_cont = numpy.matrix(
+        [[0],
+         [self.motor_feedforward_difference]])
+
+    self.C = numpy.matrix([[1, 0, 0, 0],
+                           [1, 1, 0, 0]])
+    self.D = numpy.matrix([[0, 0],
+                           [0, 0]])
+
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    self.A_bottom, self.B_bottom = controls.c2d(
+        self.A_bottom_cont, self.B_bottom_cont, self.dt)
+    self.A_diff, self.B_diff = controls.c2d(
+        self.A_diff_cont, self.B_diff_cont, self.dt)
+
+    self.K_bottom = controls.dplace(self.A_bottom, self.B_bottom, [.75 + 0.1j, .75 - 0.1j])
+    self.K_diff = controls.dplace(self.A_diff, self.B_diff, [.75 + 0.1j, .75 - 0.1j])
+
+    print "K_diff", self.K_diff
+    print "K_bottom", self.K_bottom
+
+    print "A"
+    print self.A
+    print "B"
+    print self.B
+
+    
+    self.Q = numpy.matrix([[(1.0 / (0.10 ** 2.0)), 0.0, 0.0, 0.0],
+                           [0.0, (1.0 / (0.06 ** 2.0)), 0.0, 0.0],
+                           [0.0, 0.0, 0.10, 0.0],
+                           [0.0, 0.0, 0.0, 0.1]])
+
+    self.R = numpy.matrix([[(1.0 / (40.0 ** 2.0)), 0.0],
+                           [0.0, (1.0 / (5.0 ** 2.0))]])
+    #self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+
+    self.K = numpy.matrix([[self.K_bottom[0, 0], 0.0, self.K_bottom[0, 1], 0.0],
+                           [0.0, self.K_diff[0, 0], 0.0, self.K_diff[0, 1]]])
+
+    # Compute the feed forwards aceleration term.
+    self.K[1, 0] = -self.B[1, 0] * self.K[0, 0] / self.B[1, 1]
+
+    lstsq_A = numpy.identity(2)
+    lstsq_A[0, :] = self.B[1, :]
+    lstsq_A[1, :] = self.B[3, :]
+    print "System of Equations coefficients:"
+    print lstsq_A
+    print "det", numpy.linalg.det(lstsq_A)
+
+    out_x = numpy.linalg.lstsq(
+                         lstsq_A,
+                         numpy.matrix([[self.A[1, 2]], [self.A[3, 2]]]))[0]
+    self.K[1, 2] = -lstsq_A[0, 0] * (self.K[0, 2] - out_x[0]) / lstsq_A[0, 1] + out_x[1]
+
+    print "K unaugmented"
+    print self.K
+    print "B * K unaugmented"
+    print self.B * self.K
+    F = self.A - self.B * self.K
+    print "A - B * K unaugmented"
+    print F
+    print "eigenvalues"
+    print numpy.linalg.eig(F)[0]
+
+    self.rpl = .05
+    self.ipl = 0.010
+    self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+                             self.rpl + 1j * self.ipl,
+                             self.rpl - 1j * self.ipl,
+                             self.rpl - 1j * self.ipl])
+
+    # The box formed by U_min and U_max must encompass all possible values,
+    # or else Austin's code gets angry.
+    self.U_max = numpy.matrix([[12.0], [12.0]])
+    self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
+    # For the tests that check the limits, these are (upper, lower) for both
+    # claws.
+    self.hard_pos_limits = None
+    self.pos_limits = None
+
+    # Compute the steady state velocities for a given applied voltage.
+    # The top and bottom of the claw should spin at the same rate if the
+    # physics is right.
+    X_ss = numpy.matrix([[0], [0], [0.0], [0]])
+    
+    U = numpy.matrix([[1.0],[1.0]])
+    A = self.A
+    B = self.B
+    #X_ss[2, 0] = X_ss[2, 0] * A[2, 2] + B[2, 0] * U[0, 0]
+    X_ss[2, 0] = 1 / (1 - A[2, 2]) * B[2, 0] * U[0, 0]
+    #X_ss[3, 0] = X_ss[3, 0] * A[3, 3] + X_ss[2, 0] * A[3, 2] + B[3, 0] * U[0, 0] + B[3, 1] * U[1, 0]
+    #X_ss[3, 0] * (1 - A[3, 3]) = X_ss[2, 0] * A[3, 2] + B[3, 0] * U[0, 0] + B[3, 1] * U[1, 0]
+    X_ss[3, 0] = 1 / (1 - A[3, 3]) * (X_ss[2, 0] * A[3, 2] + B[3, 1] * U[1, 0] + B[3, 0] * U[0, 0])
+    #X_ss[3, 0] = 1 / (1 - A[3, 3]) / (1 - A[2, 2]) * B[2, 0] * U[0, 0] * A[3, 2] + B[3, 0] * U[0, 0] + B[3, 1] * U[1, 0]
+    X_ss[0, 0] = A[0, 2] * X_ss[2, 0] + B[0, 0] * U[0, 0]
+    X_ss[1, 0] = A[1, 2] * X_ss[2, 0] + A[1, 3] * X_ss[3, 0] + B[1, 0] * U[0, 0] + B[1, 1] * U[1, 0]
+
+    print "X_ss", X_ss
+
+    self.InitializeState()
+
+
+class ClawDeltaU(Claw):
+  def __init__(self, name="Claw"):
+    super(ClawDeltaU, self).__init__(name)
+    A_unaugmented = self.A
+    B_unaugmented = self.B
+    C_unaugmented = self.C
+
+    self.A = numpy.matrix([[0.0, 0.0, 0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0, 0.0, 1.0]])
+    self.A[0:4, 0:4] = A_unaugmented
+    self.A[0:4, 4] = B_unaugmented[0:4, 0]
+
+    self.B = numpy.matrix([[0.0, 0.0],
+                           [0.0, 0.0],
+                           [0.0, 0.0],
+                           [0.0, 0.0],
+                           [1.0, 0.0]])
+    self.B[0:4, 1] = B_unaugmented[0:4, 1]
+
+    self.C = numpy.concatenate((C_unaugmented, numpy.matrix([[0.0], [0.0]])),
+                               axis=1)
+    self.D = numpy.matrix([[0.0, 0.0],
+                           [0.0, 0.0]])
+
+    #self.PlaceControllerPoles([0.55, 0.35, 0.55, 0.35, 0.80])
+    self.Q = numpy.matrix([[(1.0 / (0.04 ** 2.0)), 0.0, 0.0, 0.0, 0.0],
+                           [0.0, (1.0 / (0.01 ** 2)), 0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.01, 0.0, 0.0],
+                           [0.0, 0.0, 0.0, 0.08, 0.0],
+                           [0.0, 0.0, 0.0, 0.0, (1.0 / (10.0 ** 2))]])
+
+    self.R = numpy.matrix([[0.000001, 0.0],
+                           [0.0, 1.0 / (10.0 ** 2.0)]])
+    self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+
+    self.K = numpy.matrix([[50.0, 0.0, 10.0, 0.0, 1.0],
+                           [50.0, 0.0, 10.0, 0.0, 1.0]])
+    #self.K = numpy.matrix([[50.0, -100.0, 0, -10, 0],
+    #                       [50.0,  100.0, 0, 10, 0]])
+
+    controlability = controls.ctrb(self.A, self.B);
+    print "Rank of augmented controlability matrix.", numpy.linalg.matrix_rank(controlability)
+
+    print "K"
+    print self.K
+    print "Placed controller poles are"
+    print numpy.linalg.eig(self.A - self.B * self.K)[0]
+    print [numpy.abs(x) for x in numpy.linalg.eig(self.A - self.B * self.K)[0]]
+
+    self.rpl = .05
+    self.ipl = 0.008
+    self.PlaceObserverPoles([self.rpl + 1j * self.ipl, 0.10, 0.09,
+                             self.rpl - 1j * self.ipl, 0.90])
+    #print "A is"
+    #print self.A
+    #print "L is"
+    #print self.L
+    #print "C is"
+    #print self.C
+    #print "A - LC is"
+    #print self.A - self.L * self.C
+
+    #print "Placed observer poles are"
+    #print numpy.linalg.eig(self.A - self.L * self.C)[0]
+
+    self.U_max = numpy.matrix([[12.0], [12.0]])
+    self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
+    self.InitializeState()
+
+def ScaleU(claw, U, K, error):
+  """Clips U as necessary.
+
+    Args:
+      claw: claw object containing moments of inertia and U limits.
+      U: Input matrix to clip as necessary.
+  """
+
+  bottom_u = U[0, 0]
+  top_u = U[1, 0]
+  position_error = error[0:2, 0]
+  velocity_error = error[2:, 0]
+
+  U_poly = polytope.HPolytope(
+      numpy.matrix([[1, 0],
+                    [-1, 0],
+                    [0, 1],
+                    [0, -1]]),
+      numpy.matrix([[12],
+                    [12],
+                    [12],
+                    [12]]))
+
+  if (bottom_u > claw.U_max[0, 0] or bottom_u < claw.U_min[0, 0] or
+      top_u > claw.U_max[0, 0] or top_u < claw.U_min[0, 0]):
+
+    position_K = K[:, 0:2]
+    velocity_K = K[:, 2:]
+
+    # H * U <= k
+    # U = UPos + UVel
+    # H * (UPos + UVel) <= k
+    # H * UPos <= k - H * UVel
+    #
+    # Now, we can do a coordinate transformation and say the following.
+    #
+    # UPos = position_K * position_error
+    # (H * position_K) * position_error <= k - H * UVel
+    #
+    # Add in the constraint that 0 <= t <= 1
+    # Now, there are 2 ways this can go.  Either we have a region, or we don't
+    # have a region.  If we have a region, then pick the largest t and go for it.
+    # If we don't have a region, we need to pick a good comprimise.
+
+    pos_poly = polytope.HPolytope(
+        U_poly.H * position_K,
+        U_poly.k - U_poly.H * velocity_K * velocity_error)
+
+    # The actual angle for the line we call 45.
+    angle_45 = numpy.matrix([[numpy.sqrt(3), 1]])
+    if claw.pos_limits and claw.hard_pos_limits and claw.X[0, 0] + claw.X[1, 0] > claw.pos_limits[1]:
+      angle_45 = numpy.matrix([[1, 1]])
+
+    P = position_error
+    L45 = numpy.multiply(numpy.matrix([[numpy.sign(P[1, 0]), -numpy.sign(P[0, 0])]]), angle_45)
+    if L45[0, 1] == 0:
+      L45[0, 1] = 1
+    if L45[0, 0] == 0:
+      L45[0, 0] = 1
+    w45 = numpy.matrix([[0]])
+
+    if numpy.abs(P[0, 0]) > numpy.abs(P[1, 0]):
+      LH = numpy.matrix([[0, 1]])
+    else:
+      LH = numpy.matrix([[1, 0]])
+    wh = LH * P
+    standard = numpy.concatenate((L45, LH))
+    W = numpy.concatenate((w45, wh))
+    intersection = numpy.linalg.inv(standard) * W
+    adjusted_pos_error_h, is_inside_h = polydrivetrain.DoCoerceGoal(pos_poly,
+        LH, wh, position_error)
+    adjusted_pos_error_45, is_inside_45 = polydrivetrain.DoCoerceGoal(pos_poly,
+        L45, w45, intersection)
+    if pos_poly.IsInside(intersection):
+      adjusted_pos_error = adjusted_pos_error_h
+    else:
+      if is_inside_h:
+        if numpy.linalg.norm(adjusted_pos_error_h) > numpy.linalg.norm(adjusted_pos_error_45):
+          adjusted_pos_error = adjusted_pos_error_h
+        else:
+          adjusted_pos_error = adjusted_pos_error_45
+      else:
+        adjusted_pos_error = adjusted_pos_error_45
+    #print adjusted_pos_error
+
+    #print "Actual power is ", velocity_K * velocity_error + position_K * adjusted_pos_error
+    return velocity_K * velocity_error + position_K * adjusted_pos_error
+
+    #U = Kpos * poserror + Kvel * velerror
+      
+    #scalar = claw.U_max[0, 0] / max(numpy.abs(top_u), numpy.abs(bottom_u))
+
+    #top_u *= scalar
+    #bottom_u *= scalar
+
+  return numpy.matrix([[bottom_u], [top_u]])
+
+def run_test(claw, initial_X, goal, max_separation_error=0.01, show_graph=False, iterations=200):
+  """Runs the claw plant on a given claw (claw) with an initial condition (initial_X) and goal (goal).
+
+    The tests themselves are not terribly sophisticated; I just test for 
+    whether the goal has been reached and whether the separation goes
+    outside of the initial and goal values by more than max_separation_error.
+    Prints out something for a failure of either condition and returns
+    False if tests fail.
+    Args:
+      claw: claw object to use.
+      initial_X: starting state.
+      goal: goal state.
+      show_graph: Whether or not to display a graph showing the changing
+           states and voltages.
+      iterations: Number of timesteps to run the model for."""
+
+  claw.X = initial_X
+
+  # Various lists for graphing things.
+  t = []
+  x_bottom = []
+  x_top = []
+  u_bottom = []
+  u_top = []
+  x_separation = []
+
+  tests_passed = True
+
+  # Bounds which separation should not exceed.
+  lower_bound = (initial_X[1, 0] if initial_X[1, 0] < goal[1, 0]
+                 else goal[1, 0]) - max_separation_error
+  upper_bound = (initial_X[1, 0] if initial_X[1, 0] > goal[1, 0]
+                 else goal[1, 0]) + max_separation_error
+
+  for i in xrange(iterations):
+    U = claw.K * (goal - claw.X)
+    U = ScaleU(claw, U, claw.K, goal - claw.X)
+    claw.Update(U)
+
+    if claw.X[1, 0] > upper_bound or claw.X[1, 0] < lower_bound:
+      tests_passed = False
+      print "Claw separation was", claw.X[1, 0]
+      print "Should have been between", lower_bound, "and", upper_bound
+
+    if claw.hard_pos_limits and \
+      (claw.X[0, 0] > claw.hard_pos_limits[1] or
+          claw.X[0, 0] < claw.hard_pos_limits[0] or
+          claw.X[0, 0] + claw.X[1, 0] > claw.hard_pos_limits[1] or
+          claw.X[0, 0] + claw.X[1, 0] < claw.hard_pos_limits[0]):
+      tests_passed = False
+      print "Claws at %f and %f" % (claw.X[0, 0], claw.X[0, 0] + claw.X[1, 0])
+      print "Both should be in %s, definitely %s" % \
+          (claw.pos_limits, claw.hard_pos_limits)
+
+    t.append(i * claw.dt)
+    x_bottom.append(claw.X[0, 0] * 10.0)
+    x_top.append((claw.X[1, 0] + claw.X[0, 0]) * 10.0)
+    u_bottom.append(U[0, 0])
+    u_top.append(U[1, 0])
+    x_separation.append(claw.X[1, 0] * 10.0)
+
+  if show_graph:
+    pylab.plot(t, x_bottom, label='x bottom * 10')
+    pylab.plot(t, x_top, label='x top * 10')
+    pylab.plot(t, u_bottom, label='u bottom')
+    pylab.plot(t, u_top, label='u top')
+    pylab.plot(t, x_separation, label='separation * 10')
+    pylab.legend()
+    pylab.show()
+
+  # Test to make sure that we are near the goal.
+  if numpy.max(abs(claw.X - goal)) > 1e-4:
+    tests_passed = False
+    print "X was", claw.X, "Expected", goal
+
+  return tests_passed
+
+def main(argv):
+  claw = Claw()
+
+  # Test moving the claw with constant separation.
+  initial_X = numpy.matrix([[-1.0], [0.0], [0.0], [0.0]])
+  R = numpy.matrix([[1.0], [0.0], [0.0], [0.0]])
+  run_test(claw, initial_X, R)
+
+  # Test just changing separation.
+  initial_X = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+  R = numpy.matrix([[0.0], [1.0], [0.0], [0.0]])
+  run_test(claw, initial_X, R)
+
+  # Test changing both separation and position at once.
+  initial_X = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+  R = numpy.matrix([[1.0], [1.0], [0.0], [0.0]])
+  run_test(claw, initial_X, R)
+
+  # Test a small separation error and a large position one.
+  initial_X = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+  R = numpy.matrix([[2.0], [0.05], [0.0], [0.0]])
+  run_test(claw, initial_X, R)
+
+  # Test a small separation error and a large position one.
+  initial_X = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+  R = numpy.matrix([[-0.5], [1.0], [0.0], [0.0]])
+  run_test(claw, initial_X, R)
+
+  # Test opening with the top claw at the limit.
+  initial_X = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+  R = numpy.matrix([[-1.5], [1.5], [0.0], [0.0]])
+  claw.hard_pos_limits = (-1.6, 0.1)
+  claw.pos_limits = (-1.5, 0.0)
+  run_test(claw, initial_X, R)
+  claw.pos_limits = None
+
+  # Test opening with the bottom claw at the limit.
+  initial_X = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+  R = numpy.matrix([[0], [1.5], [0.0], [0.0]])
+  claw.hard_pos_limits = (-0.1, 1.6)
+  claw.pos_limits = (0.0, 1.6)
+  run_test(claw, initial_X, R)
+  claw.pos_limits = None
+
+  # Write the generated constants out to a file.
+  if len(argv) != 3:
+    print "Expected .h file name and .cc file name for the claw."
+  else:
+    claw = Claw("Claw")
+    loop_writer = control_loop.ControlLoopWriter("Claw", [claw])
+    loop_writer.AddConstant(control_loop.Constant("kClawMomentOfInertiaRatio",
+      "%f", claw.J_top / claw.J_bottom))
+    if argv[1][-3:] == '.cc':
+      loop_writer.Write(argv[2], argv[1])
+    else:
+      loop_writer.Write(argv[1], argv[2])
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/y2014/control_loops/python/drivetrain.py b/y2014/control_loops/python/drivetrain.py
new file mode 100755
index 0000000..ac05a57
--- /dev/null
+++ b/y2014/control_loops/python/drivetrain.py
@@ -0,0 +1,239 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import numpy
+import sys
+from matplotlib import pylab
+
+
+class CIM(control_loop.ControlLoop):
+  def __init__(self):
+    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.005
+
+    # 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, name="Drivetrain", left_low=True, right_low=True):
+    super(Drivetrain, self).__init__(name)
+    # Stall Torque in N m
+    self.stall_torque = 2.42
+    # Stall Current in Amps
+    self.stall_current = 133.0
+    # Free Speed in RPM. Used number from last year.
+    self.free_speed = 4650.0
+    # Free Current in Amps
+    self.free_current = 2.7
+    # Moment of inertia of the drivetrain in kg m^2
+    # Just borrowed from last year.
+    self.J = 4.5
+    # Mass of the robot, in kg.
+    self.m = 68
+    # Radius of the robot, in meters (from last year).
+    self.rb = 0.617998644 / 2.0
+    # 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 / 4
+    # 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 = 18.0 / 60.0 * 18.0 / 50.0
+    self.G_high = 28.0 / 50.0 * 18.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.005
+
+    # These describe the way that a given side of a robot will be influenced
+    # by the other side. Units of 1 / kg.
+    self.msp = 1.0 / self.m + self.rb * self.rb / self.J
+    self.msn = 1.0 / self.m - self.rb * self.rb / self.J
+    # The calculations which we will need for A and B.
+    self.tcl = -self.Kt / self.Kv / (self.Gl * self.Gl * self.R * self.r * self.r)
+    self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.R * self.r * self.r)
+    self.mpl = self.Kt / (self.Gl * self.R * self.r)
+    self.mpr = self.Kt / (self.Gr * self.R * self.r)
+
+    # State feedback matrices
+    # X will be of the format
+    # [[positionl], [velocityl], [positionr], velocityr]]
+    self.A_continuous = numpy.matrix(
+        [[0, 1, 0, 0],
+         [0, self.msp * self.tcl, 0, self.msn * self.tcr],
+         [0, 0, 0, 1],
+         [0, self.msn * self.tcl, 0, self.msp * self.tcr]])
+    self.B_continuous = numpy.matrix(
+        [[0, 0],
+         [self.msp * self.mpl, self.msn * self.mpr],
+         [0, 0],
+         [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],
+                           [0, 0]])
+
+    #print "THE NUMBER I WANT" + str(numpy.linalg.inv(self.A_continuous) * -self.B_continuous * numpy.matrix([[12.0], [12.0]]))
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    # Poles from last year.
+    self.hp = 0.65
+    self.lp = 0.83
+    self.PlaceControllerPoles([self.hp, self.lp, self.hp, self.lp])
+    print self.K
+    q_pos = 0.07
+    q_vel = 1.0
+    self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
+                           [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
+                           [0.0, 0.0, (1.0 / (q_pos ** 2.0)), 0.0],
+                           [0.0, 0.0, 0.0, (1.0 / (q_vel ** 2.0))]])
+
+    self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
+                           [0.0, (1.0 / (12.0 ** 2.0))]])
+    self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+    print self.A
+    print self.B
+    print self.K
+    print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+    self.hlp = 0.3
+    self.llp = 0.4
+    self.PlaceObserverPoles([self.hlp, self.hlp, self.llp, self.llp])
+
+    self.U_max = numpy.matrix([[12.0], [12.0]])
+    self.U_min = numpy.matrix([[-12.0], [-12.0]])
+    self.InitializeState()
+
+def main(argv):
+  # Simulate the response of the system to a step input.
+  drivetrain = Drivetrain()
+  simulated_left = []
+  simulated_right = []
+  for _ in xrange(100):
+    drivetrain.Update(numpy.matrix([[12.0], [12.0]]))
+    simulated_left.append(drivetrain.X[0, 0])
+    simulated_right.append(drivetrain.X[2, 0])
+
+  #pylab.plot(range(100), simulated_left)
+  #pylab.plot(range(100), simulated_right)
+  #pylab.show()
+
+  # Simulate forwards motion.
+  drivetrain = Drivetrain()
+  close_loop_left = []
+  close_loop_right = []
+  R = numpy.matrix([[1.0], [0.0], [1.0], [0.0]])
+  for _ in xrange(100):
+    U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
+                   drivetrain.U_min, drivetrain.U_max)
+    drivetrain.UpdateObserver(U)
+    drivetrain.Update(U)
+    close_loop_left.append(drivetrain.X[0, 0])
+    close_loop_right.append(drivetrain.X[2, 0])
+
+  #pylab.plot(range(100), close_loop_left)
+  #pylab.plot(range(100), close_loop_right)
+  #pylab.show()
+
+  # Try turning in place
+  drivetrain = Drivetrain()
+  close_loop_left = []
+  close_loop_right = []
+  R = numpy.matrix([[-1.0], [0.0], [1.0], [0.0]])
+  for _ in xrange(100):
+    U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
+                   drivetrain.U_min, drivetrain.U_max)
+    drivetrain.UpdateObserver(U)
+    drivetrain.Update(U)
+    close_loop_left.append(drivetrain.X[0, 0])
+    close_loop_right.append(drivetrain.X[2, 0])
+
+  #pylab.plot(range(100), close_loop_left)
+  #pylab.plot(range(100), close_loop_right)
+  #pylab.show()
+
+  # Try turning just one side.
+  drivetrain = Drivetrain()
+  close_loop_left = []
+  close_loop_right = []
+  R = numpy.matrix([[0.0], [0.0], [1.0], [0.0]])
+  for _ in xrange(100):
+    U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
+                   drivetrain.U_min, drivetrain.U_max)
+    drivetrain.UpdateObserver(U)
+    drivetrain.Update(U)
+    close_loop_left.append(drivetrain.X[0, 0])
+    close_loop_right.append(drivetrain.X[2, 0])
+
+  #pylab.plot(range(100), close_loop_left)
+  #pylab.plot(range(100), close_loop_right)
+  #pylab.show()
+
+  # Write the generated constants out to a file.
+  print "Output one"
+  drivetrain_low_low = Drivetrain(name="DrivetrainLowLow", left_low=True, right_low=True)
+  drivetrain_low_high = Drivetrain(name="DrivetrainLowHigh", left_low=True, right_low=False)
+  drivetrain_high_low = Drivetrain(name="DrivetrainHighLow", left_low=False, right_low=True)
+  drivetrain_high_high = Drivetrain(name="DrivetrainHighHigh", left_low=False, right_low=False)
+
+  if len(argv) != 5:
+    print "Expected .h file name and .cc file name"
+  else:
+    dog_loop_writer = control_loop.ControlLoopWriter(
+        "Drivetrain", [drivetrain_low_low, drivetrain_low_high,
+                       drivetrain_high_low, 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])
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/y2014/control_loops/python/elevator.py b/y2014/control_loops/python/elevator.py
new file mode 100755
index 0000000..fba72c8
--- /dev/null
+++ b/y2014/control_loops/python/elevator.py
@@ -0,0 +1,246 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import polytope
+import polydrivetrain
+import numpy
+import sys
+import matplotlib
+from matplotlib import pylab
+
+class Elevator(control_loop.ControlLoop):
+  def __init__(self, name="Elevator", mass=None):
+    super(Elevator, self).__init__(name)
+    # Stall Torque in N m
+    self.stall_torque = 0.476
+    # Stall Current in Amps
+    self.stall_current = 80.730
+    # Free Speed in RPM
+    self.free_speed = 13906.0
+    # Free Current in Amps
+    self.free_current = 5.820
+    # Mass of the elevator
+    if mass is None:
+      self.mass = 13.0
+    else:
+      self.mass = mass
+
+    # Resistance of the motor
+    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
+    # Gear ratio
+    self.G = (56.0 / 12.0) * (84.0 / 14.0)
+    # Pulley diameter
+    self.r = 32 * 0.005 / numpy.pi / 2.0
+    # Control loop time step
+    self.dt = 0.005
+
+    # Elevator left/right spring constant (N/m)
+    self.spring = 800.0
+
+    # State is [average position, average velocity,
+    #           position difference/2, velocity difference/2]
+    # Input is [V_left, V_right]
+
+    C1 = self.spring / (self.mass * 0.5)
+    C2 = self.Kt * self.G / (self.mass * 0.5 * self.r * self.R)
+    C3 = self.G * self.G * self.Kt / (
+        self.R  * self.r * self.r * self.mass * 0.5 * self.Kv)
+
+    self.A_continuous = numpy.matrix(
+        [[0, 1, 0, 0],
+         [0, -C3, 0, 0],
+         [0, 0, 0, 1],
+         [0, 0, -C1 * 2.0, -C3]])
+
+    print "Full speed is", C2 / C3 * 12.0
+
+    # Start with the unmodified input
+    self.B_continuous = numpy.matrix(
+        [[0, 0],
+         [C2 / 2.0, C2 / 2.0],
+         [0, 0],
+         [C2 / 2.0, -C2 / 2.0]])
+
+    self.C = numpy.matrix([[1, 0, 1, 0],
+                           [1, 0, -1, 0]])
+    self.D = numpy.matrix([[0, 0],
+                           [0, 0]])
+
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    print self.A
+
+    controlability = controls.ctrb(self.A, self.B);
+    print "Rank of augmented controlability matrix.", numpy.linalg.matrix_rank(
+        controlability)
+
+    q_pos = 0.02
+    q_vel = 0.400
+    q_pos_diff = 0.01
+    q_vel_diff = 0.45
+    self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
+                           [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
+                           [0.0, 0.0, (1.0 / (q_pos_diff ** 2.0)), 0.0],
+                           [0.0, 0.0, 0.0, (1.0 / (q_vel_diff ** 2.0))]])
+
+    self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
+                           [0.0, 1.0 / (12.0 ** 2.0)]])
+    self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+    print self.K
+
+    print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+    self.rpl = 0.20
+    self.ipl = 0.05
+    self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+                             self.rpl + 1j * self.ipl,
+                             self.rpl - 1j * self.ipl,
+                             self.rpl - 1j * self.ipl])
+
+    # The box formed by U_min and U_max must encompass all possible values,
+    # or else Austin's code gets angry.
+    self.U_max = numpy.matrix([[12.0], [12.0]])
+    self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
+    self.InitializeState()
+
+
+def CapU(U):
+  if U[0, 0] - U[1, 0] > 24:
+    return numpy.matrix([[12], [-12]])
+  elif U[0, 0] - U[1, 0] < -24:
+    return numpy.matrix([[-12], [12]])
+  else:
+    max_u = max(U[0, 0], U[1, 0])
+    min_u = min(U[0, 0], U[1, 0])
+    if max_u > 12:
+      return U - (max_u - 12)
+    if min_u < -12:
+      return U - (min_u + 12)
+    return U
+
+
+def run_test(elevator, initial_X, goal, max_separation_error=0.01,
+             show_graph=True, iterations=200, controller_elevator=None,
+             observer_elevator=None):
+  """Runs the elevator plant with an initial condition and goal.
+
+    The tests themselves are not terribly sophisticated; I just test for
+    whether the goal has been reached and whether the separation goes
+    outside of the initial and goal values by more than max_separation_error.
+    Prints out something for a failure of either condition and returns
+    False if tests fail.
+    Args:
+      elevator: elevator object to use.
+      initial_X: starting state.
+      goal: goal state.
+      show_graph: Whether or not to display a graph showing the changing
+           states and voltages.
+      iterations: Number of timesteps to run the model for.
+      controller_elevator: elevator object to get K from, or None if we should
+          use elevator.
+      observer_elevator: elevator object to use for the observer, or None if we
+          should use the actual state.
+  """
+
+  elevator.X = initial_X
+
+  if controller_elevator is None:
+    controller_elevator = elevator
+
+  if observer_elevator is not None:
+    observer_elevator.X_hat = initial_X + 0.01
+    observer_elevator.X_hat = initial_X
+
+  # Various lists for graphing things.
+  t = []
+  x_avg = []
+  x_sep = []
+  x_hat_avg = []
+  x_hat_sep = []
+  v_avg = []
+  v_sep = []
+  u_left = []
+  u_right = []
+
+  sep_plot_gain = 100.0
+
+  for i in xrange(iterations):
+    X_hat = elevator.X
+    if observer_elevator is not None:
+      X_hat = observer_elevator.X_hat
+      x_hat_avg.append(observer_elevator.X_hat[0, 0])
+      x_hat_sep.append(observer_elevator.X_hat[2, 0] * sep_plot_gain)
+    U = controller_elevator.K * (goal - X_hat)
+    U = CapU(U)
+    x_avg.append(elevator.X[0, 0])
+    v_avg.append(elevator.X[1, 0])
+    x_sep.append(elevator.X[2, 0] * sep_plot_gain)
+    v_sep.append(elevator.X[3, 0])
+    if observer_elevator is not None:
+      observer_elevator.PredictObserver(U)
+    elevator.Update(U)
+    if observer_elevator is not None:
+      observer_elevator.Y = elevator.Y
+      observer_elevator.CorrectObserver(U)
+
+    t.append(i * elevator.dt)
+    u_left.append(U[0, 0])
+    u_right.append(U[1, 0])
+
+  print numpy.linalg.inv(elevator.A)
+  print "delta time is ", elevator.dt
+  print "Velocity at t=0 is ", x_avg[0], v_avg[0], x_sep[0], v_sep[0]
+  print "Velocity at t=1+dt is ", x_avg[1], v_avg[1], x_sep[1], v_sep[1]
+
+  if show_graph:
+    pylab.subplot(2, 1, 1)
+    pylab.plot(t, x_avg, label='x avg')
+    pylab.plot(t, x_sep, label='x sep')
+    if observer_elevator is not None:
+      pylab.plot(t, x_hat_avg, label='x_hat avg')
+      pylab.plot(t, x_hat_sep, label='x_hat sep')
+    pylab.legend()
+
+    pylab.subplot(2, 1, 2)
+    pylab.plot(t, u_left, label='u left')
+    pylab.plot(t, u_right, label='u right')
+    pylab.legend()
+    pylab.show()
+
+
+def main(argv):
+  loaded_mass = 25
+  #loaded_mass = 0
+  elevator = Elevator(mass=13 + loaded_mass)
+  elevator_controller = Elevator(mass=13 + 15)
+  observer_elevator = Elevator(mass=13 + 15)
+  #observer_elevator = None
+
+  # Test moving the elevator with constant separation.
+  initial_X = numpy.matrix([[0.0], [0.0], [0.01], [0.0]])
+  #initial_X = numpy.matrix([[0.0], [0.0], [0.00], [0.0]])
+  R = numpy.matrix([[1.0], [0.0], [0.0], [0.0]])
+  run_test(elevator, initial_X, R, controller_elevator=elevator_controller,
+           observer_elevator=observer_elevator)
+
+  # Write the generated constants out to a file.
+  if len(argv) != 3:
+    print "Expected .h file name and .cc file name for the elevator."
+  else:
+    elevator = Elevator("Elevator")
+    loop_writer = control_loop.ControlLoopWriter("Elevator", [elevator])
+    if argv[1][-3:] == '.cc':
+      loop_writer.Write(argv[2], argv[1])
+    else:
+      loop_writer.Write(argv[1], argv[2])
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/y2014/control_loops/python/polydrivetrain.py b/y2014/control_loops/python/polydrivetrain.py
new file mode 100755
index 0000000..a2c63fa
--- /dev/null
+++ b/y2014/control_loops/python/polydrivetrain.py
@@ -0,0 +1,503 @@
+#!/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.
+  """
+  return DoCoerceGoal(region, K, w, R)[0]
+
+def DoCoerceGoal(region, K, w, R):
+  if region.IsInside(R):
+    return (R, True)
+
+  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, True)
+  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, False)
+
+
+class VelocityDrivetrainModel(control_loop.ControlLoop):
+  def __init__(self, left_low=True, right_low=True, name="VelocityDrivetrainModel"):
+    super(VelocityDrivetrainModel, self).__init__(name)
+    self._drivetrain = drivetrain.Drivetrain(left_low=left_low,
+                                             right_low=right_low)
+    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):
+    self.drivetrain_low_low = VelocityDrivetrainModel(
+        left_low=True, right_low=True, name='VelocityDrivetrainLowLow')
+    self.drivetrain_low_high = VelocityDrivetrainModel(left_low=True, right_low=False, name='VelocityDrivetrainLowHigh')
+    self.drivetrain_high_low = VelocityDrivetrainModel(left_low=False, right_low=True, name = 'VelocityDrivetrainHighLow')
+    self.drivetrain_high_high = VelocityDrivetrainModel(left_low=False, right_low=False, name = 'VelocityDrivetrainHighHigh')
+
+    # 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.right_gear = True
+    if True:
+      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.
+      steering_velocity = numpy.abs(fvel) * steering
+      left_velocity = fvel - steering_velocity
+      right_velocity = fvel + steering_velocity
+
+      # 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):
+  vdrivetrain = VelocityDrivetrain()
+
+  if len(argv) != 7:
+    print "Expected .h file name and .cc file name"
+  else:
+    dog_loop_writer = control_loop.ControlLoopWriter(
+        "VelocityDrivetrain", [vdrivetrain.drivetrain_low_low,
+                       vdrivetrain.drivetrain_low_high,
+                       vdrivetrain.drivetrain_high_low,
+                       vdrivetrain.drivetrain_high_high])
+
+    if argv[1][-3:] == '.cc':
+      dog_loop_writer.Write(argv[2], argv[1])
+    else:
+      dog_loop_writer.Write(argv[1], argv[2])
+
+    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, 1.7, vdrivetrain.dt):
+    if t < 0.5:
+      vdrivetrain.Update(throttle=0.00, steering=1.0)
+    elif t < 1.2:
+      vdrivetrain.Update(throttle=0.5, steering=1.0)
+    else:
+      vdrivetrain.Update(throttle=0.00, steering=1.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/y2014/control_loops/python/polydrivetrain_test.py b/y2014/control_loops/python/polydrivetrain_test.py
new file mode 100755
index 0000000..434cdca
--- /dev/null
+++ b/y2014/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/y2014/control_loops/python/shooter.py b/y2014/control_loops/python/shooter.py
new file mode 100755
index 0000000..69f2599
--- /dev/null
+++ b/y2014/control_loops/python/shooter.py
@@ -0,0 +1,254 @@
+#!/usr/bin/python
+
+import control_loop
+import numpy
+import sys
+from matplotlib import pylab
+
+class SprungShooter(control_loop.ControlLoop):
+  def __init__(self, name="RawSprungShooter"):
+    super(SprungShooter, self).__init__(name)
+    # Stall Torque in N m
+    self.stall_torque = .4982
+    # Stall Current in Amps
+    self.stall_current = 85
+    # Free Speed in RPM
+    self.free_speed = 19300.0
+    # Free Current in Amps
+    self.free_current = 1.2
+    # Effective mass of the shooter in kg.
+    # This rough estimate should about include the effect of the masses
+    # of the gears. If this number is too low, the eigen values of self.A
+    # will start to become extremely small.
+    self.J = 200
+    # Resistance of the motor, divided by the number of motors.
+    self.R = 12.0 / self.stall_current / 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
+    # Spring constant for the springs, N/m
+    self.Ks = 2800.0
+    # Maximum extension distance (Distance from the 0 force point on the
+    # spring to the latch position.)
+    self.max_extension = 0.32385
+    # Gear ratio multiplied by radius of final sprocket.
+    self.G = 10.0 / 40.0 * 20.0 / 54.0 * 24.0 / 54.0 * 20.0 / 84.0 * 16.0 * (3.0 / 8.0) / (2.0 * numpy.pi) * 0.0254
+
+    # Control loop time step
+    self.dt = 0.01
+
+    # State feedback matrices
+    self.A_continuous = numpy.matrix(
+        [[0, 1],
+         [-self.Ks / self.J,
+          -self.Kt / self.Kv / (self.J * self.G * self.G * self.R)]])
+    self.B_continuous = numpy.matrix(
+        [[0],
+         [self.Kt / (self.J * self.G * self.R)]])
+    self.C = numpy.matrix([[1, 0]])
+    self.D = numpy.matrix([[0]])
+
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    self.PlaceControllerPoles([0.45, 0.45])
+
+    self.rpl = .05
+    self.ipl = 0.008
+    self.PlaceObserverPoles([self.rpl,
+                             self.rpl])
+
+    self.U_max = numpy.matrix([[12.0]])
+    self.U_min = numpy.matrix([[-12.0]])
+
+    self.InitializeState()
+
+
+class Shooter(SprungShooter):
+  def __init__(self, name="RawShooter"):
+    super(Shooter, self).__init__(name)
+
+    # State feedback matrices
+    self.A_continuous = numpy.matrix(
+        [[0, 1],
+         [0, -self.Kt / self.Kv / (self.J * self.G * self.G * self.R)]])
+    self.B_continuous = numpy.matrix(
+        [[0],
+         [self.Kt / (self.J * self.G * self.R)]])
+
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    self.PlaceControllerPoles([0.45, 0.45])
+
+    self.rpl = .05
+    self.ipl = 0.008
+    self.PlaceObserverPoles([self.rpl,
+                             self.rpl])
+
+    self.U_max = numpy.matrix([[12.0]])
+    self.U_min = numpy.matrix([[-12.0]])
+
+    self.InitializeState()
+
+
+class SprungShooterDeltaU(SprungShooter):
+  def __init__(self, name="SprungShooter"):
+    super(SprungShooterDeltaU, self).__init__(name)
+    A_unaugmented = self.A
+    B_unaugmented = self.B
+
+    self.A = numpy.matrix([[0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0],
+                           [0.0, 0.0, 1.0]])
+    self.A[0:2, 0:2] = A_unaugmented
+    self.A[0:2, 2] = B_unaugmented
+
+    self.B = numpy.matrix([[0.0],
+                           [0.0],
+                           [1.0]])
+
+    self.C = numpy.matrix([[1.0, 0.0, 0.0]])
+    self.D = numpy.matrix([[0.0]])
+
+    self.PlaceControllerPoles([0.50, 0.35, 0.80])
+
+    print "K"
+    print self.K
+    print "Placed controller poles are"
+    print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+    self.rpl = .05
+    self.ipl = 0.008
+    self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+                             self.rpl - 1j * self.ipl, 0.90])
+    print "Placed observer poles are"
+    print numpy.linalg.eig(self.A - self.L * self.C)[0]
+
+    self.U_max = numpy.matrix([[12.0]])
+    self.U_min = numpy.matrix([[-12.0]])
+
+    self.InitializeState()
+
+
+class ShooterDeltaU(Shooter):
+  def __init__(self, name="Shooter"):
+    super(ShooterDeltaU, self).__init__(name)
+    A_unaugmented = self.A
+    B_unaugmented = self.B
+
+    self.A = numpy.matrix([[0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0],
+                           [0.0, 0.0, 1.0]])
+    self.A[0:2, 0:2] = A_unaugmented
+    self.A[0:2, 2] = B_unaugmented
+
+    self.B = numpy.matrix([[0.0],
+                           [0.0],
+                           [1.0]])
+
+    self.C = numpy.matrix([[1.0, 0.0, 0.0]])
+    self.D = numpy.matrix([[0.0]])
+
+    self.PlaceControllerPoles([0.55, 0.45, 0.80])
+
+    print "K"
+    print self.K
+    print "Placed controller poles are"
+    print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+    self.rpl = .05
+    self.ipl = 0.008
+    self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+                             self.rpl - 1j * self.ipl, 0.90])
+    print "Placed observer poles are"
+    print numpy.linalg.eig(self.A - self.L * self.C)[0]
+
+    self.U_max = numpy.matrix([[12.0]])
+    self.U_min = numpy.matrix([[-12.0]])
+
+    self.InitializeState()
+
+
+def ClipDeltaU(shooter, old_voltage, delta_u):
+  old_u = old_voltage
+  new_u = numpy.clip(old_u + delta_u, shooter.U_min, shooter.U_max)
+  return new_u - old_u
+
+def main(argv):
+  # Simulate the response of the system to a goal.
+  sprung_shooter = SprungShooterDeltaU()
+  raw_sprung_shooter = SprungShooter()
+  close_loop_x = []
+  close_loop_u = []
+  goal_position = -0.3
+  R = numpy.matrix([[goal_position], [0.0], [-sprung_shooter.A[1, 0] / sprung_shooter.A[1, 2] * goal_position]])
+  voltage = numpy.matrix([[0.0]])
+  for _ in xrange(500):
+    U = sprung_shooter.K * (R - sprung_shooter.X_hat)
+    U = ClipDeltaU(sprung_shooter, voltage, U)
+    sprung_shooter.Y = raw_sprung_shooter.Y + 0.01
+    sprung_shooter.UpdateObserver(U)
+    voltage += U;
+    raw_sprung_shooter.Update(voltage)
+    close_loop_x.append(raw_sprung_shooter.X[0, 0] * 10)
+    close_loop_u.append(voltage[0, 0])
+
+  pylab.plot(range(500), close_loop_x)
+  pylab.plot(range(500), close_loop_u)
+  pylab.show()
+
+  shooter = ShooterDeltaU()
+  raw_shooter = Shooter()
+  close_loop_x = []
+  close_loop_u = []
+  goal_position = -0.3
+  R = numpy.matrix([[goal_position], [0.0], [-shooter.A[1, 0] / shooter.A[1, 2] * goal_position]])
+  voltage = numpy.matrix([[0.0]])
+  for _ in xrange(500):
+    U = shooter.K * (R - shooter.X_hat)
+    U = ClipDeltaU(shooter, voltage, U)
+    shooter.Y = raw_shooter.Y + 0.01
+    shooter.UpdateObserver(U)
+    voltage += U;
+    raw_shooter.Update(voltage)
+    close_loop_x.append(raw_shooter.X[0, 0] * 10)
+    close_loop_u.append(voltage[0, 0])
+
+  pylab.plot(range(500), close_loop_x)
+  pylab.plot(range(500), close_loop_u)
+  pylab.show()
+
+  # Write the generated constants out to a file.
+  if len(argv) != 5:
+    print "Expected .h file name and .cc file name for"
+    print "both the plant and unaugmented plant"
+  else:
+    unaug_sprung_shooter = SprungShooter("RawSprungShooter")
+    unaug_shooter = Shooter("RawShooter")
+    unaug_loop_writer = control_loop.ControlLoopWriter("RawShooter",
+                                                       [unaug_sprung_shooter,
+                                                        unaug_shooter])
+    if argv[3][-3:] == '.cc':
+      unaug_loop_writer.Write(argv[4], argv[3])
+    else:
+      unaug_loop_writer.Write(argv[3], argv[4])
+
+    sprung_shooter = SprungShooterDeltaU()
+    shooter = ShooterDeltaU()
+    loop_writer = control_loop.ControlLoopWriter("Shooter", [sprung_shooter,
+                                                             shooter])
+
+    loop_writer.AddConstant(control_loop.Constant("kMaxExtension", "%f",
+                                                  sprung_shooter.max_extension))
+    loop_writer.AddConstant(control_loop.Constant("kSpringConstant", "%f",
+                                                  sprung_shooter.Ks))
+    if argv[1][-3:] == '.cc':
+      loop_writer.Write(argv[2], argv[1])
+    else:
+      loop_writer.Write(argv[1], argv[2])
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/y2014/control_loops/shooter/replay_shooter.cc b/y2014/control_loops/shooter/replay_shooter.cc
new file mode 100644
index 0000000..20c953f
--- /dev/null
+++ b/y2014/control_loops/shooter/replay_shooter.cc
@@ -0,0 +1,24 @@
+#include "aos/common/controls/replay_control_loop.h"
+#include "aos/linux_code/init.h"
+
+#include "y2014/control_loops/shooter/shooter.q.h"
+
+// Reads one or more log files and sends out all the queue messages (in the
+// correct order and at the correct time) to feed a "live" shooter process.
+
+int main(int argc, char **argv) {
+  if (argc <= 1) {
+    fprintf(stderr, "Need at least one file to replay!\n");
+    return EXIT_FAILURE;
+  }
+
+  ::aos::InitNRT();
+
+  ::aos::controls::ControlLoopReplayer<::frc971::control_loops::ShooterQueue>
+      replayer(&::frc971::control_loops::shooter_queue, "shooter");
+  for (int i = 1; i < argc; ++i) {
+    replayer.ProcessFile(argv[i]);
+  }
+
+  ::aos::Cleanup();
+}
diff --git a/y2014/control_loops/shooter/shooter.cc b/y2014/control_loops/shooter/shooter.cc
new file mode 100644
index 0000000..f137235
--- /dev/null
+++ b/y2014/control_loops/shooter/shooter.cc
@@ -0,0 +1,695 @@
+#include "y2014/control_loops/shooter/shooter.h"
+
+#include <stdio.h>
+
+#include <algorithm>
+#include <limits>
+
+#include "aos/common/controls/control_loops.q.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/logging/queue_logging.h"
+
+#include "y2014/constants.h"
+#include "y2014/control_loops/shooter/shooter_motor_plant.h"
+
+namespace frc971 {
+namespace control_loops {
+
+using ::aos::time::Time;
+
+void ZeroedStateFeedbackLoop::CapU() {
+  const double old_voltage = voltage_;
+  voltage_ += U(0, 0);
+
+  uncapped_voltage_ = voltage_;
+
+  // Make sure that reality and the observer can't get too far off.  There is a
+  // delay by one cycle between the applied voltage and X_hat(2, 0), so compare
+  // against last cycle's voltage.
+  if (X_hat(2, 0) > last_voltage_ + 4.0) {
+    voltage_ -= X_hat(2, 0) - (last_voltage_ + 4.0);
+    LOG(DEBUG, "Capping due to runaway\n");
+  } else if (X_hat(2, 0) < last_voltage_ - 4.0) {
+    voltage_ += X_hat(2, 0) - (last_voltage_ - 4.0);
+    LOG(DEBUG, "Capping due to runaway\n");
+  }
+
+  voltage_ = std::min(max_voltage_, voltage_);
+  voltage_ = std::max(-max_voltage_, voltage_);
+  mutable_U(0, 0) = voltage_ - old_voltage;
+
+  LOG_STRUCT(DEBUG, "output", ShooterVoltageToLog(X_hat(2, 0), voltage_));
+
+  last_voltage_ = voltage_;
+  capped_goal_ = false;
+}
+
+void ZeroedStateFeedbackLoop::CapGoal() {
+  if (uncapped_voltage() > max_voltage_) {
+    double dx;
+    if (controller_index() == 0) {
+      dx = (uncapped_voltage() - max_voltage_) /
+           (K(0, 0) - A(1, 0) * K(0, 2) / A(1, 2));
+      mutable_R(0, 0) -= dx;
+      mutable_R(2, 0) -= -A(1, 0) / A(1, 2) * dx;
+    } else {
+      dx = (uncapped_voltage() - max_voltage_) / K(0, 0);
+      mutable_R(0, 0) -= dx;
+    }
+    capped_goal_ = true;
+    LOG_STRUCT(DEBUG, "to prevent windup", ShooterMovingGoal(dx));
+  } else if (uncapped_voltage() < -max_voltage_) {
+    double dx;
+    if (controller_index() == 0) {
+      dx = (uncapped_voltage() + max_voltage_) /
+           (K(0, 0) - A(1, 0) * K(0, 2) / A(1, 2));
+      mutable_R(0, 0) -= dx;
+      mutable_R(2, 0) -= -A(1, 0) / A(1, 2) * dx;
+    } else {
+      dx = (uncapped_voltage() + max_voltage_) / K(0, 0);
+      mutable_R(0, 0) -= dx;
+    }
+    capped_goal_ = true;
+    LOG_STRUCT(DEBUG, "to prevent windup", ShooterMovingGoal(dx));
+  } else {
+    capped_goal_ = false;
+  }
+}
+
+void ZeroedStateFeedbackLoop::RecalculatePowerGoal() {
+  if (controller_index() == 0) {
+    mutable_R(2, 0) = (-A(1, 0) / A(1, 2) * R(0, 0) - A(1, 1) / A(1, 2) * R(1, 0));
+  } else {
+    mutable_R(2, 0) = -A(1, 1) / A(1, 2) * R(1, 0);
+  }
+}
+
+void ZeroedStateFeedbackLoop::SetCalibration(double encoder_val,
+                                             double known_position) {
+  double old_position = absolute_position();
+  double previous_offset = offset_;
+  offset_ = known_position - encoder_val;
+  double doffset = offset_ - previous_offset;
+  mutable_X_hat(0, 0) += doffset;
+  // Offset our measurements because the offset is baked into them.
+  // This is safe because if we got here, it means position != nullptr, which
+  // means we already set Y to something and it won't just get overwritten.
+  mutable_Y(0, 0) += doffset;
+  // Offset the goal so we don't move.
+  mutable_R(0, 0) += doffset;
+  if (controller_index() == 0) {
+    mutable_R(2, 0) += -A(1, 0) / A(1, 2) * (doffset);
+  }
+  LOG_STRUCT(
+      DEBUG, "sensor edge (fake?)",
+      ShooterChangeCalibration(encoder_val, known_position, old_position,
+                               absolute_position(), previous_offset, offset_));
+}
+
+ShooterMotor::ShooterMotor(control_loops::ShooterGroup *my_shooter)
+    : aos::controls::ControlLoop<control_loops::ShooterGroup>(my_shooter),
+      shooter_(MakeShooterLoop()),
+      state_(STATE_INITIALIZE),
+      loading_problem_end_time_(0, 0),
+      load_timeout_(0, 0),
+      shooter_brake_set_time_(0, 0),
+      unload_timeout_(0, 0),
+      shot_end_time_(0, 0),
+      cycles_not_moved_(0),
+      shot_count_(0),
+      zeroed_(false),
+      distal_posedge_validation_cycles_left_(0),
+      proximal_posedge_validation_cycles_left_(0),
+      last_distal_current_(true),
+      last_proximal_current_(true) {}
+
+double ShooterMotor::PowerToPosition(double power) {
+  const frc971::constants::Values &values = constants::GetValues();
+  double maxpower = 0.5 * kSpringConstant *
+                    (kMaxExtension * kMaxExtension -
+                     (kMaxExtension - values.shooter.upper_limit) *
+                         (kMaxExtension - values.shooter.upper_limit));
+  if (power < 0) {
+    LOG_STRUCT(WARNING, "negative power", PowerAdjustment(power, 0));
+    power = 0;
+  } else if (power > maxpower) {
+    LOG_STRUCT(WARNING, "power too high", PowerAdjustment(power, maxpower));
+    power = maxpower;
+  }
+
+  double mp = kMaxExtension * kMaxExtension - (power + power) / kSpringConstant;
+  double new_pos = 0.10;
+  if (mp < 0) {
+    LOG(ERROR,
+        "Power calculation has negative number before square root (%f).\n", mp);
+  } else {
+    new_pos = kMaxExtension - ::std::sqrt(mp);
+  }
+
+  new_pos = ::std::min(::std::max(new_pos, values.shooter.lower_limit),
+                              values.shooter.upper_limit);
+  return new_pos;
+}
+
+double ShooterMotor::PositionToPower(double position) {
+  double power = kSpringConstant * position * (kMaxExtension - position / 2.0);
+  return power;
+}
+
+void ShooterMotor::CheckCalibrations(
+    const control_loops::ShooterGroup::Position *position) {
+  CHECK_NOTNULL(position);
+  const frc971::constants::Values &values = constants::GetValues();
+
+  // TODO(austin): Validate that this is the right edge.
+  // If we see a posedge on any of the hall effects,
+  if (position->pusher_proximal.posedge_count != last_proximal_posedge_count_ &&
+      !last_proximal_current_) {
+    proximal_posedge_validation_cycles_left_ = 2;
+  }
+  if (proximal_posedge_validation_cycles_left_ > 0) {
+    if (position->pusher_proximal.current) {
+      --proximal_posedge_validation_cycles_left_;
+      if (proximal_posedge_validation_cycles_left_ == 0) {
+        shooter_.SetCalibration(
+            position->pusher_proximal.posedge_value,
+            values.shooter.pusher_proximal.upper_angle);
+
+        LOG(DEBUG, "Setting calibration using proximal sensor\n");
+        zeroed_ = true;
+      }
+    } else {
+      proximal_posedge_validation_cycles_left_ = 0;
+    }
+  }
+
+  if (position->pusher_distal.posedge_count != last_distal_posedge_count_ &&
+      !last_distal_current_) {
+    distal_posedge_validation_cycles_left_ = 2;
+  }
+  if (distal_posedge_validation_cycles_left_ > 0) {
+    if (position->pusher_distal.current) {
+      --distal_posedge_validation_cycles_left_;
+      if (distal_posedge_validation_cycles_left_ == 0) {
+        shooter_.SetCalibration(
+            position->pusher_distal.posedge_value,
+            values.shooter.pusher_distal.upper_angle);
+
+        LOG(DEBUG, "Setting calibration using distal sensor\n");
+        zeroed_ = true;
+      }
+    } else {
+      distal_posedge_validation_cycles_left_ = 0;
+    }
+  }
+}
+
+// Positive is out, and positive power is out.
+void ShooterMotor::RunIteration(
+    const control_loops::ShooterGroup::Goal *goal,
+    const control_loops::ShooterGroup::Position *position,
+    control_loops::ShooterGroup::Output *output,
+    control_loops::ShooterGroup::Status *status) {
+  constexpr double dt = 0.01;
+
+  if (goal && ::std::isnan(goal->shot_power)) {
+	  state_ = STATE_ESTOP;
+    LOG(ERROR, "Estopping because got a shot power of NAN.\n");
+  }
+
+  // we must always have these or we have issues.
+  if (status == NULL) {
+    if (output) output->voltage = 0;
+    LOG(ERROR, "Thought I would just check for null and die.\n");
+    return;
+  }
+  status->ready = false;
+
+  if (WasReset()) {
+    state_ = STATE_INITIALIZE;
+    last_distal_current_ = position->pusher_distal.current;
+    last_proximal_current_ = position->pusher_proximal.current;
+  }
+  if (position) {
+    shooter_.CorrectPosition(position->position);
+  }
+
+  // Disable the motors now so that all early returns will return with the
+  // motors disabled.
+  if (output) output->voltage = 0;
+
+  const frc971::constants::Values &values = constants::GetValues();
+
+  // Don't even let the control loops run.
+  bool shooter_loop_disable = false;
+
+  const bool disabled =
+      !::aos::joystick_state.get() || !::aos::joystick_state->enabled;
+
+  // If true, move the goal if we saturate.
+  bool cap_goal = false;
+
+  // TODO(austin): Move the offset if we see or don't see a hall effect when we
+  // expect to see one.
+  // Probably not needed yet.
+
+  if (position) {
+    int last_controller_index = shooter_.controller_index();
+    if (position->plunger && position->latch) {
+      // Use the controller without the spring if the latch is set and the
+      // plunger is back
+      shooter_.set_controller_index(1);
+    } else {
+      // Otherwise use the controller with the spring.
+      shooter_.set_controller_index(0);
+    }
+    if (shooter_.controller_index() != last_controller_index) {
+      shooter_.RecalculatePowerGoal();
+    }
+  }
+
+  switch (state_) {
+    case STATE_INITIALIZE:
+      if (position) {
+        // Reinitialize the internal filter state.
+        shooter_.InitializeState(position->position);
+
+        // Start off with the assumption that we are at the value
+        // futhest back given our sensors.
+        if (position->pusher_distal.current) {
+          shooter_.SetCalibration(position->position,
+                                  values.shooter.pusher_distal.lower_angle);
+        } else if (position->pusher_proximal.current) {
+          shooter_.SetCalibration(position->position,
+                                  values.shooter.pusher_proximal.upper_angle);
+        } else {
+          shooter_.SetCalibration(position->position,
+                                  values.shooter.upper_limit);
+        }
+
+        // Go to the current position.
+        shooter_.SetGoalPosition(shooter_.absolute_position(), 0.0);
+        // If the plunger is all the way back, we want to be latched.
+        latch_piston_ = position->plunger;
+        brake_piston_ = false;
+        if (position->latch == latch_piston_) {
+          state_ = STATE_REQUEST_LOAD;
+        } else {
+          shooter_loop_disable = true;
+          LOG(DEBUG,
+              "Not moving on until the latch has moved to avoid a crash\n");
+        }
+      } else {
+        // If we can't start yet because we don't know where we are, set the
+        // latch and brake to their defaults.
+        latch_piston_ = true;
+        brake_piston_ = true;
+      }
+      break;
+    case STATE_REQUEST_LOAD:
+      if (position) {
+        zeroed_ = false;
+        if (position->pusher_distal.current ||
+            position->pusher_proximal.current) {
+          // We started on the sensor, back up until we are found.
+          // If the plunger is all the way back and not latched, it won't be
+          // there for long.
+          state_ = STATE_LOAD_BACKTRACK;
+
+          // The plunger is already back and latched.  Don't release it.
+          if (position->plunger && position->latch) {
+            latch_piston_ = true;
+          } else {
+            latch_piston_ = false;
+          }
+        } else if (position->plunger && position->latch) {
+          // The plunger is back and we are latched.  We most likely got here
+          // from Initialize, in which case we want to 'load' again anyways to
+          // zero.
+          Load();
+          latch_piston_ = true;
+        } else {
+          // Off the sensor, start loading.
+          Load();
+          latch_piston_ = false;
+        }
+      }
+
+      // Hold our current position.
+      shooter_.SetGoalPosition(shooter_.absolute_position(), 0.0);
+      brake_piston_ = false;
+      break;
+    case STATE_LOAD_BACKTRACK:
+      // If we are here, then that means we started past the edge where we want
+      // to zero.  Move backwards until we don't see the sensor anymore.
+      // The plunger is contacting the pusher (or will be shortly).
+
+      if (!disabled) {
+        shooter_.SetGoalPosition(
+            shooter_.goal_position() + values.shooter.zeroing_speed * dt,
+            values.shooter.zeroing_speed);
+      }
+      cap_goal = true;
+      shooter_.set_max_voltage(4.0);
+
+      if (position) {
+        if (!position->pusher_distal.current &&
+            !position->pusher_proximal.current) {
+          Load();
+        }
+        latch_piston_ = position->plunger;
+      }
+
+      brake_piston_ = false;
+      break;
+    case STATE_LOAD:
+      // If we are disabled right now, reset the timer.
+      if (disabled) {
+        Load();
+        // Latch defaults to true when disabled.  Leave it latched until we have
+        // useful sensor data.
+        latch_piston_ = true;
+      }
+      if (output == nullptr) {
+        load_timeout_ += ::aos::controls::kLoopFrequency;
+      }
+      // Go to 0, which should be the latch position, or trigger a hall effect
+      // on the way.  If we don't see edges where we are supposed to, the
+      // offset will be updated by code above.
+      shooter_.SetGoalPosition(0.0, 0.0);
+
+      if (position) {
+        CheckCalibrations(position);
+
+        // Latch if the plunger is far enough back to trigger the hall effect.
+        // This happens when the distal sensor is triggered.
+        latch_piston_ = position->pusher_distal.current || position->plunger;
+
+        // Check if we are latched and back.  Make sure the plunger is all the
+        // way back as well.
+        if (position->plunger && position->latch &&
+            position->pusher_distal.current) {
+          if (!zeroed_) {
+            state_ = STATE_REQUEST_LOAD;
+          } else {
+            state_ = STATE_PREPARE_SHOT;
+          }
+        } else if (position->plunger &&
+                   ::std::abs(shooter_.absolute_position() -
+                              shooter_.goal_position()) < 0.001) {
+          // We are at the goal, but not latched.
+          state_ = STATE_LOADING_PROBLEM;
+          loading_problem_end_time_ = Time::Now() + kLoadProblemEndTimeout;
+        }
+      }
+      if (load_timeout_ < Time::Now()) {
+        if (position) {
+          if (!position->pusher_distal.current ||
+              !position->pusher_proximal.current) {
+            state_ = STATE_ESTOP;
+            LOG(ERROR, "Estopping because took too long to load.\n");
+          }
+        }
+      }
+      brake_piston_ = false;
+      break;
+    case STATE_LOADING_PROBLEM:
+      if (disabled) {
+        state_ = STATE_REQUEST_LOAD;
+        break;
+      }
+      // We got to the goal, but the latch hasn't registered as down.  It might
+      // be stuck, or on it's way but not there yet.
+      if (Time::Now() > loading_problem_end_time_) {
+        // Timeout by unloading.
+        Unload();
+      } else if (position && position->plunger && position->latch) {
+        // If both trigger, we are latched.
+        state_ = STATE_PREPARE_SHOT;
+      }
+      // Move a bit further back to help it trigger.
+      // If the latch is slow due to the air flowing through the tubes or
+      // inertia, but is otherwise free, this won't have much time to do
+      // anything and is safe.  Otherwise this gives us a bit more room to free
+      // up the latch.
+      shooter_.SetGoalPosition(values.shooter.lower_limit, 0.0);
+      if (position) {
+        LOG(DEBUG, "Waiting on latch: plunger %d, latch: %d\n",
+            position->plunger, position->latch);
+      }
+
+      latch_piston_ = true;
+      brake_piston_ = false;
+      break;
+    case STATE_PREPARE_SHOT:
+      // Move the shooter to the shot power set point and then lock the brake.
+      // TODO(austin): Timeout.  Low priority.
+
+      if (goal) {
+        shooter_.SetGoalPosition(PowerToPosition(goal->shot_power), 0.0);
+      }
+
+      LOG(DEBUG, "PDIFF: absolute_position: %.2f, pow: %.2f\n",
+          shooter_.absolute_position(),
+          goal ? PowerToPosition(goal->shot_power)
+               : ::std::numeric_limits<double>::quiet_NaN());
+      if (goal &&
+          ::std::abs(shooter_.absolute_position() -
+                     PowerToPosition(goal->shot_power)) < 0.001 &&
+          ::std::abs(shooter_.absolute_velocity()) < 0.005) {
+        // We are there, set the brake and move on.
+        latch_piston_ = true;
+        brake_piston_ = true;
+        shooter_brake_set_time_ = Time::Now() + kShooterBrakeSetTime;
+        state_ = STATE_READY;
+      } else {
+        latch_piston_ = true;
+        brake_piston_ = false;
+      }
+      if (goal && goal->unload_requested) {
+        Unload();
+      }
+      break;
+    case STATE_READY:
+      LOG(DEBUG, "In ready\n");
+      // Wait until the brake is set, and a shot is requested or the shot power
+      // is changed.
+      if (Time::Now() > shooter_brake_set_time_) {
+        status->ready = true;
+        // We have waited long enough for the brake to set, turn the shooter
+        // control loop off.
+        shooter_loop_disable = true;
+        LOG(DEBUG, "Brake is now set\n");
+        if (goal && goal->shot_requested && !disabled) {
+          LOG(DEBUG, "Shooting now\n");
+          shooter_loop_disable = true;
+          shot_end_time_ = Time::Now() + kShotEndTimeout;
+          firing_starting_position_ = shooter_.absolute_position();
+          state_ = STATE_FIRE;
+        }
+      }
+      if (state_ == STATE_READY && goal &&
+          ::std::abs(shooter_.absolute_position() -
+                     PowerToPosition(goal->shot_power)) > 0.002) {
+        // TODO(austin): Add a state to release the brake.
+
+        // TODO(austin): Do we want to set the brake here or after shooting?
+        // Depends on air usage.
+        status->ready = false;
+        LOG(DEBUG, "Preparing shot again.\n");
+        state_ = STATE_PREPARE_SHOT;
+      }
+
+      if (goal) {
+        shooter_.SetGoalPosition(PowerToPosition(goal->shot_power), 0.0);
+      }
+
+      latch_piston_ = true;
+      brake_piston_ = true;
+
+      if (goal && goal->unload_requested) {
+        Unload();
+      }
+      break;
+
+    case STATE_FIRE:
+      if (disabled) {
+        if (position) {
+          if (position->plunger) {
+            // If disabled and the plunger is still back there, reset the
+            // timeout.
+            shot_end_time_ = Time::Now() + kShotEndTimeout;
+          }
+        }
+      }
+      shooter_loop_disable = true;
+      // Count the number of contiguous cycles during which we haven't moved.
+      if (::std::abs(last_position_.position - shooter_.absolute_position()) <
+          0.0005) {
+        ++cycles_not_moved_;
+      } else {
+        cycles_not_moved_ = 0;
+      }
+
+      // If we have moved any amount since the start and the shooter has now
+      // been still for a couple cycles, the shot finished.
+      // Also move on if it times out.
+      if ((::std::abs(firing_starting_position_ -
+                      shooter_.absolute_position()) > 0.0005 &&
+           cycles_not_moved_ > 3) ||
+          Time::Now() > shot_end_time_) {
+        state_ = STATE_REQUEST_LOAD;
+        ++shot_count_;
+      }
+      latch_piston_ = false;
+      brake_piston_ = true;
+      break;
+    case STATE_UNLOAD:
+      // Reset the timeouts.
+      if (disabled) Unload();
+
+      // If it is latched and the plunger is back, move the pusher back to catch
+      // the plunger.
+      bool all_back;
+      if (position) {
+        all_back = position->plunger && position->latch;
+      } else {
+        all_back = last_position_.plunger && last_position_.latch;
+      }
+
+      if (all_back) {
+        // Pull back to 0, 0.
+        shooter_.SetGoalPosition(0.0, 0.0);
+        if (shooter_.absolute_position() < 0.005) {
+          // When we are close enough, 'fire'.
+          latch_piston_ = false;
+        } else {
+          latch_piston_ = true;
+
+          if (position) {
+            CheckCalibrations(position);
+          }
+        }
+      } else {
+        // The plunger isn't all the way back, or it is and it is unlatched, so
+        // we can now unload.
+        shooter_.SetGoalPosition(shooter_.absolute_position(), 0.0);
+        latch_piston_ = false;
+        state_ = STATE_UNLOAD_MOVE;
+        unload_timeout_ = Time::Now() + kUnloadTimeout;
+      }
+
+      if (Time::Now() > unload_timeout_) {
+        // We have been stuck trying to unload for way too long, give up and
+        // turn everything off.
+        state_ = STATE_ESTOP;
+        LOG(ERROR, "Estopping because took too long to unload.\n");
+      }
+
+      brake_piston_ = false;
+      break;
+    case STATE_UNLOAD_MOVE: {
+      if (disabled) {
+        unload_timeout_ = Time::Now() + kUnloadTimeout;
+        shooter_.SetGoalPosition(shooter_.absolute_position(), 0.0);
+      }
+      cap_goal = true;
+      shooter_.set_max_voltage(6.0);
+
+      // Slowly move back until we hit the upper limit.
+      // If we were at the limit last cycle, we are done unloading.
+      // This is because if we saturate, we might hit the limit before we are
+      // actually there.
+      if (shooter_.goal_position() >= values.shooter.upper_limit) {
+        shooter_.SetGoalPosition(values.shooter.upper_limit, 0.0);
+        // We don't want the loop fighting the spring when we are unloaded.
+        // Turn it off.
+        shooter_loop_disable = true;
+        state_ = STATE_READY_UNLOAD;
+      } else {
+        shooter_.SetGoalPosition(
+            ::std::min(
+                values.shooter.upper_limit,
+                shooter_.goal_position() + values.shooter.unload_speed * dt),
+            values.shooter.unload_speed);
+      }
+
+      latch_piston_ = false;
+      brake_piston_ = false;
+    } break;
+    case STATE_READY_UNLOAD:
+      if (goal && goal->load_requested) {
+        state_ = STATE_REQUEST_LOAD;
+      }
+      // If we are ready to load again,
+      shooter_loop_disable = true;
+
+      latch_piston_ = false;
+      brake_piston_ = false;
+      break;
+
+    case STATE_ESTOP:
+      LOG(WARNING, "estopped\n");
+      // Totally lost, go to a safe state.
+      shooter_loop_disable = true;
+      latch_piston_ = true;
+      brake_piston_ = true;
+      break;
+  }
+
+  if (!shooter_loop_disable) {
+    LOG_STRUCT(DEBUG, "running the loop",
+               ShooterStatusToLog(shooter_.goal_position(),
+                                  shooter_.absolute_position()));
+    if (!cap_goal) {
+      shooter_.set_max_voltage(12.0);
+    }
+    shooter_.Update(output == NULL);
+    if (cap_goal) {
+      shooter_.CapGoal();
+    }
+    // We don't really want to output anything if we went through everything
+    // assuming the motors weren't working.
+    if (output) output->voltage = shooter_.voltage();
+  } else {
+    shooter_.Update(true);
+    shooter_.ZeroPower();
+    if (output) output->voltage = 0.0;
+  }
+
+  status->hard_stop_power = PositionToPower(shooter_.absolute_position());
+
+  if (output) {
+    output->latch_piston = latch_piston_;
+    output->brake_piston = brake_piston_;
+  }
+
+  if (position) {
+    LOG_STRUCT(DEBUG, "internal state",
+               ShooterStateToLog(
+                   shooter_.absolute_position(), shooter_.absolute_velocity(),
+                   state_, position->latch, position->pusher_proximal.current,
+                   position->pusher_distal.current, position->plunger,
+                   brake_piston_, latch_piston_));
+
+    last_position_ = *position;
+
+    last_distal_posedge_count_ = position->pusher_distal.posedge_count;
+    last_proximal_posedge_count_ = position->pusher_proximal.posedge_count;
+    last_distal_current_ = position->pusher_distal.current;
+    last_proximal_current_ = position->pusher_proximal.current;
+  }
+
+  status->shots = shot_count_;
+}
+
+void ShooterMotor::ZeroOutputs() {
+  queue_group()->output.MakeWithBuilder()
+      .voltage(0)
+      .latch_piston(latch_piston_)
+      .brake_piston(brake_piston_)
+      .Send();
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/shooter/shooter.gyp b/y2014/control_loops/shooter/shooter.gyp
new file mode 100644
index 0000000..260fb11
--- /dev/null
+++ b/y2014/control_loops/shooter/shooter.gyp
@@ -0,0 +1,82 @@
+{
+  'targets': [
+    {
+      'target_name': 'replay_shooter',
+      'type': 'executable',
+      'variables': {
+        'no_rsync': 1,
+      },
+      'sources': [
+        'replay_shooter.cc',
+      ],
+      'dependencies': [
+        'shooter_queue',
+        '<(AOS)/common/controls/controls.gyp:replay_control_loop',
+        '<(AOS)/linux_code/linux_code.gyp:init',
+      ],
+    },
+    {
+      'target_name': 'shooter_loop',
+      'type': 'static_library',
+      'sources': ['shooter.q'],
+      'variables': {
+        'header_path': 'y2014/control_loops/shooter',
+      },
+      'dependencies': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+      ],
+      'includes': ['../../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'shooter_lib',
+      'type': 'static_library',
+      'sources': [
+        'shooter.cc',
+        'shooter_motor_plant.cc',
+        'unaugmented_shooter_motor_plant.cc',
+      ],
+      'dependencies': [
+        'shooter_loop',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(DEPTH)/y2014/y2014.gyp:constants',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+      ],
+      'export_dependent_settings': [
+        'shooter_loop',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+    },
+    {
+      'target_name': 'shooter_lib_test',
+      'type': 'executable',
+      'sources': [
+        'shooter_lib_test.cc',
+      ],
+      'dependencies': [
+        '<(EXTERNALS):gtest',
+        'shooter_loop',
+        'shooter_lib',
+        '<(AOS)/common/controls/controls.gyp:control_loop_test',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+    },
+    {
+      'target_name': 'shooter',
+      'type': 'executable',
+      'sources': [
+        'shooter_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'shooter_lib',
+      ],
+    },
+  ],
+}
diff --git a/y2014/control_loops/shooter/shooter.h b/y2014/control_loops/shooter/shooter.h
new file mode 100644
index 0000000..1339f6b
--- /dev/null
+++ b/y2014/control_loops/shooter/shooter.h
@@ -0,0 +1,224 @@
+#ifndef Y2014_CONTROL_LOOPS_shooter_shooter_H_
+#define Y2014_CONTROL_LOOPS_shooter_shooter_H_
+
+#include <memory>
+
+#include "aos/common/controls/control_loop.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "aos/common/time.h"
+
+#include "y2014/constants.h"
+#include "y2014/control_loops/shooter/shooter_motor_plant.h"
+#include "y2014/control_loops/shooter/shooter.q.h"
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+class ShooterTest_UnloadWindupPositive_Test;
+class ShooterTest_UnloadWindupNegative_Test;
+class ShooterTest_RezeroWhileUnloading_Test;
+};
+
+using ::aos::time::Time;
+
+// Note: Everything in this file assumes that there is a 1 cycle delay between
+// power being requested and it showing up at the motor.  It assumes that
+// X_hat(2, 1) is the voltage being applied as well.  It will go unstable if
+// that isn't true.
+
+// This class implements the CapU function correctly given all the extra
+// information that we know about.
+// It does not have any zeroing logic in it, only logic to deal with a delta U
+// controller.
+class ZeroedStateFeedbackLoop : public StateFeedbackLoop<3, 1, 1> {
+ public:
+  ZeroedStateFeedbackLoop(StateFeedbackLoop<3, 1, 1> &&loop)
+      : StateFeedbackLoop<3, 1, 1>(::std::move(loop)),
+        voltage_(0.0),
+        last_voltage_(0.0),
+        uncapped_voltage_(0.0),
+        offset_(0.0),
+        max_voltage_(12.0),
+        capped_goal_(false) {}
+
+  const static int kZeroingMaxVoltage = 5;
+
+  virtual void CapU();
+
+  // Returns the accumulated voltage.
+  double voltage() const { return voltage_; }
+
+  // Returns the uncapped voltage.
+  double uncapped_voltage() const { return uncapped_voltage_; }
+
+  // Zeros the accumulator.
+  void ZeroPower() { voltage_ = 0.0; }
+
+  // Sets the calibration offset given the absolute angle and the corrisponding
+  // encoder value.
+  void SetCalibration(double encoder_val, double known_position);
+
+  double offset() const { return offset_; }
+
+  double absolute_position() const { return X_hat(0, 0) + kPositionOffset; }
+  double absolute_velocity() const { return X_hat(1, 0); }
+
+  void CorrectPosition(double position) {
+    Eigen::Matrix<double, 1, 1> Y;
+    Y << position + offset_ - kPositionOffset;
+    Correct(Y);
+  }
+
+  // Recomputes the power goal for the current controller and position/velocity.
+  void RecalculatePowerGoal();
+
+  double goal_position() const { return R(0, 0) + kPositionOffset; }
+  double goal_velocity() const { return R(1, 0); }
+  void InitializeState(double position) {
+    mutable_X_hat(0, 0) = position - kPositionOffset;
+    mutable_X_hat(1, 0) = 0.0;
+    mutable_X_hat(2, 0) = 0.0;
+  }
+
+  void SetGoalPosition(double desired_position, double desired_velocity) {
+    LOG(DEBUG, "Goal position: %f Goal velocity: %f\n", desired_position,
+        desired_velocity);
+
+    mutable_R() << desired_position - kPositionOffset, desired_velocity,
+        (-A(1, 0) / A(1, 2) * (desired_position - kPositionOffset) -
+         A(1, 1) / A(1, 2) * desired_velocity);
+  }
+
+  double position() const { return X_hat(0, 0) - offset_ + kPositionOffset; }
+
+  void set_max_voltage(double max_voltage) { max_voltage_ = max_voltage; }
+  bool capped_goal() const { return capped_goal_; }
+
+  void CapGoal();
+
+  // Friend the test classes for acces to the internal state.
+  friend class testing::ShooterTest_RezeroWhileUnloading_Test;
+
+ private:
+  // The offset between what is '0' (0 rate on the spring) and the 0 (all the
+  // way cocked).
+  constexpr static double kPositionOffset = kMaxExtension;
+  // The accumulated voltage to apply to the motor.
+  double voltage_;
+  double last_voltage_;
+  double uncapped_voltage_;
+  double offset_;
+  double max_voltage_;
+  bool capped_goal_;
+};
+
+const Time kUnloadTimeout = Time::InSeconds(10);
+const Time kLoadTimeout = Time::InSeconds(2);
+const Time kLoadProblemEndTimeout = Time::InSeconds(1.0);
+const Time kShooterBrakeSetTime = Time::InSeconds(0.05);
+// Time to wait after releasing the latch piston before winching back again.
+const Time kShotEndTimeout = Time::InSeconds(0.2);
+const Time kPrepareFireEndTime = Time::InMS(40);
+
+class ShooterMotor
+    : public aos::controls::ControlLoop<control_loops::ShooterGroup> {
+ public:
+  explicit ShooterMotor(control_loops::ShooterGroup *my_shooter =
+                            &control_loops::shooter_queue_group);
+
+  // True if the goal was moved to avoid goal windup.
+  bool capped_goal() const { return shooter_.capped_goal(); }
+
+  double PowerToPosition(double power);
+  double PositionToPower(double position);
+  void CheckCalibrations(const control_loops::ShooterGroup::Position *position);
+
+  typedef enum {
+    STATE_INITIALIZE = 0,
+    STATE_REQUEST_LOAD = 1,
+    STATE_LOAD_BACKTRACK = 2,
+    STATE_LOAD = 3,
+    STATE_LOADING_PROBLEM = 4,
+    STATE_PREPARE_SHOT = 5,
+    STATE_READY = 6,
+    STATE_FIRE = 8,
+    STATE_UNLOAD = 9,
+    STATE_UNLOAD_MOVE = 10,
+    STATE_READY_UNLOAD = 11,
+    STATE_ESTOP = 12
+  } State;
+
+  State state() { return state_; }
+
+ protected:
+  virtual void RunIteration(
+      const ShooterGroup::Goal *goal,
+      const control_loops::ShooterGroup::Position *position,
+      ShooterGroup::Output *output, ShooterGroup::Status *status);
+
+ private:
+  // We have to override this to keep the pistons in the correct positions.
+  virtual void ZeroOutputs();
+
+  // Friend the test classes for acces to the internal state.
+  friend class testing::ShooterTest_UnloadWindupPositive_Test;
+  friend class testing::ShooterTest_UnloadWindupNegative_Test;
+  friend class testing::ShooterTest_RezeroWhileUnloading_Test;
+
+  // Enter state STATE_UNLOAD
+  void Unload() {
+    state_ = STATE_UNLOAD;
+    unload_timeout_ = Time::Now() + kUnloadTimeout;
+  }
+  // Enter state STATE_LOAD
+  void Load() {
+    state_ = STATE_LOAD;
+    load_timeout_ = Time::Now() + kLoadTimeout;
+  }
+
+  control_loops::ShooterGroup::Position last_position_;
+
+  ZeroedStateFeedbackLoop shooter_;
+
+  // state machine state
+  State state_;
+
+  // time to giving up on loading problem
+  Time loading_problem_end_time_;
+
+  // The end time when loading for it to timeout.
+  Time load_timeout_;
+
+  // wait for brake to set
+  Time shooter_brake_set_time_;
+
+  // The timeout for unloading.
+  Time unload_timeout_;
+
+  // time that shot must have completed
+  Time shot_end_time_;
+
+  // track cycles that we are stuck to detect errors
+  int cycles_not_moved_;
+
+  double firing_starting_position_;
+
+  // True if the latch should be engaged and the brake should be engaged.
+  bool latch_piston_;
+  bool brake_piston_;
+  int32_t last_distal_posedge_count_;
+  int32_t last_proximal_posedge_count_;
+  uint32_t shot_count_;
+  bool zeroed_;
+  int distal_posedge_validation_cycles_left_;
+  int proximal_posedge_validation_cycles_left_;
+  bool last_distal_current_;
+  bool last_proximal_current_;
+
+  DISALLOW_COPY_AND_ASSIGN(ShooterMotor);
+};
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // Y2014_CONTROL_LOOPS_shooter_shooter_H_
diff --git a/y2014/control_loops/shooter/shooter.q b/y2014/control_loops/shooter/shooter.q
new file mode 100644
index 0000000..bc83ff7
--- /dev/null
+++ b/y2014/control_loops/shooter/shooter.q
@@ -0,0 +1,100 @@
+package frc971.control_loops;
+
+import "aos/common/controls/control_loops.q";
+import "frc971/control_loops/control_loops.q";
+
+queue_group ShooterGroup {
+  implements aos.control_loops.ControlLoop;
+
+  message Output {
+    double voltage;
+    // true: latch engaged, false: latch open
+    bool latch_piston;
+    // true: brake engaged false: brake released
+    bool brake_piston;
+  };
+  message Goal {
+    // Shot power in joules.
+    double shot_power;
+    // Shoots as soon as this is true.
+    bool shot_requested;
+    bool unload_requested;
+    bool load_requested;
+  };
+
+  // Back is when the springs are all the way stretched.
+  message Position {
+    // In meters, out is positive.
+    double position;
+
+    // If the latch piston is fired and this hall effect has been triggered, the
+    // plunger is all the way back and latched.
+    bool plunger;
+    // Gets triggered when the pusher is all the way back.
+    PosedgeOnlyCountedHallEffectStruct pusher_distal;
+    // Triggers just before pusher_distal.
+    PosedgeOnlyCountedHallEffectStruct pusher_proximal;
+    // Triggers when the latch engages.
+    bool latch;
+  };
+  message Status {
+    // Whether it's ready to shoot right now.
+    bool ready;
+    // Whether the plunger is in and out of the way of grabbing a ball.
+    // TODO(ben): Populate these!
+    bool cocked;
+    // How many times we've shot.
+    int32_t shots;
+    bool done;
+    // What we think the current position of the hard stop on the shooter is, in
+    // shot power (Joules).
+    double hard_stop_power;
+  };
+
+  queue Goal goal;
+  queue Position position;
+  queue Output output;
+  queue Status status;
+};
+
+queue_group ShooterGroup shooter_queue_group;
+
+struct ShooterStateToLog {
+	double absolute_position;
+	double absolute_velocity;
+	uint32_t state;
+	bool latch_sensor;
+	bool proximal;
+	bool distal;
+	bool plunger;
+	bool brake;
+	bool latch_piston;
+};
+
+struct ShooterVoltageToLog {
+	double X_hat;
+	double applied;
+};
+
+struct ShooterMovingGoal {
+	double dx;
+};
+
+struct ShooterChangeCalibration {
+	double encoder;
+	double real_position;
+	double old_position;
+	double new_position;
+	double old_offset;
+	double new_offset;
+};
+
+struct ShooterStatusToLog {
+	double goal;
+	double position;
+};
+
+struct PowerAdjustment {
+	double requested_power;
+	double actual_power;
+};
diff --git a/y2014/control_loops/shooter/shooter_lib_test.cc b/y2014/control_loops/shooter/shooter_lib_test.cc
new file mode 100644
index 0000000..a65e56f
--- /dev/null
+++ b/y2014/control_loops/shooter/shooter_lib_test.cc
@@ -0,0 +1,723 @@
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/network/team_number.h"
+#include "aos/common/controls/control_loop_test.h"
+#include "y2014/control_loops/shooter/shooter.q.h"
+#include "y2014/control_loops/shooter/shooter.h"
+#include "y2014/control_loops/shooter/unaugmented_shooter_motor_plant.h"
+#include "y2014/constants.h"
+
+using ::aos::time::Time;
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+
+static const int kTestTeam = 1;
+
+class TeamNumberEnvironment : public ::testing::Environment {
+ public:
+  // Override this to define how to set up the environment.
+  virtual void SetUp() { aos::network::OverrideTeamNumber(kTestTeam); }
+};
+
+::testing::Environment *const team_number_env =
+    ::testing::AddGlobalTestEnvironment(new TeamNumberEnvironment);
+
+
+// Class which simulates the shooter and sends out queue messages containing the
+// position.
+class ShooterSimulation {
+ public:
+  // Constructs a motor simulation.
+  ShooterSimulation(double initial_position)
+      : shooter_plant_(new StateFeedbackPlant<2, 1, 1>(MakeRawShooterPlant())),
+        latch_piston_state_(false),
+        latch_delay_count_(0),
+        plunger_latched_(false),
+        brake_piston_state_(true),
+        brake_delay_count_(0),
+        shooter_queue_group_(
+            ".frc971.control_loops.shooter_queue_group", 0xcbf22ba9,
+            ".frc971.control_loops.shooter_queue_group.goal",
+            ".frc971.control_loops.shooter_queue_group.position",
+            ".frc971.control_loops.shooter_queue_group.output",
+            ".frc971.control_loops.shooter_queue_group.status") {
+    Reinitialize(initial_position);
+  }
+
+  // The difference between the position with 0 at the back, and the position
+  // with 0 measured where the spring has 0 force.
+  constexpr static double kPositionOffset = kMaxExtension;
+
+  void Reinitialize(double initial_position) {
+    LOG(INFO, "Reinitializing to {pos: %f}\n", initial_position);
+    StateFeedbackPlant<2, 1, 1> *plant = shooter_plant_.get();
+    initial_position_ = initial_position;
+    plant->mutable_X(0, 0) = initial_position_ - kPositionOffset;
+    plant->mutable_X(1, 0) = 0.0;
+    plant->mutable_Y() = plant->C() * plant->X();
+    last_voltage_ = 0.0;
+    last_plant_position_ = 0.0;
+    SetPhysicalSensors(&last_position_message_);
+  }
+
+  // Returns the absolute angle of the shooter.
+  double GetAbsolutePosition() const {
+    return shooter_plant_->Y(0, 0) + kPositionOffset;
+  }
+
+  // Returns the adjusted angle of the shooter.
+  double GetPosition() const {
+    return GetAbsolutePosition() - initial_position_;
+  }
+
+  // Makes sure pos is inside range (inclusive)
+  bool CheckRange(double pos, struct constants::Values::AnglePair pair) {
+    return (pos >= pair.lower_angle && pos <= pair.upper_angle);
+  }
+
+  // Sets the values of the physical sensors that can be directly observed
+  // (encoder, hall effect).
+  void SetPhysicalSensors(control_loops::ShooterGroup::Position *position) {
+    const frc971::constants::Values &values = constants::GetValues();
+
+   	position->position = GetPosition();
+
+    LOG(DEBUG, "Physical shooter at {%f}\n", GetAbsolutePosition());
+
+    // Signal that the hall effect sensor has been triggered if it is within
+    // the correct range.
+    if (plunger_latched_) {
+      position->plunger = true;
+      // Only disengage the spring if we are greater than 0, which is where the
+      // latch will take the load off the pusher.
+      if (GetAbsolutePosition() > 0.0) {
+        shooter_plant_->set_plant_index(1);
+      } else {
+        shooter_plant_->set_plant_index(0);
+      }
+    } else {
+      shooter_plant_->set_plant_index(0);
+      position->plunger =
+          CheckRange(GetAbsolutePosition(), values.shooter.plunger_back);
+    }
+    position->pusher_distal.current =
+        CheckRange(GetAbsolutePosition(), values.shooter.pusher_distal);
+    position->pusher_proximal.current =
+        CheckRange(GetAbsolutePosition(), values.shooter.pusher_proximal);
+  }
+
+  void UpdateEffectEdge(
+      PosedgeOnlyCountedHallEffectStruct *sensor,
+      const PosedgeOnlyCountedHallEffectStruct &last_sensor,
+      const constants::Values::AnglePair &limits,
+      const control_loops::ShooterGroup::Position &last_position) {
+    sensor->posedge_count = last_sensor.posedge_count;
+    sensor->negedge_count = last_sensor.negedge_count;
+
+    sensor->posedge_value = last_sensor.posedge_value;
+
+    if (sensor->current && !last_sensor.current) {
+      ++sensor->posedge_count;
+      if (last_position.position + initial_position_ < limits.lower_angle) {
+        LOG(DEBUG, "Posedge value on lower edge of sensor, count is now %d\n",
+            sensor->posedge_count);
+        sensor->posedge_value = limits.lower_angle - initial_position_;
+      } else {
+        LOG(DEBUG, "Posedge value on upper edge of sensor, count is now %d\n",
+            sensor->posedge_count);
+        sensor->posedge_value = limits.upper_angle - initial_position_;
+      }
+    }
+    if (!sensor->current && last_sensor.current) {
+      ++sensor->negedge_count;
+    }
+  }
+
+  void SendPositionMessage() {
+    // the first bool is false
+    SendPositionMessage(false, false, false, false);
+  }
+
+  // Sends out the position queue messages.
+  // if the first bool is false then this is
+  // just the default state, otherwise will force
+  // it into a state using the passed values
+  void SendPositionMessage(bool use_passed, bool plunger_in,
+                           bool latch_in, bool brake_in) {
+    const frc971::constants::Values &values = constants::GetValues();
+    ::aos::ScopedMessagePtr<control_loops::ShooterGroup::Position> position =
+        shooter_queue_group_.position.MakeMessage();
+
+    if (use_passed) {
+      plunger_latched_ = latch_in && plunger_in;
+      latch_piston_state_ = plunger_latched_;
+      brake_piston_state_ = brake_in;
+    }
+
+    SetPhysicalSensors(position.get());
+
+    position->latch = latch_piston_state_;
+
+    // Handle pusher distal hall effect
+    UpdateEffectEdge(&position->pusher_distal,
+                     last_position_message_.pusher_distal,
+                     values.shooter.pusher_distal, last_position_message_);
+
+    // Handle pusher proximal hall effect
+    UpdateEffectEdge(&position->pusher_proximal,
+                     last_position_message_.pusher_proximal,
+                     values.shooter.pusher_proximal, last_position_message_);
+
+    last_position_message_ = *position;
+    position.Send();
+  }
+
+  // Simulates the claw moving for one timestep.
+  void Simulate() {
+    last_plant_position_ = GetAbsolutePosition();
+    EXPECT_TRUE(shooter_queue_group_.output.FetchLatest());
+    if (shooter_queue_group_.output->latch_piston && !latch_piston_state_ &&
+        latch_delay_count_ <= 0) {
+      ASSERT_EQ(0, latch_delay_count_) << "The test doesn't support that.";
+      latch_delay_count_ = 6;
+    } else if (!shooter_queue_group_.output->latch_piston &&
+               latch_piston_state_ && latch_delay_count_ >= 0) {
+      ASSERT_EQ(0, latch_delay_count_) << "The test doesn't support that.";
+      latch_delay_count_ = -6;
+    }
+
+    if (shooter_queue_group_.output->brake_piston && !brake_piston_state_ &&
+        brake_delay_count_ <= 0) {
+      ASSERT_EQ(0, brake_delay_count_) << "The test doesn't support that.";
+      brake_delay_count_ = 5;
+    } else if (!shooter_queue_group_.output->brake_piston &&
+               brake_piston_state_ && brake_delay_count_ >= 0) {
+      ASSERT_EQ(0, brake_delay_count_) << "The test doesn't support that.";
+      brake_delay_count_ = -5;
+    }
+
+    // Handle brake internal state
+    if (!brake_piston_state_ && brake_delay_count_ > 0) {
+      if (brake_delay_count_ == 1) {
+        brake_piston_state_ = true;
+      }
+      brake_delay_count_--;
+    } else if (brake_piston_state_ && brake_delay_count_ < 0) {
+      if (brake_delay_count_ == -1) {
+        brake_piston_state_ = false;
+      }
+      brake_delay_count_++;
+    }
+
+    if (brake_piston_state_) {
+      shooter_plant_->mutable_U() << 0.0;
+      shooter_plant_->mutable_X(1, 0) = 0.0;
+      shooter_plant_->mutable_Y() = shooter_plant_->C() * shooter_plant_->X() +
+                                   shooter_plant_->D() * shooter_plant_->U();
+    } else {
+      shooter_plant_->mutable_U() << last_voltage_;
+      //shooter_plant_->U << shooter_queue_group_.output->voltage;
+      shooter_plant_->Update();
+    }
+    LOG(DEBUG, "Plant index is %d\n", shooter_plant_->plant_index());
+
+    // Handle latch hall effect
+    if (!latch_piston_state_ && latch_delay_count_ > 0) {
+      LOG(DEBUG, "latching simulation: %dp\n", latch_delay_count_);
+      if (latch_delay_count_ == 1) {
+        latch_piston_state_ = true;
+        EXPECT_GE(constants::GetValues().shooter.latch_max_safe_position,
+                  GetAbsolutePosition());
+        plunger_latched_ = true;
+      }
+      latch_delay_count_--;
+    } else if (latch_piston_state_ && latch_delay_count_ < 0) {
+      LOG(DEBUG, "latching simulation: %dn\n", latch_delay_count_);
+      if (latch_delay_count_ == -1) {
+        latch_piston_state_ = false;
+        if (GetAbsolutePosition() > 0.002) {
+          EXPECT_TRUE(brake_piston_state_) << "Must have the brake set when "
+                                              "releasing the latch for "
+                                              "powerful shots.";
+        }
+        plunger_latched_ = false;
+        // TODO(austin): The brake should be set for a number of cycles after
+        // this as well.
+        shooter_plant_->mutable_X(0, 0) += 0.005;
+      }
+      latch_delay_count_++;
+    }
+
+    EXPECT_GE(constants::GetValues().shooter.upper_hard_limit,
+              GetAbsolutePosition());
+    EXPECT_LE(constants::GetValues().shooter.lower_hard_limit,
+              GetAbsolutePosition());
+
+    last_voltage_ = shooter_queue_group_.output->voltage;
+    ::aos::time::Time::IncrementMockTime(::aos::time::Time::InMS(10.0));
+  }
+
+  // pointer to plant
+  const ::std::unique_ptr<StateFeedbackPlant<2, 1, 1>> shooter_plant_;
+
+  // true latch closed
+  bool latch_piston_state_;
+  // greater than zero, delaying close. less than zero delaying open
+  int latch_delay_count_;
+
+  // Goes to true after latch_delay_count_ hits 0 while the plunger is back.
+  bool plunger_latched_;
+
+  // true brake locked
+  bool brake_piston_state_;
+  // greater than zero, delaying close. less than zero delaying open
+  int brake_delay_count_;
+
+ private:
+  ShooterGroup shooter_queue_group_;
+  double initial_position_;
+  double last_voltage_;
+
+  control_loops::ShooterGroup::Position last_position_message_;
+  double last_plant_position_;
+};
+
+class ShooterTest : public ::aos::testing::ControlLoopTest {
+
+ protected:
+  // Create a new instance of the test queue so that it invalidates the queue
+  // that it points to.  Otherwise, we will have a pointer to shared memory that
+  // is no longer valid.
+  ShooterGroup shooter_queue_group_;
+
+  // Create a loop and simulation plant.
+  ShooterMotor shooter_motor_;
+  ShooterSimulation shooter_motor_plant_;
+
+  void Reinitialize(double position) {
+    shooter_motor_plant_.Reinitialize(position);
+  }
+
+  ShooterTest()
+      : shooter_queue_group_(
+            ".frc971.control_loops.shooter_queue_group", 0xcbf22ba9,
+            ".frc971.control_loops.shooter_queue_group.goal",
+            ".frc971.control_loops.shooter_queue_group.position",
+            ".frc971.control_loops.shooter_queue_group.output",
+            ".frc971.control_loops.shooter_queue_group.status"),
+        shooter_motor_(&shooter_queue_group_),
+        shooter_motor_plant_(0.2) {
+  }
+
+  void VerifyNearGoal() {
+    shooter_queue_group_.goal.FetchLatest();
+    shooter_queue_group_.position.FetchLatest();
+    double pos = shooter_motor_plant_.GetAbsolutePosition();
+    EXPECT_NEAR(shooter_queue_group_.goal->shot_power, pos, 1e-4);
+  }
+};
+
+TEST_F(ShooterTest, PowerConversion) {
+  const frc971::constants::Values &values = constants::GetValues();
+  // test a couple of values return the right thing
+  EXPECT_NEAR(0.254001, shooter_motor_.PowerToPosition(140.0), 0.00001);
+  EXPECT_NEAR(0.00058, shooter_motor_.PowerToPosition(0.53), 0.00001);
+  EXPECT_NEAR(0.095251238129837101, shooter_motor_.PowerToPosition(73.67),
+              0.00001);
+
+  // value too large should get max
+  EXPECT_NEAR(values.shooter.upper_limit,
+              shooter_motor_.PowerToPosition(505050.99), 0.00001);
+  // negative values should zero
+  EXPECT_NEAR(0, shooter_motor_.PowerToPosition(-123.4), 0.00001);
+}
+
+// Test that PowerToPosition and PositionToPower are inverses of each other.
+// Note that PowerToPosition will cap position whereas PositionToPower will not
+// cap power.
+TEST_F(ShooterTest, InversePowerConversion) {
+  // Test a few values.
+  double power = 140.0;
+  double position = shooter_motor_.PowerToPosition(power);
+  EXPECT_NEAR(power, shooter_motor_.PositionToPower(position), 1e-5);
+  power = .53;
+  position = shooter_motor_.PowerToPosition(power);
+  EXPECT_NEAR(power, shooter_motor_.PositionToPower(position), 1e-5);
+  power = 71.971;
+  position = shooter_motor_.PowerToPosition(power);
+  EXPECT_NEAR(power, shooter_motor_.PositionToPower(position), 1e-5);
+}
+
+// Tests that the shooter zeros correctly and goes to a position.
+TEST_F(ShooterTest, GoesToValue) {
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 200; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  // EXPECT_NEAR(0.0, shooter_motor_.GetPosition(), 0.01);
+  double pos = shooter_motor_plant_.GetAbsolutePosition();
+  EXPECT_NEAR(
+      shooter_motor_.PowerToPosition(shooter_queue_group_.goal->shot_power),
+      pos, 0.05);
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+}
+
+// Tests that the shooter zeros correctly and goes to a position.
+TEST_F(ShooterTest, Fire) {
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 120; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+  shooter_queue_group_.goal.MakeWithBuilder()
+      .shot_power(35.0)
+      .shot_requested(true)
+      .Send();
+
+  bool hit_fire = false;
+  for (int i = 0; i < 400; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+    if (shooter_motor_.state() == ShooterMotor::STATE_FIRE) {
+      if (!hit_fire) {
+        shooter_queue_group_.goal.MakeWithBuilder()
+            .shot_power(17.0)
+            .shot_requested(false)
+            .Send();
+      }
+      hit_fire = true;
+    }
+  }
+
+  double pos = shooter_motor_plant_.GetAbsolutePosition();
+  EXPECT_NEAR(
+      shooter_motor_.PowerToPosition(shooter_queue_group_.goal->shot_power),
+      pos, 0.05);
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+  EXPECT_TRUE(hit_fire);
+}
+
+// Tests that the shooter zeros correctly and goes to a position.
+TEST_F(ShooterTest, FireLong) {
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 150; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+  shooter_queue_group_.goal.MakeWithBuilder().shot_requested(true).Send();
+
+  bool hit_fire = false;
+  for (int i = 0; i < 400; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+    if (shooter_motor_.state() == ShooterMotor::STATE_FIRE) {
+      if (!hit_fire) {
+        shooter_queue_group_.goal.MakeWithBuilder()
+            .shot_requested(false)
+            .Send();
+      }
+      hit_fire = true;
+    }
+  }
+
+  double pos = shooter_motor_plant_.GetAbsolutePosition();
+  EXPECT_NEAR(shooter_motor_.PowerToPosition(shooter_queue_group_.goal->shot_power), pos, 0.05);
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+  EXPECT_TRUE(hit_fire);
+}
+
+// Verifies that it doesn't try to go out too far if you give it a ridicilous
+// power.
+TEST_F(ShooterTest, LoadTooFar) {
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(500.0).Send();
+  for (int i = 0; i < 160; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+    EXPECT_LT(
+        shooter_motor_plant_.GetAbsolutePosition(),
+        constants::GetValuesForTeam(kTestTeam).shooter.upper_limit);
+  }
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+}
+
+// Tests that the shooter zeros correctly and goes to a position.
+TEST_F(ShooterTest, MoveGoal) {
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 150; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(14.0).Send();
+
+  for (int i = 0; i < 100; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+
+  double pos = shooter_motor_plant_.GetAbsolutePosition();
+  EXPECT_NEAR(
+      shooter_motor_.PowerToPosition(shooter_queue_group_.goal->shot_power),
+      pos, 0.05);
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+}
+
+
+TEST_F(ShooterTest, Unload) {
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 150; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+  shooter_queue_group_.goal.MakeWithBuilder().unload_requested(true).Send();
+
+  for (int i = 0;
+       i < 800 && shooter_motor_.state() != ShooterMotor::STATE_READY_UNLOAD;
+       ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+
+  EXPECT_NEAR(constants::GetValues().shooter.upper_limit,
+              shooter_motor_plant_.GetAbsolutePosition(), 0.015);
+  EXPECT_EQ(ShooterMotor::STATE_READY_UNLOAD, shooter_motor_.state());
+}
+
+// Tests that it rezeros while unloading.
+TEST_F(ShooterTest, RezeroWhileUnloading) {
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 150; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+
+  shooter_motor_.shooter_.offset_ += 0.01;
+  for (int i = 0; i < 50; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+
+  shooter_queue_group_.goal.MakeWithBuilder().unload_requested(true).Send();
+
+  for (int i = 0;
+       i < 800 && shooter_motor_.state() != ShooterMotor::STATE_READY_UNLOAD;
+       ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+
+  EXPECT_NEAR(constants::GetValues().shooter.upper_limit,
+              shooter_motor_plant_.GetAbsolutePosition(), 0.015);
+  EXPECT_EQ(ShooterMotor::STATE_READY_UNLOAD, shooter_motor_.state());
+}
+
+// Tests that the shooter zeros correctly and goes to a position.
+TEST_F(ShooterTest, UnloadWindupNegative) {
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 150; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+  shooter_queue_group_.goal.MakeWithBuilder().unload_requested(true).Send();
+
+  int kicked_delay = 20;
+  int capped_goal_count = 0;
+  for (int i = 0;
+       i < 800 && shooter_motor_.state() != ShooterMotor::STATE_READY_UNLOAD;
+       ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    if (shooter_motor_.state() == ShooterMotor::STATE_UNLOAD_MOVE) {
+      LOG(DEBUG, "State is UnloadMove\n");
+      --kicked_delay;
+      if (kicked_delay == 0) {
+        shooter_motor_.shooter_.mutable_R(0, 0) -= 100;
+      }
+    }
+    if (shooter_motor_.capped_goal() && kicked_delay < 0) {
+      ++capped_goal_count;
+    }
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+
+  EXPECT_NEAR(constants::GetValues().shooter.upper_limit,
+              shooter_motor_plant_.GetAbsolutePosition(), 0.05);
+  EXPECT_EQ(ShooterMotor::STATE_READY_UNLOAD, shooter_motor_.state());
+  EXPECT_LE(1, capped_goal_count);
+  EXPECT_GE(3, capped_goal_count);
+}
+
+// Tests that the shooter zeros correctly and goes to a position.
+TEST_F(ShooterTest, UnloadWindupPositive) {
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 150; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+  shooter_queue_group_.goal.MakeWithBuilder().unload_requested(true).Send();
+
+  int kicked_delay = 20;
+  int capped_goal_count = 0;
+  for (int i = 0;
+       i < 800 && shooter_motor_.state() != ShooterMotor::STATE_READY_UNLOAD;
+       ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    if (shooter_motor_.state() == ShooterMotor::STATE_UNLOAD_MOVE) {
+      LOG(DEBUG, "State is UnloadMove\n");
+      --kicked_delay;
+      if (kicked_delay == 0) {
+        shooter_motor_.shooter_.mutable_R(0, 0) += 0.1;
+      }
+    }
+    if (shooter_motor_.capped_goal() && kicked_delay < 0) {
+      ++capped_goal_count;
+    }
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+
+  EXPECT_NEAR(constants::GetValues().shooter.upper_limit,
+              shooter_motor_plant_.GetAbsolutePosition(), 0.05);
+  EXPECT_EQ(ShooterMotor::STATE_READY_UNLOAD, shooter_motor_.state());
+  EXPECT_LE(1, capped_goal_count);
+  EXPECT_GE(3, capped_goal_count);
+}
+
+double HallEffectMiddle(constants::Values::AnglePair pair) {
+  return (pair.lower_angle + pair.upper_angle) / 2.0;
+}
+
+// Tests that the shooter zeros correctly and goes to a position.
+TEST_F(ShooterTest, StartsOnDistal) {
+  Reinitialize(HallEffectMiddle(constants::GetValues().shooter.pusher_distal));
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 200; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  // EXPECT_NEAR(0.0, shooter_motor_.GetPosition(), 0.01);
+  double pos = shooter_motor_plant_.GetAbsolutePosition();
+  EXPECT_NEAR(
+      shooter_motor_.PowerToPosition(shooter_queue_group_.goal->shot_power),
+      pos, 0.05);
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+}
+
+
+// Tests that the shooter zeros correctly and goes to a position.
+TEST_F(ShooterTest, StartsOnProximal) {
+  Reinitialize(
+      HallEffectMiddle(constants::GetValues().shooter.pusher_proximal));
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(70.0).Send();
+  for (int i = 0; i < 300; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  // EXPECT_NEAR(0.0, shooter_motor_.GetPosition(), 0.01);
+  double pos = shooter_motor_plant_.GetAbsolutePosition();
+  EXPECT_NEAR(
+      shooter_motor_.PowerToPosition(shooter_queue_group_.goal->shot_power),
+      pos, 0.05);
+  EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+}
+
+class ShooterZeroingTest : public ShooterTest,
+                    public ::testing::WithParamInterface<
+                        ::std::tr1::tuple<bool, bool, bool, double>> {};
+
+TEST_P(ShooterZeroingTest, AllDisparateStartingZero) {
+  bool latch = ::std::tr1::get<0>(GetParam());
+  bool brake = ::std::tr1::get<1>(GetParam());
+  bool plunger_back = ::std::tr1::get<2>(GetParam());
+  double start_pos = ::std::tr1::get<3>(GetParam());
+  // flag to initialize test
+	//printf("@@@@ l= %d b= %d p= %d s= %.3f\n",
+	//		latch, brake, plunger_back, start_pos);
+  bool initialized = false;
+  Reinitialize(start_pos);
+  shooter_queue_group_.goal.MakeWithBuilder().shot_power(120.0).Send();
+  for (int i = 0; i < 200; ++i) {
+    shooter_motor_plant_.SendPositionMessage(!initialized, plunger_back, latch, brake);
+    initialized = true;
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  // EXPECT_NEAR(0.0, shooter_motor_.GetPosition(), 0.01);
+  double pos = shooter_motor_plant_.GetAbsolutePosition();
+  EXPECT_NEAR(
+      shooter_motor_.PowerToPosition(shooter_queue_group_.goal->shot_power),
+      pos, 0.05);
+  ASSERT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
+}
+
+INSTANTIATE_TEST_CASE_P(
+    ShooterZeroingTest, ShooterZeroingTest,
+    ::testing::Combine(
+        ::testing::Bool(), ::testing::Bool(), ::testing::Bool(),
+        ::testing::Values(
+            0.05,
+            constants::GetValuesForTeam(kTestTeam).shooter.upper_limit - 0.05,
+            HallEffectMiddle(constants::GetValuesForTeam(kTestTeam)
+                                 .shooter.pusher_proximal),
+            HallEffectMiddle(constants::GetValuesForTeam(kTestTeam)
+                                 .shooter.pusher_distal),
+            constants::GetValuesForTeam(kTestTeam)
+                    .shooter.latch_max_safe_position -
+                0.001)));
+
+// TODO(austin): Slip the encoder somewhere.
+
+// TODO(austin): Test all the timeouts...
+
+}  // namespace testing
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/shooter/shooter_main.cc b/y2014/control_loops/shooter/shooter_main.cc
new file mode 100644
index 0000000..31b24bf
--- /dev/null
+++ b/y2014/control_loops/shooter/shooter_main.cc
@@ -0,0 +1,11 @@
+#include "y2014/control_loops/shooter/shooter.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+  ::aos::Init();
+  frc971::control_loops::ShooterMotor shooter;
+  shooter.Run();
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2014/control_loops/shooter/shooter_motor_plant.cc b/y2014/control_loops/shooter/shooter_motor_plant.cc
new file mode 100644
index 0000000..7da6407
--- /dev/null
+++ b/y2014/control_loops/shooter/shooter_motor_plant.cc
@@ -0,0 +1,77 @@
+#include "y2014/control_loops/shooter/shooter_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<3, 1, 1> MakeSprungShooterPlantCoefficients() {
+  Eigen::Matrix<double, 3, 3> A;
+  A << 0.999391114909, 0.00811316740387, 7.59766686183e-05, -0.113584343654, 0.64780421498, 0.0141730519709, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 3, 1> B;
+  B << 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 1, 3> C;
+  C << 1.0, 0.0, 0.0;
+  Eigen::Matrix<double, 1, 1> D;
+  D << 0.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<3, 1, 1>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<3, 1, 1> MakeShooterPlantCoefficients() {
+  Eigen::Matrix<double, 3, 3> A;
+  A << 1.0, 0.00811505488455, 7.59852687598e-05, 0.0, 0.648331305446, 0.0141763492481, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 3, 1> B;
+  B << 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 1, 3> C;
+  C << 1.0, 0.0, 0.0;
+  Eigen::Matrix<double, 1, 1> D;
+  D << 0.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<3, 1, 1>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<3, 1, 1> MakeSprungShooterController() {
+  Eigen::Matrix<double, 3, 1> L;
+  L << 1.64719532989, 57.0572680832, 636.74290365;
+  Eigen::Matrix<double, 1, 3> K;
+  K << 450.571849185, 11.8404918938, 0.997195329889;
+  Eigen::Matrix<double, 3, 3> A_inv;
+  A_inv << 0.99918700445, -0.0125139220268, 0.00010144556732, 0.175194908375, 1.54148211958, -0.0218608169185, 0.0, 0.0, 1.0;
+  return StateFeedbackController<3, 1, 1>(L, K, A_inv, MakeSprungShooterPlantCoefficients());
+}
+
+StateFeedbackController<3, 1, 1> MakeShooterController() {
+  Eigen::Matrix<double, 3, 1> L;
+  L << 1.64833130545, 57.2417604572, 636.668851906;
+  Eigen::Matrix<double, 1, 3> K;
+  K << 349.173113146, 8.65077618169, 0.848331305446;
+  Eigen::Matrix<double, 3, 3> A_inv;
+  A_inv << 1.0, -0.0125168333171, 0.000101457731824, 0.0, 1.5424212769, -0.021865902709, 0.0, 0.0, 1.0;
+  return StateFeedbackController<3, 1, 1>(L, K, A_inv, MakeShooterPlantCoefficients());
+}
+
+StateFeedbackPlant<3, 1, 1> MakeShooterPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<3, 1, 1>>> plants(2);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<3, 1, 1>>(new StateFeedbackPlantCoefficients<3, 1, 1>(MakeSprungShooterPlantCoefficients()));
+  plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<3, 1, 1>>(new StateFeedbackPlantCoefficients<3, 1, 1>(MakeShooterPlantCoefficients()));
+  return StateFeedbackPlant<3, 1, 1>(&plants);
+}
+
+StateFeedbackLoop<3, 1, 1> MakeShooterLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<3, 1, 1>>> controllers(2);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<3, 1, 1>>(new StateFeedbackController<3, 1, 1>(MakeSprungShooterController()));
+  controllers[1] = ::std::unique_ptr<StateFeedbackController<3, 1, 1>>(new StateFeedbackController<3, 1, 1>(MakeShooterController()));
+  return StateFeedbackLoop<3, 1, 1>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/shooter/shooter_motor_plant.h b/y2014/control_loops/shooter/shooter_motor_plant.h
new file mode 100644
index 0000000..45d6ed1
--- /dev/null
+++ b/y2014/control_loops/shooter/shooter_motor_plant.h
@@ -0,0 +1,28 @@
+#ifndef Y2014_CONTROL_LOOPS_SHOOTER_SHOOTER_MOTOR_PLANT_H_
+#define Y2014_CONTROL_LOOPS_SHOOTER_SHOOTER_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+static constexpr double kMaxExtension = 0.323850;
+
+static constexpr double kSpringConstant = 2800.000000;
+
+
+StateFeedbackPlantCoefficients<3, 1, 1> MakeSprungShooterPlantCoefficients();
+
+StateFeedbackController<3, 1, 1> MakeSprungShooterController();
+
+StateFeedbackPlantCoefficients<3, 1, 1> MakeShooterPlantCoefficients();
+
+StateFeedbackController<3, 1, 1> MakeShooterController();
+
+StateFeedbackPlant<3, 1, 1> MakeShooterPlant();
+
+StateFeedbackLoop<3, 1, 1> MakeShooterLoop();
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // Y2014_CONTROL_LOOPS_SHOOTER_SHOOTER_MOTOR_PLANT_H_
diff --git a/y2014/control_loops/shooter/unaugmented_shooter_motor_plant.cc b/y2014/control_loops/shooter/unaugmented_shooter_motor_plant.cc
new file mode 100644
index 0000000..8311948
--- /dev/null
+++ b/y2014/control_loops/shooter/unaugmented_shooter_motor_plant.cc
@@ -0,0 +1,77 @@
+#include "y2014/control_loops/shooter/unaugmented_shooter_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 1, 1> MakeRawSprungShooterPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.999391114909, 0.00811316740387, -0.113584343654, 0.64780421498;
+  Eigen::Matrix<double, 2, 1> B;
+  B << 7.59766686183e-05, 0.0141730519709;
+  Eigen::Matrix<double, 1, 2> C;
+  C << 1, 0;
+  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<2, 1, 1>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<2, 1, 1> MakeRawShooterPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 1.0, 0.00811505488455, 0.0, 0.648331305446;
+  Eigen::Matrix<double, 2, 1> B;
+  B << 7.59852687598e-05, 0.0141763492481;
+  Eigen::Matrix<double, 1, 2> C;
+  C << 1, 0;
+  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<2, 1, 1>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<2, 1, 1> MakeRawSprungShooterController() {
+  Eigen::Matrix<double, 2, 1> L;
+  L << 1.54719532989, 43.9345489758;
+  Eigen::Matrix<double, 1, 2> K;
+  K << 2126.06977433, 41.3223370936;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 0.99918700445, -0.0125139220268, 0.175194908375, 1.54148211958;
+  return StateFeedbackController<2, 1, 1>(L, K, A_inv, MakeRawSprungShooterPlantCoefficients());
+}
+
+StateFeedbackController<2, 1, 1> MakeRawShooterController() {
+  Eigen::Matrix<double, 2, 1> L;
+  L << 1.54833130545, 44.1155797675;
+  Eigen::Matrix<double, 1, 2> K;
+  K << 2133.83569145, 41.3499425476;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.0, -0.0125168333171, 0.0, 1.5424212769;
+  return StateFeedbackController<2, 1, 1>(L, K, A_inv, MakeRawShooterPlantCoefficients());
+}
+
+StateFeedbackPlant<2, 1, 1> MakeRawShooterPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 1, 1>>> plants(2);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 1, 1>>(new StateFeedbackPlantCoefficients<2, 1, 1>(MakeRawSprungShooterPlantCoefficients()));
+  plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 1, 1>>(new StateFeedbackPlantCoefficients<2, 1, 1>(MakeRawShooterPlantCoefficients()));
+  return StateFeedbackPlant<2, 1, 1>(&plants);
+}
+
+StateFeedbackLoop<2, 1, 1> MakeRawShooterLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<2, 1, 1>>> controllers(2);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<2, 1, 1>>(new StateFeedbackController<2, 1, 1>(MakeRawSprungShooterController()));
+  controllers[1] = ::std::unique_ptr<StateFeedbackController<2, 1, 1>>(new StateFeedbackController<2, 1, 1>(MakeRawShooterController()));
+  return StateFeedbackLoop<2, 1, 1>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/y2014/control_loops/shooter/unaugmented_shooter_motor_plant.h b/y2014/control_loops/shooter/unaugmented_shooter_motor_plant.h
new file mode 100644
index 0000000..5b7de85
--- /dev/null
+++ b/y2014/control_loops/shooter/unaugmented_shooter_motor_plant.h
@@ -0,0 +1,24 @@
+#ifndef Y2014_CONTROL_LOOPS_SHOOTER_UNAUGMENTED_SHOOTER_MOTOR_PLANT_H_
+#define Y2014_CONTROL_LOOPS_SHOOTER_UNAUGMENTED_SHOOTER_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 1, 1> MakeRawSprungShooterPlantCoefficients();
+
+StateFeedbackController<2, 1, 1> MakeRawSprungShooterController();
+
+StateFeedbackPlantCoefficients<2, 1, 1> MakeRawShooterPlantCoefficients();
+
+StateFeedbackController<2, 1, 1> MakeRawShooterController();
+
+StateFeedbackPlant<2, 1, 1> MakeRawShooterPlant();
+
+StateFeedbackLoop<2, 1, 1> MakeRawShooterLoop();
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif  // Y2014_CONTROL_LOOPS_SHOOTER_UNAUGMENTED_SHOOTER_MOTOR_PLANT_H_
diff --git a/y2014/control_loops/update_arm.sh b/y2014/control_loops/update_arm.sh
new file mode 100755
index 0000000..c4c1ab9
--- /dev/null
+++ b/y2014/control_loops/update_arm.sh
@@ -0,0 +1,10 @@
+#!/bin/bash
+#
+# Updates the arm controllers (for both robots).
+
+cd $(dirname $0)
+
+./python/arm.py fridge/arm_motor_plant.cc \
+    fridge/arm_motor_plant.h \
+    fridge/integral_arm_plant.cc \
+    fridge/integral_arm_plant.h
diff --git a/y2014/control_loops/update_claw.sh b/y2014/control_loops/update_claw.sh
new file mode 100755
index 0000000..2800d2a
--- /dev/null
+++ b/y2014/control_loops/update_claw.sh
@@ -0,0 +1,8 @@
+#!/bin/bash
+#
+# Updates the claw controllers.
+
+cd $(dirname $0)
+
+./python/claw.py claw/claw_motor_plant.h \
+    claw/claw_motor_plant.cc
diff --git a/y2014/control_loops/update_drivetrain.sh b/y2014/control_loops/update_drivetrain.sh
new file mode 100755
index 0000000..bad1074
--- /dev/null
+++ b/y2014/control_loops/update_drivetrain.sh
@@ -0,0 +1,10 @@
+#!/bin/bash
+#
+# Updates the drivetrain controllers (for both robots).
+
+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/y2014/control_loops/update_polydrivetrain.sh b/y2014/control_loops/update_polydrivetrain.sh
new file mode 100755
index 0000000..2e2748e
--- /dev/null
+++ b/y2014/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/y2014/control_loops/update_shooter.sh b/y2014/control_loops/update_shooter.sh
new file mode 100755
index 0000000..a9c5807
--- /dev/null
+++ b/y2014/control_loops/update_shooter.sh
@@ -0,0 +1,10 @@
+#!/bin/bash
+#
+# Updates the shooter controller.
+
+cd $(dirname $0)
+
+./python/shooter.py shooter/shooter_motor_plant.h \
+    shooter/shooter_motor_plant.cc \
+    shooter/unaugmented_shooter_motor_plant.h \
+    shooter/unaugmented_shooter_motor_plant.cc
diff --git a/y2014/joystick_reader.cc b/y2014/joystick_reader.cc
new file mode 100644
index 0000000..8bbf452
--- /dev/null
+++ b/y2014/joystick_reader.cc
@@ -0,0 +1,529 @@
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+#include <math.h>
+
+#include "aos/linux_code/init.h"
+#include "aos/prime/input/joystick_input.h"
+#include "aos/common/input/driver_station_data.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/util/log_interval.h"
+#include "aos/common/time.h"
+#include "aos/common/actions/actions.h"
+
+#include "y2014/control_loops/drivetrain/drivetrain.q.h"
+#include "y2014/constants.h"
+#include "frc971/queues/gyro.q.h"
+#include "frc971/autonomous/auto.q.h"
+#include "y2014/control_loops/claw/claw.q.h"
+#include "y2014/control_loops/shooter/shooter.q.h"
+#include "y2014/actors/shoot_actor.h"
+
+using ::frc971::control_loops::drivetrain_queue;
+using ::frc971::sensors::gyro_reading;
+
+using ::aos::input::driver_station::ButtonLocation;
+using ::aos::input::driver_station::JoystickAxis;
+using ::aos::input::driver_station::ControlBit;
+
+#define OLD_DS 0
+
+namespace frc971 {
+namespace input {
+namespace joysticks {
+
+const ButtonLocation kDriveControlLoopEnable1(1, 7),
+                     kDriveControlLoopEnable2(1, 11);
+const JoystickAxis kSteeringWheel(1, 1), kDriveThrottle(2, 2);
+const ButtonLocation kShiftHigh(2, 1), kShiftLow(2, 3);
+const ButtonLocation kQuickTurn(1, 5);
+
+const ButtonLocation kCatch(3, 10);
+
+#if OLD_DS
+const ButtonLocation kFire(3, 11);
+const ButtonLocation kUnload(1, 4);
+const ButtonLocation kReload(1, 2);
+
+const ButtonLocation kRollersOut(3, 12);
+const ButtonLocation kRollersIn(3, 7);
+
+const ButtonLocation kTuck(3, 9);
+const ButtonLocation kIntakePosition(3, 8);
+const ButtonLocation kIntakeOpenPosition(3, 10);
+const ButtonLocation kVerticalTuck(3, 1);
+const JoystickAxis kFlipRobot(3, 3);
+
+const ButtonLocation kLongShot(3, 5);
+const ButtonLocation kCloseShot(3, 2);
+const ButtonLocation kFenderShot(3, 3);
+const ButtonLocation kTrussShot(2, 11);
+const ButtonLocation kHumanPlayerShot(3, 2);
+#else
+const ButtonLocation kFire(3, 9);
+const ButtonLocation kUnload(1, 4);
+const ButtonLocation kReload(1, 2);
+
+const ButtonLocation kRollersOut(3, 8);
+const ButtonLocation kRollersIn(3, 3);
+
+const ButtonLocation kTuck(3, 4);
+const ButtonLocation kIntakePosition(3, 5);
+const ButtonLocation kIntakeOpenPosition(3, 11);
+const ButtonLocation kVerticalTuck(2, 6);
+const JoystickAxis kFlipRobot(3, 3);
+
+const ButtonLocation kLongShot(3, 7);
+const ButtonLocation kCloseShot(3, 6);
+const ButtonLocation kFenderShot(3, 2);
+const ButtonLocation kTrussShot(2, 11);
+const ButtonLocation kHumanPlayerShot(3, 1);
+#endif
+
+const ButtonLocation kUserLeft(2, 7);
+const ButtonLocation kUserRight(2, 10);
+
+const JoystickAxis kAdjustClawGoal(3, 2);
+const JoystickAxis kAdjustClawSeparation(3, 1);
+
+struct ClawGoal {
+  double angle;
+  double separation;
+};
+
+struct ShotGoal {
+  ClawGoal claw;
+  double shot_power;
+  double velocity_compensation;
+  double intake_power;
+};
+
+const double kIntakePower = 4.0;
+// In case we have to quickly adjust it.
+const double kGrabSeparation = 0;
+const double kShootSeparation = 0.11 + kGrabSeparation;
+
+const ClawGoal kTuckGoal = {-2.273474, -0.749484};
+const ClawGoal kVerticalTuckGoal = {0, kGrabSeparation};
+const ClawGoal kIntakeGoal = {-2.24, kGrabSeparation};
+const ClawGoal kIntakeOpenGoal = {-2.0, 1.1};
+
+// TODO(austin): Tune these by hand...
+const ClawGoal kFlippedTuckGoal = {2.733474, -0.75};
+const ClawGoal kFlippedIntakeGoal = {2.0, kGrabSeparation};
+const ClawGoal kFlippedIntakeOpenGoal = {0.95, 1.0};
+
+// 34" between near edge of colored line and rear edge of bumper.
+// Only works running?
+const ShotGoal kLongShotGoal = {
+    {-1.08, kShootSeparation}, 145, 0.04, kIntakePower};
+// old 34" {-1.06, kShootSeparation}, 140, 0.04, kIntakePower};
+const ShotGoal kFlippedLongShotGoal = {
+    {0.96, kShootSeparation}, 145, 0.09, kIntakePower};
+// old 34" {0.96, kShootSeparation}, 140, 0.09, kIntakePower};
+
+// 78" between near edge of colored line and rear edge of bumper.
+const ShotGoal kCloseShotGoal = {
+    {-0.95, kShootSeparation}, 105, 0.2, kIntakePower};
+// 3/4" plunger {-0.90, kShootSeparation}, 105, 0.2, kIntakePower};
+const ShotGoal kFlippedMediumShotGoal = {
+    {0.865, kShootSeparation}, 120, 0.2, kIntakePower};
+// 3/4" plunger {0.80, kShootSeparation}, 105, 0.2, kIntakePower};
+
+// Shot from the fender.
+const ShotGoal kFenderShotGoal = {
+    {-0.68, kShootSeparation}, 115.0, 0.0, kIntakePower};
+const ShotGoal kFlippedShortShotGoal = {
+    {0.63, kShootSeparation}, 115.0, 0.0, kIntakePower};
+
+const ShotGoal kHumanShotGoal = {
+    {-0.90, kShootSeparation}, 140, 0.04, kIntakePower};
+const ShotGoal kFlippedHumanShotGoal = {
+    {0.90, kShootSeparation}, 140, 0, kIntakePower};
+const ShotGoal kTrussShotGoal = {
+    {-0.68, kShootSeparation}, 88.0, 0.4, kIntakePower};
+const ShotGoal kFlippedTrussShotGoal = {
+    {0.68, kShootSeparation}, 92.0, 0.4, kIntakePower};
+
+const ShotGoal kFlippedDemoShotGoal = {
+    {1.0, kShootSeparation}, 65.0, 0.0, kIntakePower};
+const ShotGoal kDemoShotGoal = {
+    {-1.0, kShootSeparation}, 50.0, 0.0, kIntakePower};
+
+const ClawGoal k254PassGoal = {-1.95, kGrabSeparation};
+const ClawGoal kFlipped254PassGoal = {1.96, kGrabSeparation};
+
+class Reader : public ::aos::input::JoystickInput {
+ public:
+  Reader()
+      : is_high_gear_(false),
+        shot_power_(80.0),
+        goal_angle_(0.0),
+        separation_angle_(kGrabSeparation),
+        velocity_compensation_(0.0),
+        intake_power_(0.0),
+        was_running_(false) {}
+
+  void RunIteration(const ::aos::input::driver_station::Data &data) override {
+    bool last_auto_running = auto_running_;
+    auto_running_ = data.GetControlBit(ControlBit::kAutonomous) &&
+                    data.GetControlBit(ControlBit::kEnabled);
+    if (auto_running_ != last_auto_running) {
+      if (auto_running_) {
+        StartAuto();
+      } else {
+        StopAuto();
+      }
+    }
+
+    if (!data.GetControlBit(ControlBit::kAutonomous)) {
+      HandleDrivetrain(data);
+      HandleTeleop(data);
+    }
+  }
+
+  void HandleDrivetrain(const ::aos::input::driver_station::Data &data) {
+    bool is_control_loop_driving = false;
+    double left_goal = 0.0;
+    double right_goal = 0.0;
+    const double wheel = -data.GetAxis(kSteeringWheel);
+    const double throttle = -data.GetAxis(kDriveThrottle);
+    const double kThrottleGain = 1.0 / 2.5;
+    if (false && (data.IsPressed(kDriveControlLoopEnable1) ||
+                  data.IsPressed(kDriveControlLoopEnable2))) {
+      // TODO(austin): Static sucks!
+      static double distance = 0.0;
+      static double angle = 0.0;
+      static double filtered_goal_distance = 0.0;
+      if (data.PosEdge(kDriveControlLoopEnable1) ||
+          data.PosEdge(kDriveControlLoopEnable2)) {
+        if (drivetrain_queue.position.FetchLatest() &&
+            gyro_reading.FetchLatest()) {
+          distance = (drivetrain_queue.position->left_encoder +
+                      drivetrain_queue.position->right_encoder) /
+                         2.0 -
+                     throttle * kThrottleGain / 2.0;
+          angle = gyro_reading->angle;
+          filtered_goal_distance = distance;
+        }
+      }
+      is_control_loop_driving = true;
+
+      // const double gyro_angle = Gyro.View().angle;
+      const double goal_theta = angle - wheel * 0.27;
+      const double goal_distance = distance + throttle * kThrottleGain;
+      const double robot_width = 22.0 / 100.0 * 2.54;
+      const double kMaxVelocity = 0.6;
+      if (goal_distance > kMaxVelocity * 0.02 + filtered_goal_distance) {
+        filtered_goal_distance += kMaxVelocity * 0.02;
+      } else if (goal_distance <
+                 -kMaxVelocity * 0.02 + filtered_goal_distance) {
+        filtered_goal_distance -= kMaxVelocity * 0.02;
+      } else {
+        filtered_goal_distance = goal_distance;
+      }
+      left_goal = filtered_goal_distance - robot_width * goal_theta / 2.0;
+      right_goal = filtered_goal_distance + robot_width * goal_theta / 2.0;
+      is_high_gear_ = false;
+
+      LOG(DEBUG, "Left goal %f Right goal %f\n", left_goal, right_goal);
+    }
+    if (!drivetrain_queue.goal.MakeWithBuilder()
+             .steering(wheel)
+             .throttle(throttle)
+             .highgear(is_high_gear_)
+             .quickturn(data.IsPressed(kQuickTurn))
+             .control_loop_driving(is_control_loop_driving)
+             .left_goal(left_goal)
+             .right_goal(right_goal)
+             .left_velocity_goal(0)
+             .right_velocity_goal(0)
+             .Send()) {
+      LOG(WARNING, "sending stick values failed\n");
+    }
+    if (data.PosEdge(kShiftHigh)) {
+      is_high_gear_ = false;
+    }
+    if (data.PosEdge(kShiftLow)) {
+      is_high_gear_ = true;
+    }
+  }
+
+  void SetGoal(ClawGoal goal) {
+    goal_angle_ = goal.angle;
+    separation_angle_ = goal.separation;
+    moving_for_shot_ = false;
+    velocity_compensation_ = 0.0;
+    intake_power_ = 0.0;
+  }
+
+  void SetGoal(ShotGoal goal) {
+    goal_angle_ = goal.claw.angle;
+    shot_separation_angle_ = goal.claw.separation;
+    separation_angle_ = kGrabSeparation;
+    moving_for_shot_ = true;
+    shot_power_ = goal.shot_power;
+    velocity_compensation_ = goal.velocity_compensation;
+    intake_power_ = goal.intake_power;
+  }
+
+  void HandleTeleop(const ::aos::input::driver_station::Data &data) {
+    if (!data.GetControlBit(ControlBit::kEnabled)) {
+      action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+    }
+    if (data.IsPressed(kRollersIn) || data.IsPressed(kRollersOut)) {
+      intake_power_ = 0.0;
+      separation_angle_ = kGrabSeparation;
+      moving_for_shot_ = false;
+    }
+
+    static const double kAdjustClawGoalDeadband = 0.08;
+    double claw_goal_adjust = data.GetAxis(kAdjustClawGoal);
+    if (OLD_DS || ::std::abs(claw_goal_adjust) < kAdjustClawGoalDeadband) {
+      claw_goal_adjust = 0;
+    } else {
+      claw_goal_adjust = (claw_goal_adjust -
+                          ((claw_goal_adjust < 0) ? -kAdjustClawGoalDeadband
+                                                  : kAdjustClawGoalDeadband)) *
+                         0.035;
+    }
+    double claw_separation_adjust = data.GetAxis(kAdjustClawSeparation);
+    if (OLD_DS ||
+        ::std::abs(claw_separation_adjust) < kAdjustClawGoalDeadband) {
+      claw_separation_adjust = 0;
+    } else {
+      claw_separation_adjust =
+          (claw_separation_adjust -
+           ((claw_separation_adjust < 0) ? -kAdjustClawGoalDeadband
+                                         : kAdjustClawGoalDeadband)) *
+          -0.035;
+    }
+
+#if OLD_DS
+    if (data.IsPressed(kFenderShot)) {
+#else
+    if (data.GetAxis(kFlipRobot) > 0.9) {
+#endif
+      claw_goal_adjust += claw_separation_adjust;
+      claw_goal_adjust *= -1;
+
+      if (data.IsPressed(kIntakeOpenPosition)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlippedIntakeOpenGoal);
+      } else if (data.IsPressed(kIntakePosition)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlippedIntakeGoal);
+      } else if (data.IsPressed(kVerticalTuck)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kVerticalTuckGoal);
+      } else if (data.IsPressed(kTuck)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlippedTuckGoal);
+      } else if (data.PosEdge(kLongShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlippedLongShotGoal);
+      } else if (data.PosEdge(kCloseShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlippedMediumShotGoal);
+      } else if (data.PosEdge(kFenderShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlippedShortShotGoal);
+      } else if (data.PosEdge(kHumanPlayerShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlippedHumanShotGoal);
+      } else if (data.PosEdge(kUserLeft)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlipped254PassGoal);
+      } else if (data.PosEdge(kUserRight)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlippedDemoShotGoal);
+      } else if (data.PosEdge(kTrussShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFlippedTrussShotGoal);
+      }
+    } else {
+      if (data.IsPressed(kIntakeOpenPosition)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kIntakeOpenGoal);
+      } else if (data.IsPressed(kIntakePosition)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kIntakeGoal);
+      } else if (data.IsPressed(kVerticalTuck)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kVerticalTuckGoal);
+      } else if (data.IsPressed(kTuck)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kTuckGoal);
+      } else if (data.PosEdge(kLongShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kLongShotGoal);
+      } else if (data.PosEdge(kCloseShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kCloseShotGoal);
+      } else if (data.PosEdge(kFenderShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kFenderShotGoal);
+      } else if (data.PosEdge(kHumanPlayerShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kHumanShotGoal);
+      } else if (data.PosEdge(kUserLeft)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(k254PassGoal);
+      } else if (data.PosEdge(kUserRight)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kDemoShotGoal);
+      } else if (data.PosEdge(kTrussShot)) {
+        action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+        SetGoal(kTrussShotGoal);
+      }
+    }
+
+    if (data.PosEdge(kFire)) {
+      action_queue_.EnqueueAction(actors::MakeShootAction());
+    } else if (data.NegEdge(kFire)) {
+      action_queue_.CancelCurrentAction();
+    }
+
+    action_queue_.Tick();
+    if (data.IsPressed(kUnload) || data.IsPressed(kReload)) {
+      action_queue_.CancelAllActions();
+        LOG(DEBUG, "Canceling\n");
+      intake_power_ = 0.0;
+      velocity_compensation_ = 0.0;
+    }
+
+    // Send out the claw and shooter goals if no actions are running.
+    if (!action_queue_.Running()) {
+      goal_angle_ += claw_goal_adjust;
+      separation_angle_ += claw_separation_adjust;
+
+      // If the action just ended, turn the intake off and stop velocity
+      // compensating.
+      if (was_running_) {
+        intake_power_ = 0.0;
+        velocity_compensation_ = 0.0;
+      }
+
+      control_loops::drivetrain_queue.status.FetchLatest();
+      double goal_angle = goal_angle_;
+      if (control_loops::drivetrain_queue.status.get()) {
+        goal_angle += SpeedToAngleOffset(
+            control_loops::drivetrain_queue.status->robot_speed);
+      } else {
+        LOG_INTERVAL(no_drivetrain_status_);
+      }
+
+      if (moving_for_shot_) {
+        auto &claw_status = control_loops::claw_queue.status;
+        claw_status.FetchLatest();
+        if (claw_status.get()) {
+          if (::std::abs(claw_status->bottom - goal_angle) < 0.2) {
+            moving_for_shot_ = false;
+            separation_angle_ = shot_separation_angle_;
+          }
+        }
+      }
+
+      double separation_angle = separation_angle_;
+
+      if (data.IsPressed(kCatch)) {
+        const double kCatchSeparation = 1.0;
+        goal_angle -= kCatchSeparation / 2.0;
+        separation_angle = kCatchSeparation;
+      }
+
+      bool intaking =
+          data.IsPressed(kRollersIn) || data.IsPressed(kIntakePosition) ||
+          data.IsPressed(kIntakeOpenPosition) || data.IsPressed(kCatch);
+      if (!control_loops::claw_queue.goal.MakeWithBuilder()
+               .bottom_angle(goal_angle)
+               .separation_angle(separation_angle)
+               .intake(intaking ? 12.0
+                                : (data.IsPressed(kRollersOut) ? -12.0
+                                                               : intake_power_))
+               .centering(intaking ? 12.0 : 0.0)
+               .Send()) {
+        LOG(WARNING, "sending claw goal failed\n");
+      }
+
+      if (!control_loops::shooter_queue.goal.MakeWithBuilder()
+               .shot_power(shot_power_)
+               .shot_requested(data.IsPressed(kFire))
+               .unload_requested(data.IsPressed(kUnload))
+               .load_requested(data.IsPressed(kReload))
+               .Send()) {
+        LOG(WARNING, "sending shooter goal failed\n");
+      }
+    }
+    was_running_ = action_queue_.Running();
+  }
+
+  double SpeedToAngleOffset(double speed) {
+    const frc971::constants::Values &values = frc971::constants::GetValues();
+    // scale speed to a [0.0-1.0] on something close to the max
+    // TODO(austin): Change the scale factor for different shots.
+    return (speed / values.drivetrain_max_speed) * velocity_compensation_;
+  }
+
+ private:
+  void StartAuto() {
+    LOG(INFO, "Starting auto mode\n");
+    ::frc971::autonomous::autonomous.MakeWithBuilder().run_auto(true).Send();
+  }
+
+  void StopAuto() {
+    LOG(INFO, "Stopping auto mode\n");
+    ::frc971::autonomous::autonomous.MakeWithBuilder().run_auto(false).Send();
+  }
+
+  bool is_high_gear_;
+  double shot_power_;
+  double goal_angle_;
+  double separation_angle_, shot_separation_angle_;
+  double velocity_compensation_;
+  double intake_power_;
+  bool was_running_;
+  bool moving_for_shot_ = false;
+
+  bool auto_running_ = false;
+  
+  ::aos::common::actions::ActionQueue action_queue_;
+
+  ::aos::util::SimpleLogInterval no_drivetrain_status_ =
+      ::aos::util::SimpleLogInterval(::aos::time::Time::InSeconds(0.2), WARNING,
+                                     "no drivetrain status");
+};
+
+}  // namespace joysticks
+}  // namespace input
+}  // namespace frc971
+
+int main() {
+  ::aos::Init();
+  ::frc971::input::joysticks::Reader reader;
+  reader.Run();
+  ::aos::Cleanup();
+}
diff --git a/y2014/prime/build.sh b/y2014/prime/build.sh
new file mode 100755
index 0000000..f83d9f4
--- /dev/null
+++ b/y2014/prime/build.sh
@@ -0,0 +1,5 @@
+#!/bin/bash
+
+cd $(dirname $0)
+
+exec ../../aos/build/build.py $0 prime y2014 prime.gyp "$@"
diff --git a/y2014/prime/compile_loop.sh b/y2014/prime/compile_loop.sh
new file mode 100755
index 0000000..de6b0d3
--- /dev/null
+++ b/y2014/prime/compile_loop.sh
@@ -0,0 +1,16 @@
+#!/bin/bash
+
+# Runs `build.sh all` and then waits for a file to be modified in a loop.
+# Useful for making changes to the code while continuously making sure they
+# compile.
+# Requires the util-linux and inotify-tools packages.
+
+chrt -i -p 0 $$
+ionice -c 3 -p $$
+
+while true; do
+	$(dirname $0)/build.sh all
+	echo 'compile_loop.sh: Waiting for a file modification...' 1>&2
+	inotifywait -e close_write -r aos frc971 bbb_cape
+	echo 'compile_loop.sh: Done waiting for a file modification' 1>&2
+done
diff --git a/y2014/prime/hot_goal_reader.cc b/y2014/prime/hot_goal_reader.cc
new file mode 100644
index 0000000..ffdb3a3
--- /dev/null
+++ b/y2014/prime/hot_goal_reader.cc
@@ -0,0 +1,108 @@
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <errno.h>
+#include <string.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+
+#include "aos/common/time.h"
+#include "aos/common/logging/queue_logging.h"
+#include "aos/common/logging/logging.h"
+#include "aos/linux_code/init.h"
+#include "aos/common/byteorder.h"
+
+#include "y2014/queues/hot_goal.q.h"
+
+int main() {
+  ::aos::InitNRT();
+
+  uint64_t left_count, right_count;
+  ::frc971::hot_goal.FetchLatest();
+  if (::frc971::hot_goal.get()) {
+    LOG_STRUCT(DEBUG, "starting with", *::frc971::hot_goal);
+    left_count = ::frc971::hot_goal->left_count;
+    right_count = ::frc971::hot_goal->left_count;
+  } else {
+    LOG(DEBUG, "no starting message\n");
+    left_count = right_count = 0;
+  }
+
+  int my_socket = -1;
+  while (true) {
+    if (my_socket == -1) {
+      my_socket = socket(AF_INET, SOCK_STREAM, 0);
+      if (my_socket == -1) {
+        PLOG(WARNING, "socket(AF_INET, SOCK_STREAM, 0) failed");
+        continue;
+      } else {
+        LOG(INFO, "opened socket (is %d)\n", my_socket);
+        sockaddr_in address, *sockaddr_pointer;
+        memset(&address, 0, sizeof(address));
+        address.sin_family = AF_INET;
+        address.sin_port = ::aos::hton<uint16_t>(1180);
+        sockaddr *address_pointer;
+        sockaddr_pointer = &address;
+        memcpy(&address_pointer, &sockaddr_pointer, sizeof(void *));
+        if (bind(my_socket, address_pointer, sizeof(address)) == -1) {
+          PLOG(WARNING, "bind(%d, %p, %zu) failed",
+               my_socket, &address, sizeof(address));
+          close(my_socket);
+          my_socket = -1;
+          continue;
+        }
+
+        if (listen(my_socket, 1) == -1) {
+          PLOG(WARNING, "listen(%d, 1) failed", my_socket);
+          close(my_socket);
+          my_socket = -1;
+          continue;
+        }
+      }
+    }
+
+    int connection = accept4(my_socket, nullptr, nullptr, SOCK_NONBLOCK);
+    if (connection == -1) {
+      PLOG(WARNING, "accept(%d, nullptr, nullptr) failed", my_socket);
+      continue;
+    }
+    LOG(INFO, "accepted (is %d)\n", connection);
+
+    while (connection != -1) {
+      fd_set fds;
+      FD_ZERO(&fds);
+      FD_SET(connection, &fds);
+      struct timeval timeout_timeval =
+          ::aos::time::Time::InSeconds(1).ToTimeval();
+      switch (
+          select(connection + 1, &fds, nullptr, nullptr, &timeout_timeval)) {
+        case 1: {
+          uint8_t data;
+          ssize_t read_bytes = read(connection, &data, sizeof(data));
+          if (read_bytes != sizeof(data)) {
+            LOG(WARNING, "read %zd bytes instead of %zd\n", read_bytes,
+                sizeof(data));
+            break;
+          }
+          if (data & 0x01) ++right_count;
+          if (data & 0x02) ++left_count;
+          auto message = ::frc971::hot_goal.MakeMessage();
+          message->left_count = left_count;
+          message->right_count = right_count;
+          LOG_STRUCT(DEBUG, "sending", *message);
+          message.Send();
+        } break;
+        case 0:
+          LOG(WARNING, "read on %d timed out\n", connection);
+          close(connection);
+          connection = -1;
+          break;
+        default:
+          PLOG(FATAL,
+               "select(%d, %p, nullptr, nullptr, %p) failed",
+               connection + 1, &fds, &timeout_timeval);
+      }
+    }
+  }
+
+  LOG(FATAL, "finished???\n");
+}
diff --git a/y2014/prime/prime.gyp b/y2014/prime/prime.gyp
new file mode 100644
index 0000000..a64fc1c
--- /dev/null
+++ b/y2014/prime/prime.gyp
@@ -0,0 +1,55 @@
+{
+  'targets': [
+    {
+      'target_name': 'All',
+      'type': 'none',
+      'dependencies': [
+        '../../frc971/frc971.gyp:All',
+
+        '../control_loops/drivetrain/drivetrain.gyp:drivetrain',
+        '../control_loops/drivetrain/drivetrain.gyp:drivetrain_lib_test',
+        '../control_loops/drivetrain/drivetrain.gyp:replay_drivetrain',
+        '../control_loops/claw/claw.gyp:claw',
+        '../control_loops/claw/claw.gyp:claw_calibration',
+        '../control_loops/claw/claw.gyp:claw_lib_test',
+        '../control_loops/claw/claw.gyp:replay_claw',
+        '../control_loops/shooter/shooter.gyp:shooter',
+        '../control_loops/shooter/shooter.gyp:shooter_lib_test',
+        '../control_loops/shooter/shooter.gyp:replay_shooter',
+        '../autonomous/autonomous.gyp:auto',
+        '../y2014.gyp:joystick_reader',
+        '../actors/actors.gyp:binaries',
+        'hot_goal_reader',
+      ],
+      'copies': [
+        {
+          'destination': '<(rsync_dir)',
+          'files': [
+            'start_list.txt',
+          ],
+        },
+      ],
+      'conditions': [
+        ['ARCHITECTURE=="arm_frc"', {
+          'dependencies': [
+            '../wpilib/wpilib.gyp:wpilib_interface',
+          ],
+        }],
+      ],
+    },
+    {
+      'target_name': 'hot_goal_reader',
+      'type': 'executable',
+      'sources': [
+        'hot_goal_reader.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/common/common.gyp:time',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        '<(DEPTH)/y2014/queues/queues.gyp:hot_goal'
+      ],
+    },
+  ],
+}
diff --git a/y2014/prime/start_list.txt b/y2014/prime/start_list.txt
new file mode 100644
index 0000000..276aca8
--- /dev/null
+++ b/y2014/prime/start_list.txt
@@ -0,0 +1,13 @@
+binary_log_writer
+motor_writer
+joystick_reader
+drivetrain
+auto
+sensor_receiver
+joystick_proxy
+claw
+shooter
+shoot_action
+drivetrain_action
+catch_action
+hot_goal_reader
diff --git a/y2014/queues/auto_mode.q b/y2014/queues/auto_mode.q
new file mode 100644
index 0000000..7922dbf
--- /dev/null
+++ b/y2014/queues/auto_mode.q
@@ -0,0 +1,6 @@
+package frc971.sensors;
+
+message AutoMode {
+	double voltage;
+};
+queue AutoMode auto_mode;
diff --git a/y2014/queues/hot_goal.q b/y2014/queues/hot_goal.q
new file mode 100644
index 0000000..3444553
--- /dev/null
+++ b/y2014/queues/hot_goal.q
@@ -0,0 +1,7 @@
+package frc971;
+
+message HotGoal {
+	uint64_t left_count;
+	uint64_t right_count;
+};
+queue HotGoal hot_goal;
diff --git a/y2014/queues/profile_params.q b/y2014/queues/profile_params.q
new file mode 100644
index 0000000..e7ffe9a
--- /dev/null
+++ b/y2014/queues/profile_params.q
@@ -0,0 +1,6 @@
+package frc971;
+
+struct ProfileParams {
+  double velocity;
+  double acceleration;
+};
diff --git a/y2014/queues/queues.gyp b/y2014/queues/queues.gyp
new file mode 100644
index 0000000..1325384
--- /dev/null
+++ b/y2014/queues/queues.gyp
@@ -0,0 +1,37 @@
+{
+  'targets': [
+    {
+      'target_name': 'profile_params',
+      'type': 'static_library',
+      'sources': [
+        'profile_params.q',
+      ],
+      'variables': {
+        'header_path': 'y2014/queues',
+      },
+      'includes': ['../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'hot_goal',
+      'type': 'static_library',
+      'sources': [
+        'hot_goal.q',
+      ],
+      'variables': {
+        'header_path': 'y2014/queues',
+      },
+      'includes': ['../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'auto_mode',
+      'type': 'static_library',
+      'sources': [
+        'auto_mode.q',
+      ],
+      'variables': {
+        'header_path': 'y2014/queues',
+      },
+      'includes': ['../../aos/build/queues.gypi'],
+    },
+  ],
+}
diff --git a/y2014/wpilib/wpilib.gyp b/y2014/wpilib/wpilib.gyp
new file mode 100644
index 0000000..d563d08
--- /dev/null
+++ b/y2014/wpilib/wpilib.gyp
@@ -0,0 +1,38 @@
+{
+  'targets': [
+    {
+      'target_name': 'wpilib_interface',
+      'type': 'executable',
+      'sources': [
+        'wpilib_interface.cc'
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        '<(AOS)/common/common.gyp:stl_mutex',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(EXTERNALS):WPILib',
+        '<(DEPTH)/frc971/frc971.gyp:constants',
+        '<(DEPTH)/frc971/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
+        '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
+        '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(AOS)/common/util/util.gyp:log_interval',
+        '<(AOS)/common/common.gyp:time',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+        '<(AOS)/common/messages/messages.gyp:robot_state',
+        '<(AOS)/common/util/util.gyp:phased_loop',
+        '<(AOS)/common/messages/messages.gyp:robot_state',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:hall_effect',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:joystick_sender',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:loop_output_handler',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:buffered_pcm',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:gyro_sender',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:dma_edge_counting',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:interrupt_edge_counting',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:encoder_and_potentiometer',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:logging_queue',
+      ],
+    },
+  ],
+}
diff --git a/y2014/wpilib/wpilib_interface.cc b/y2014/wpilib/wpilib_interface.cc
new file mode 100644
index 0000000..1c141a8
--- /dev/null
+++ b/y2014/wpilib/wpilib_interface.cc
@@ -0,0 +1,716 @@
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+#include <inttypes.h>
+
+#include <thread>
+#include <mutex>
+#include <functional>
+
+#include "aos/common/logging/logging.h"
+#include "aos/common/logging/queue_logging.h"
+#include "aos/common/time.h"
+#include "aos/common/util/log_interval.h"
+#include "aos/common/util/phased_loop.h"
+#include "aos/common/util/wrapping_counter.h"
+#include "aos/common/stl_mutex.h"
+#include "aos/linux_code/init.h"
+#include "aos/common/messages/robot_state.q.h"
+
+#include "y2014/constants.h"
+#include "frc971/control_loops/control_loops.q.h"
+#include "y2014/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/control_loops/fridge/fridge.q.h"
+#include "y2014/control_loops/claw/claw.q.h"
+
+#include "frc971/wpilib/hall_effect.h"
+#include "frc971/wpilib/joystick_sender.h"
+#include "frc971/wpilib/loop_output_handler.h"
+#include "frc971/wpilib/buffered_solenoid.h"
+#include "frc971/wpilib/buffered_pcm.h"
+#include "frc971/wpilib/gyro_sender.h"
+#include "frc971/wpilib/dma_edge_counting.h"
+#include "frc971/wpilib/interrupt_edge_counting.h"
+#include "frc971/wpilib/encoder_and_potentiometer.h"
+#include "frc971/wpilib/logging.q.h"
+
+#include "Encoder.h"
+#include "Talon.h"
+#include "DriverStation.h"
+#include "AnalogInput.h"
+#include "Compressor.h"
+#include "Relay.h"
+#include "RobotBase.h"
+#include "dma.h"
+#include "ControllerPower.h"
+
+#ifndef M_PI
+#define M_PI 3.14159265358979323846
+#endif
+
+using ::aos::util::SimpleLogInterval;
+using ::frc971::control_loops::drivetrain_queue;
+using ::frc971::control_loops::fridge_queue;
+using ::frc971::control_loops::claw_queue;
+
+namespace frc971 {
+namespace wpilib {
+
+double drivetrain_translate(int32_t in) {
+  return static_cast<double>(in) /
+         (256.0 /*cpr*/ * 4.0 /*4x*/) *
+         constants::GetValues().drivetrain_encoder_ratio *
+         (4 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
+}
+
+double arm_translate(int32_t in) {
+  return -static_cast<double>(in) /
+          (512.0 /*cpr*/ * 4.0 /*4x*/) *
+          constants::GetValues().arm_encoder_ratio *
+          (2 * M_PI /*radians*/);
+}
+
+double arm_potentiometer_translate(double voltage) {
+  return voltage *
+          constants::GetValues().arm_pot_ratio *
+          (5.0 /*turns*/ / 5.0 /*volts*/) *
+          (2 * M_PI /*radians*/);
+}
+
+double elevator_translate(int32_t in) {
+  return static_cast<double>(in) /
+          (512.0 /*cpr*/ * 4.0 /*4x*/) *
+          constants::GetValues().elev_encoder_ratio *
+          (2 * M_PI /*radians*/) *
+          constants::GetValues().elev_distance_per_radian;
+}
+
+double elevator_potentiometer_translate(double voltage) {
+  return -voltage *
+          constants::GetValues().elev_pot_ratio *
+          (2 * M_PI /*radians*/) *
+          constants::GetValues().elev_distance_per_radian *
+          (5.0 /*turns*/ / 5.0 /*volts*/);
+}
+
+double claw_translate(int32_t in) {
+  return static_cast<double>(in) /
+          (512.0 /*cpr*/ * 4.0 /*4x*/) *
+          constants::GetValues().claw_encoder_ratio *
+          (2 * M_PI /*radians*/);
+}
+
+double claw_potentiometer_translate(double voltage) {
+  return -voltage *
+          constants::GetValues().claw_pot_ratio *
+          (5.0 /*turns*/ / 5.0 /*volts*/) *
+          (2 * M_PI /*radians*/);
+}
+
+static const double kMaximumEncoderPulsesPerSecond =
+    19500.0 /* free speed RPM */ * 12.0 / 56.0 /* belt reduction */ /
+    60.0 /* seconds / minute */ * 256.0 /* CPR */ *
+    4.0 /* index pulse = 1/4 cycle */;
+
+class SensorReader {
+ public:
+  SensorReader() {
+    // Set it to filter out anything shorter than 1/4 of the minimum pulse width
+    // we should ever see.
+    filter_.SetPeriodNanoSeconds(
+        static_cast<int>(1 / 4.0 / kMaximumEncoderPulsesPerSecond * 1e9 + 0.5));
+  }
+
+  void set_arm_left_encoder(::std::unique_ptr<Encoder> encoder) {
+    filter_.Add(encoder.get());
+    arm_left_encoder_.set_encoder(::std::move(encoder));
+  }
+
+  void set_arm_left_index(::std::unique_ptr<DigitalSource> index) {
+    filter_.Add(index.get());
+    arm_left_encoder_.set_index(::std::move(index));
+  }
+
+  void set_arm_left_potentiometer(
+      ::std::unique_ptr<AnalogInput> potentiometer) {
+    arm_left_encoder_.set_potentiometer(::std::move(potentiometer));
+  }
+
+  void set_arm_right_encoder(::std::unique_ptr<Encoder> encoder) {
+    filter_.Add(encoder.get());
+    arm_right_encoder_.set_encoder(::std::move(encoder));
+  }
+
+  void set_arm_right_index(::std::unique_ptr<DigitalSource> index) {
+    filter_.Add(index.get());
+    arm_right_encoder_.set_index(::std::move(index));
+  }
+
+  void set_arm_right_potentiometer(
+      ::std::unique_ptr<AnalogInput> potentiometer) {
+    arm_right_encoder_.set_potentiometer(::std::move(potentiometer));
+  }
+
+  void set_elevator_left_encoder(::std::unique_ptr<Encoder> encoder) {
+    filter_.Add(encoder.get());
+    elevator_left_encoder_.set_encoder(::std::move(encoder));
+  }
+
+  void set_elevator_left_index(::std::unique_ptr<DigitalSource> index) {
+    filter_.Add(index.get());
+    elevator_left_encoder_.set_index(::std::move(index));
+  }
+
+  void set_elevator_left_potentiometer(
+      ::std::unique_ptr<AnalogInput> potentiometer) {
+    elevator_left_encoder_.set_potentiometer(::std::move(potentiometer));
+  }
+
+  void set_elevator_right_encoder(::std::unique_ptr<Encoder> encoder) {
+    filter_.Add(encoder.get());
+    elevator_right_encoder_.set_encoder(::std::move(encoder));
+  }
+
+  void set_elevator_right_index(::std::unique_ptr<DigitalSource> index) {
+    filter_.Add(index.get());
+    elevator_right_encoder_.set_index(::std::move(index));
+  }
+
+  void set_elevator_right_potentiometer(
+      ::std::unique_ptr<AnalogInput> potentiometer) {
+    elevator_right_encoder_.set_potentiometer(::std::move(potentiometer));
+  }
+
+  void set_wrist_encoder(::std::unique_ptr<Encoder> encoder) {
+    filter_.Add(encoder.get());
+    wrist_encoder_.set_encoder(::std::move(encoder));
+  }
+
+  void set_wrist_index(::std::unique_ptr<DigitalSource> index) {
+    filter_.Add(index.get());
+    wrist_encoder_.set_index(::std::move(index));
+  }
+
+  void set_wrist_potentiometer(::std::unique_ptr<AnalogInput> potentiometer) {
+    wrist_encoder_.set_potentiometer(::std::move(potentiometer));
+  }
+
+  void set_left_encoder(::std::unique_ptr<Encoder> left_encoder) {
+    left_encoder_ = ::std::move(left_encoder);
+  }
+
+  void set_right_encoder(::std::unique_ptr<Encoder> right_encoder) {
+    right_encoder_ = ::std::move(right_encoder);
+  }
+
+  // All of the DMA-related set_* calls must be made before this, and it doesn't
+  // hurt to do all of them.
+  void set_dma(::std::unique_ptr<DMA> dma) {
+    dma_synchronizer_.reset(new DMASynchronizer(::std::move(dma)));
+    dma_synchronizer_->Add(&arm_left_encoder_);
+    dma_synchronizer_->Add(&elevator_left_encoder_);
+    dma_synchronizer_->Add(&arm_right_encoder_);
+    dma_synchronizer_->Add(&elevator_right_encoder_);
+  }
+
+  void operator()() {
+    LOG(INFO, "In sensor reader thread\n");
+    ::aos::SetCurrentThreadName("SensorReader");
+
+    my_pid_ = getpid();
+    ds_ = DriverStation::GetInstance();
+
+    wrist_encoder_.Start();
+    dma_synchronizer_->Start();
+    LOG(INFO, "Things are now started\n");
+
+    ::aos::SetCurrentThreadRealtimePriority(kPriority);
+    while (run_) {
+      ::aos::time::PhasedLoopXMS(5, 4000);
+      RunIteration();
+    }
+
+    wrist_encoder_.Stop();
+  }
+
+  void RunIteration() {
+    {
+      auto new_state = ::aos::robot_state.MakeMessage();
+
+      new_state->reader_pid = my_pid_;
+      new_state->outputs_enabled = ds_->IsSysActive();
+      new_state->browned_out = ds_->IsSysBrownedOut();
+
+      new_state->is_3v3_active = ControllerPower::GetEnabled3V3();
+      new_state->is_5v_active = ControllerPower::GetEnabled5V();
+      new_state->voltage_3v3 = ControllerPower::GetVoltage3V3();
+      new_state->voltage_5v = ControllerPower::GetVoltage5V();
+
+      new_state->voltage_roborio_in = ControllerPower::GetInputVoltage();
+      new_state->voltage_battery = ds_->GetBatteryVoltage();
+
+      LOG_STRUCT(DEBUG, "robot_state", *new_state);
+
+      new_state.Send();
+    }
+
+    {
+      auto drivetrain_message = drivetrain_queue.position.MakeMessage();
+      drivetrain_message->right_encoder =
+          -drivetrain_translate(right_encoder_->GetRaw());
+      drivetrain_message->left_encoder =
+          drivetrain_translate(left_encoder_->GetRaw());
+
+      drivetrain_message.Send();
+    }
+
+    dma_synchronizer_->RunIteration();
+
+    const auto &values = constants::GetValues();
+
+    {
+      auto fridge_message = fridge_queue.position.MakeMessage();
+      CopyPotAndIndexPosition(arm_left_encoder_, &fridge_message->arm.left,
+                              arm_translate, arm_potentiometer_translate, false,
+                              values.fridge.left_arm_potentiometer_offset);
+      CopyPotAndIndexPosition(
+          arm_right_encoder_, &fridge_message->arm.right, arm_translate,
+          arm_potentiometer_translate, true,
+          values.fridge.right_arm_potentiometer_offset);
+      CopyPotAndIndexPosition(
+          elevator_left_encoder_, &fridge_message->elevator.left,
+          elevator_translate, elevator_potentiometer_translate, false,
+          values.fridge.left_elevator_potentiometer_offset);
+      CopyPotAndIndexPosition(
+          elevator_right_encoder_, &fridge_message->elevator.right,
+          elevator_translate, elevator_potentiometer_translate, true,
+          values.fridge.right_elevator_potentiometer_offset);
+      fridge_message.Send();
+    }
+
+    {
+      auto claw_message = claw_queue.position.MakeMessage();
+      CopyPotAndIndexPosition(wrist_encoder_, &claw_message->joint,
+                              claw_translate, claw_potentiometer_translate,
+                              false, values.claw.potentiometer_offset);
+      claw_message.Send();
+    }
+  }
+
+  void Quit() { run_ = false; }
+
+ private:
+  static const int kPriority = 30;
+  static const int kInterruptPriority = 55;
+
+  int32_t my_pid_;
+  DriverStation *ds_;
+
+  void CopyPotAndIndexPosition(
+      const DMAEncoderAndPotentiometer &encoder, PotAndIndexPosition *position,
+      ::std::function<double(int32_t)> encoder_translate,
+      ::std::function<double(double)> potentiometer_translate, bool reverse,
+      double potentiometer_offset) {
+    const double multiplier = reverse ? -1.0 : 1.0;
+    position->encoder =
+        multiplier * encoder_translate(encoder.polled_encoder_value());
+    position->pot = multiplier * potentiometer_translate(
+                                     encoder.polled_potentiometer_voltage()) +
+                    potentiometer_offset;
+    position->latched_encoder =
+        multiplier * encoder_translate(encoder.last_encoder_value());
+    position->latched_pot =
+        multiplier *
+            potentiometer_translate(encoder.last_potentiometer_voltage()) +
+        potentiometer_offset;
+    position->index_pulses = encoder.index_posedge_count();
+  }
+
+  void CopyPotAndIndexPosition(
+      const InterruptEncoderAndPotentiometer &encoder,
+      PotAndIndexPosition *position,
+      ::std::function<double(int32_t)> encoder_translate,
+      ::std::function<double(double)> potentiometer_translate, bool reverse,
+      double potentiometer_offset) {
+    const double multiplier = reverse ? -1.0 : 1.0;
+    position->encoder =
+        multiplier * encoder_translate(encoder.encoder()->GetRaw());
+    position->pot = multiplier * potentiometer_translate(
+                                     encoder.potentiometer()->GetVoltage()) +
+                    potentiometer_offset;
+    position->latched_encoder =
+        multiplier * encoder_translate(encoder.last_encoder_value());
+    position->latched_pot =
+        multiplier *
+            potentiometer_translate(encoder.last_potentiometer_voltage()) +
+        potentiometer_offset;
+    position->index_pulses = encoder.index_posedge_count();
+  }
+
+  ::std::unique_ptr<DMASynchronizer> dma_synchronizer_;
+
+  DMAEncoderAndPotentiometer arm_left_encoder_, arm_right_encoder_,
+      elevator_left_encoder_, elevator_right_encoder_;
+
+  InterruptEncoderAndPotentiometer wrist_encoder_{kInterruptPriority};
+
+  ::std::unique_ptr<Encoder> left_encoder_;
+  ::std::unique_ptr<Encoder> right_encoder_;
+
+  ::std::atomic<bool> run_{true};
+  DigitalGlitchFilter filter_;
+};
+
+class SolenoidWriter {
+ public:
+  SolenoidWriter(const ::std::unique_ptr<BufferedPcm> &pcm)
+      : pcm_(pcm),
+        fridge_(".frc971.control_loops.fridge_queue.output"),
+        claw_(".frc971.control_loops.claw_queue.output") {}
+
+  void set_pressure_switch(::std::unique_ptr<DigitalSource> pressure_switch) {
+    pressure_switch_ = ::std::move(pressure_switch);
+  }
+
+  void set_compressor_relay(::std::unique_ptr<Relay> compressor_relay) {
+    compressor_relay_ = ::std::move(compressor_relay);
+  }
+
+  void set_fridge_grabbers_top_front(::std::unique_ptr<BufferedSolenoid> s) {
+    fridge_grabbers_top_front_ = ::std::move(s);
+  }
+
+  void set_fridge_grabbers_top_back(::std::unique_ptr<BufferedSolenoid> s) {
+    fridge_grabbers_top_back_ = ::std::move(s);
+  }
+
+  void set_fridge_grabbers_bottom_front(
+      ::std::unique_ptr<BufferedSolenoid> s) {
+    fridge_grabbers_bottom_front_ = ::std::move(s);
+  }
+
+  void set_fridge_grabbers_bottom_back(
+      ::std::unique_ptr<BufferedSolenoid> s) {
+    fridge_grabbers_bottom_back_ = ::std::move(s);
+  }
+
+  void set_claw_pinchers(::std::unique_ptr<BufferedSolenoid> s) {
+    claw_pinchers_ = ::std::move(s);
+  }
+
+  void set_grabber_latch_release(::std::unique_ptr<BufferedSolenoid> s) {
+    grabber_latch_release_ = ::std::move(s);
+  }
+
+  void set_grabber_fold_up(::std::unique_ptr<BufferedSolenoid> s) {
+    grabber_fold_up_ = ::std::move(s);
+  }
+
+  void operator()() {
+    ::aos::SetCurrentThreadName("Solenoids");
+    ::aos::SetCurrentThreadRealtimePriority(30);
+
+    while (run_) {
+      ::aos::time::PhasedLoopXMS(20, 1000);
+
+      {
+        fridge_.FetchLatest();
+        if (fridge_.get()) {
+          LOG_STRUCT(DEBUG, "solenoids", *fridge_);
+          fridge_grabbers_top_front_->Set(!fridge_->grabbers.top_front);
+          fridge_grabbers_top_back_->Set(!fridge_->grabbers.top_back);
+          fridge_grabbers_bottom_front_->Set(!fridge_->grabbers.bottom_front);
+          fridge_grabbers_bottom_back_->Set(!fridge_->grabbers.bottom_back);
+        }
+      }
+
+      {
+        claw_.FetchLatest();
+        if (claw_.get()) {
+          LOG_STRUCT(DEBUG, "solenoids", *claw_);
+          claw_pinchers_->Set(claw_->rollers_closed);
+        }
+      }
+
+      ::aos::joystick_state.FetchLatest();
+      grabber_latch_release_->Set(::aos::joystick_state.get() != nullptr &&
+                                  ::aos::joystick_state->autonomous);
+      grabber_fold_up_->Set(::aos::joystick_state.get() != nullptr &&
+                            ::aos::joystick_state->joysticks[1].buttons & 1);
+
+      {
+        PneumaticsToLog to_log;
+        {
+          const bool compressor_on = !pressure_switch_->Get();
+          to_log.compressor_on = compressor_on;
+          if (compressor_on) {
+            compressor_relay_->Set(Relay::kForward);
+          } else {
+            compressor_relay_->Set(Relay::kOff);
+          }
+        }
+
+        pcm_->Flush();
+        to_log.read_solenoids = pcm_->GetAll();
+        LOG_STRUCT(DEBUG, "pneumatics info", to_log);
+      }
+    }
+  }
+
+  void Quit() { run_ = false; }
+
+ private:
+  const ::std::unique_ptr<BufferedPcm> &pcm_;
+  ::std::unique_ptr<BufferedSolenoid> fridge_grabbers_top_front_;
+  ::std::unique_ptr<BufferedSolenoid> fridge_grabbers_top_back_;
+  ::std::unique_ptr<BufferedSolenoid> fridge_grabbers_bottom_front_;
+  ::std::unique_ptr<BufferedSolenoid> fridge_grabbers_bottom_back_;
+  ::std::unique_ptr<BufferedSolenoid> claw_pinchers_;
+  ::std::unique_ptr<BufferedSolenoid> grabber_latch_release_;
+  ::std::unique_ptr<BufferedSolenoid> grabber_fold_up_;
+  ::std::unique_ptr<DigitalSource> pressure_switch_;
+  ::std::unique_ptr<Relay> compressor_relay_;
+
+  ::aos::Queue<::frc971::control_loops::FridgeQueue::Output> fridge_;
+  ::aos::Queue<::frc971::control_loops::ClawQueue::Output> claw_;
+
+  ::std::atomic<bool> run_{true};
+};
+
+class DrivetrainWriter : public LoopOutputHandler {
+ public:
+  void set_left_drivetrain_talon(::std::unique_ptr<Talon> t) {
+    left_drivetrain_talon_ = ::std::move(t);
+  }
+
+  void set_right_drivetrain_talon(::std::unique_ptr<Talon> t) {
+    right_drivetrain_talon_ = ::std::move(t);
+  }
+
+ private:
+  virtual void Read() override {
+    ::frc971::control_loops::drivetrain_queue.output.FetchAnother();
+  }
+
+  virtual void Write() override {
+    auto &queue = ::frc971::control_loops::drivetrain_queue.output;
+    LOG_STRUCT(DEBUG, "will output", *queue);
+    left_drivetrain_talon_->Set(queue->left_voltage / 12.0);
+    right_drivetrain_talon_->Set(-queue->right_voltage / 12.0);
+  }
+
+  virtual void Stop() override {
+    LOG(WARNING, "drivetrain output too old\n");
+    left_drivetrain_talon_->Disable();
+    right_drivetrain_talon_->Disable();
+  }
+
+  ::std::unique_ptr<Talon> left_drivetrain_talon_;
+  ::std::unique_ptr<Talon> right_drivetrain_talon_;
+};
+
+class FridgeWriter : public LoopOutputHandler {
+ public:
+  void set_left_arm_talon(::std::unique_ptr<Talon> t) {
+    left_arm_talon_ = ::std::move(t);
+  }
+
+  void set_right_arm_talon(::std::unique_ptr<Talon> t) {
+    right_arm_talon_ = ::std::move(t);
+  }
+
+  void set_left_elevator_talon(::std::unique_ptr<Talon> t) {
+    left_elevator_talon_ = ::std::move(t);
+  }
+
+  void set_right_elevator_talon(::std::unique_ptr<Talon> t) {
+    right_elevator_talon_ = ::std::move(t);
+  }
+
+ private:
+  virtual void Read() override {
+    ::frc971::control_loops::fridge_queue.output.FetchAnother();
+  }
+
+  virtual void Write() override {
+    auto &queue = ::frc971::control_loops::fridge_queue.output;
+    LOG_STRUCT(DEBUG, "will output", *queue);
+    left_arm_talon_->Set(queue->left_arm / 12.0);
+    right_arm_talon_->Set(-queue->right_arm / 12.0);
+    left_elevator_talon_->Set(queue->left_elevator / 12.0);
+    right_elevator_talon_->Set(-queue->right_elevator / 12.0);
+  }
+
+  virtual void Stop() override {
+    LOG(WARNING, "Fridge output too old.\n");
+    left_arm_talon_->Disable();
+    right_arm_talon_->Disable();
+    left_elevator_talon_->Disable();
+    right_elevator_talon_->Disable();
+  }
+
+  ::std::unique_ptr<Talon> left_arm_talon_;
+  ::std::unique_ptr<Talon> right_arm_talon_;
+  ::std::unique_ptr<Talon> left_elevator_talon_;
+  ::std::unique_ptr<Talon> right_elevator_talon_;
+};
+
+class ClawWriter : public LoopOutputHandler {
+ public:
+  void set_left_intake_talon(::std::unique_ptr<Talon> t) {
+    left_intake_talon_ = ::std::move(t);
+  }
+
+  void set_right_intake_talon(::std::unique_ptr<Talon> t) {
+    right_intake_talon_ = ::std::move(t);
+  }
+
+  void set_wrist_talon(::std::unique_ptr<Talon> t) {
+    wrist_talon_ = ::std::move(t);
+  }
+
+ private:
+  virtual void Read() override {
+    ::frc971::control_loops::claw_queue.output.FetchAnother();
+  }
+
+  virtual void Write() override {
+    auto &queue = ::frc971::control_loops::claw_queue.output;
+    LOG_STRUCT(DEBUG, "will output", *queue);
+    left_intake_talon_->Set(queue->intake_voltage / 12.0);
+    right_intake_talon_->Set(-queue->intake_voltage / 12.0);
+    wrist_talon_->Set(-queue->voltage / 12.0);
+  }
+
+  virtual void Stop() override {
+    LOG(WARNING, "Claw output too old.\n");
+    left_intake_talon_->Disable();
+    right_intake_talon_->Disable();
+    wrist_talon_->Disable();
+  }
+
+  ::std::unique_ptr<Talon> left_intake_talon_;
+  ::std::unique_ptr<Talon> right_intake_talon_;
+  ::std::unique_ptr<Talon> wrist_talon_;
+};
+
+// TODO(brian): Replace this with ::std::make_unique once all our toolchains
+// have support.
+template <class T, class... U>
+std::unique_ptr<T> make_unique(U &&... u) {
+  return std::unique_ptr<T>(new T(std::forward<U>(u)...));
+}
+
+class WPILibRobot : public RobotBase {
+ public:
+  ::std::unique_ptr<Encoder> encoder(int index) {
+    return make_unique<Encoder>(10 + index * 2, 11 + index * 2, false,
+                                Encoder::k4X);
+  }
+  virtual void StartCompetition() {
+    ::aos::InitNRT();
+    ::aos::SetCurrentThreadName("StartCompetition");
+
+    JoystickSender joystick_sender;
+    ::std::thread joystick_thread(::std::ref(joystick_sender));
+    // TODO(austin): Compressor needs to use a spike.
+
+    SensorReader reader;
+    LOG(INFO, "Creating the reader\n");
+    reader.set_arm_left_encoder(encoder(1));
+    reader.set_arm_left_index(make_unique<DigitalInput>(1));
+    reader.set_arm_left_potentiometer(make_unique<AnalogInput>(1));
+
+    reader.set_arm_right_encoder(encoder(5));
+    reader.set_arm_right_index(make_unique<DigitalInput>(5));
+    reader.set_arm_right_potentiometer(make_unique<AnalogInput>(5));
+
+    reader.set_elevator_left_encoder(encoder(0));
+    reader.set_elevator_left_index(make_unique<DigitalInput>(0));
+    reader.set_elevator_left_potentiometer(make_unique<AnalogInput>(0));
+
+    reader.set_elevator_right_encoder(encoder(4));
+    reader.set_elevator_right_index(make_unique<DigitalInput>(4));
+    reader.set_elevator_right_potentiometer(make_unique<AnalogInput>(4));
+
+    reader.set_wrist_encoder(encoder(6));
+    reader.set_wrist_index(make_unique<DigitalInput>(6));
+    reader.set_wrist_potentiometer(make_unique<AnalogInput>(6));
+
+    reader.set_left_encoder(encoder(2));
+    reader.set_right_encoder(encoder(3));
+    reader.set_dma(make_unique<DMA>());
+    ::std::thread reader_thread(::std::ref(reader));
+    GyroSender gyro_sender;
+    ::std::thread gyro_thread(::std::ref(gyro_sender));
+
+    DrivetrainWriter drivetrain_writer;
+    drivetrain_writer.set_left_drivetrain_talon(
+        ::std::unique_ptr<Talon>(new Talon(8)));
+    drivetrain_writer.set_right_drivetrain_talon(
+        ::std::unique_ptr<Talon>(new Talon(0)));
+    ::std::thread drivetrain_writer_thread(::std::ref(drivetrain_writer));
+
+    // TODO(sensors): Get real PWM output and relay numbers for the fridge and
+    // claw.
+    FridgeWriter fridge_writer;
+    fridge_writer.set_left_arm_talon(
+        ::std::unique_ptr<Talon>(new Talon(6)));
+    fridge_writer.set_right_arm_talon(
+        ::std::unique_ptr<Talon>(new Talon(2)));
+    fridge_writer.set_left_elevator_talon(
+        ::std::unique_ptr<Talon>(new Talon(7)));
+    fridge_writer.set_right_elevator_talon(
+        ::std::unique_ptr<Talon>(new Talon(1)));
+    ::std::thread fridge_writer_thread(::std::ref(fridge_writer));
+
+    ClawWriter claw_writer;
+    claw_writer.set_left_intake_talon(
+        ::std::unique_ptr<Talon>(new Talon(5)));
+    claw_writer.set_right_intake_talon(
+        ::std::unique_ptr<Talon>(new Talon(3)));
+    claw_writer.set_wrist_talon(
+        ::std::unique_ptr<Talon>(new Talon(4)));
+    ::std::thread claw_writer_thread(::std::ref(claw_writer));
+
+    ::std::unique_ptr<::frc971::wpilib::BufferedPcm> pcm(
+        new ::frc971::wpilib::BufferedPcm());
+    SolenoidWriter solenoid_writer(pcm);
+    solenoid_writer.set_fridge_grabbers_top_front(pcm->MakeSolenoid(0));
+    solenoid_writer.set_fridge_grabbers_top_back(pcm->MakeSolenoid(0));
+    solenoid_writer.set_fridge_grabbers_bottom_front(pcm->MakeSolenoid(2));
+    solenoid_writer.set_fridge_grabbers_bottom_back(pcm->MakeSolenoid(1));
+    solenoid_writer.set_claw_pinchers(pcm->MakeSolenoid(4));
+    solenoid_writer.set_grabber_latch_release(pcm->MakeSolenoid(7));
+    solenoid_writer.set_grabber_fold_up(pcm->MakeSolenoid(5));
+
+    solenoid_writer.set_pressure_switch(make_unique<DigitalInput>(9));
+    solenoid_writer.set_compressor_relay(make_unique<Relay>(0));
+    ::std::thread solenoid_thread(::std::ref(solenoid_writer));
+
+    // Wait forever. Not much else to do...
+    PCHECK(select(0, nullptr, nullptr, nullptr, nullptr));
+
+    LOG(ERROR, "Exiting WPILibRobot\n");
+
+    joystick_sender.Quit();
+    joystick_thread.join();
+    reader.Quit();
+    reader_thread.join();
+    gyro_sender.Quit();
+    gyro_thread.join();
+
+    drivetrain_writer.Quit();
+    drivetrain_writer_thread.join();
+    solenoid_writer.Quit();
+    solenoid_thread.join();
+
+    ::aos::Cleanup();
+  }
+};
+
+}  // namespace wpilib
+}  // namespace frc971
+
+
+START_ROBOT_CLASS(::frc971::wpilib::WPILibRobot);
diff --git a/y2014/y2014.gyp b/y2014/y2014.gyp
new file mode 100644
index 0000000..8787a9a
--- /dev/null
+++ b/y2014/y2014.gyp
@@ -0,0 +1,44 @@
+{
+  'targets': [
+    {
+      'target_name': 'constants',
+      'type': 'static_library',
+      'sources': [
+        'constants.cc',
+      ],
+      'dependencies': [
+        '<(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)/y2014/control_loops/drivetrain/drivetrain.gyp:polydrivetrain_plants',
+      ],
+      'export_dependent_settings': [
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+    },
+    {
+      'target_name': 'joystick_reader',
+      'type': 'executable',
+      'sources': [
+        'joystick_reader.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/prime/input/input.gyp:joystick_input',
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(AOS)/common/common.gyp:time',
+        '<(AOS)/common/util/util.gyp:log_interval',
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+
+        '<(DEPTH)/y2014/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
+        '<(DEPTH)/y2014/y2014.gyp:constants',
+        '<(DEPTH)/frc971/queues/queues.gyp:gyro',
+        '<(DEPTH)/frc971/autonomous/autonomous.gyp:auto_queue',
+        '<(DEPTH)/y2014/control_loops/claw/claw.gyp:claw_queue',
+        '<(DEPTH)/y2014/control_loops/shooter/shooter.gyp:shooter_queue',
+        '<(DEPTH)/y2014/actors/actors.gyp:shoot_action_lib',
+      ],
+    },
+  ],
+}