Import y2014 directory for the 2016 season.

Change-Id: Id12c60fa17d40edb23d3a7066c88d7a103fc60c5
diff --git a/y2016/BUILD b/y2016/BUILD
new file mode 100644
index 0000000..2938aa6
--- /dev/null
+++ b/y2016/BUILD
@@ -0,0 +1,75 @@
+load('/aos/downloader/downloader', 'aos_downloader')
+
+cc_library(
+  name = 'constants',
+  visibility = ['//visibility:public'],
+  srcs = [
+    'constants.cc',
+  ],
+  hdrs = [
+    'constants.h',
+  ],
+  deps = [
+    '//aos/common/logging',
+    '//aos/common:once',
+    '//aos/common/network:team_number',
+    '//aos/common:mutex',
+    '//frc971/control_loops:state_feedback_loop',
+    '//y2014/control_loops/drivetrain:polydrivetrain_plants',
+    '//frc971:shifter_hall_effect',
+  ],
+)
+
+cc_binary(
+  name = 'joystick_reader',
+  srcs = [
+    'joystick_reader.cc',
+  ],
+  deps = [
+    ':constants',
+    '//aos/input:joystick_input',
+    '//aos/linux_code:init',
+    '//aos/common/logging',
+    '//aos/common:time',
+    '//aos/common/util:log_interval',
+    '//aos/common/actions:action_lib',
+    '//frc971/control_loops/drivetrain:drivetrain_queue',
+    '//frc971/queues:gyro',
+    '//frc971/autonomous:auto_queue',
+    '//y2014/control_loops/claw:claw_queue',
+    '//y2014/control_loops/shooter:shooter_queue',
+    '//y2014/actors:shoot_action_lib',
+  ],
+)
+
+aos_downloader(
+  name = 'download',
+  start_srcs = [
+    ':hot_goal_reader',
+    ':joystick_reader',
+    '//y2014/control_loops/drivetrain:drivetrain',
+    '//y2014/control_loops/claw:claw',
+    '//y2014/control_loops/shooter:shooter',
+    '//y2014/autonomous:auto',
+    '//y2014/actors:binaries',
+    '//aos:prime_start_binaries',
+    '//y2014/wpilib:wpilib_interface',
+  ],
+  srcs = [
+    '//aos:prime_binaries',
+  ],
+)
+
+cc_binary(
+  name = 'hot_goal_reader',
+  srcs = [
+    'hot_goal_reader.cc',
+  ],
+  deps = [
+    '//aos/common:time',
+    '//aos/common/logging',
+    '//aos/common/logging:queue_logging',
+    '//aos/linux_code:init',
+    '//y2014/queues:hot_goal',
+  ],
+)
diff --git a/y2016/actors/BUILD b/y2016/actors/BUILD
new file mode 100644
index 0000000..ef94367
--- /dev/null
+++ b/y2016/actors/BUILD
@@ -0,0 +1,99 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+filegroup(
+  name = 'binaries',
+  srcs = [
+    ':drivetrain_action',
+    ':shoot_action',
+  ],
+)
+
+queue_library(
+  name = 'shoot_action_queue',
+  srcs = [
+    'shoot_action.q',
+  ],
+  deps = [
+    '//aos/common/actions:action_queue',
+  ],
+)
+
+cc_library(
+  name = 'shoot_action_lib',
+  srcs = [
+    'shoot_actor.cc',
+  ],
+  hdrs = [
+    'shoot_actor.h',
+  ],
+  deps = [
+    ':shoot_action_queue',
+    '//aos/common/actions:action_lib',
+    '//y2014/queues:profile_params',
+    '//aos/common/logging',
+    '//y2014/control_loops/shooter:shooter_queue',
+    '//y2014/control_loops/claw:claw_queue',
+    '//frc971/control_loops/drivetrain:drivetrain_queue',
+    '//y2014:constants',
+  ],
+)
+
+cc_binary(
+  name = 'shoot_action',
+  srcs = [
+    'shoot_actor_main.cc',
+  ],
+  deps = [
+    '//aos/linux_code:init',
+    ':shoot_action_lib',
+    ':shoot_action_queue',
+  ],
+)
+
+queue_library(
+  name = 'drivetrain_action_queue',
+  srcs = [
+    'drivetrain_action.q',
+  ],
+  deps = [
+    '//aos/common/actions:action_queue',
+  ],
+)
+
+cc_library(
+  name = 'drivetrain_action_lib',
+  srcs = [
+    'drivetrain_actor.cc',
+  ],
+  hdrs = [
+    'drivetrain_actor.h',
+  ],
+  deps = [
+    ':drivetrain_action_queue',
+    '//y2014:constants',
+    '//aos/common:time',
+    '//aos/common:math',
+    '//aos/common/util:phased_loop',
+    '//aos/common/logging',
+    '//aos/common/actions:action_lib',
+    '//aos/common/logging:queue_logging',
+    '//third_party/eigen',
+    '//aos/common/util:trapezoid_profile',
+    '//frc971/control_loops/drivetrain:drivetrain_queue',
+    '//frc971/control_loops:state_feedback_loop',
+  ],
+)
+
+cc_binary(
+  name = 'drivetrain_action',
+  srcs = [
+    'drivetrain_actor_main.cc',
+  ],
+  deps = [
+    '//aos/linux_code:init',
+    ':drivetrain_action_lib',
+    ':drivetrain_action_queue',
+  ],
+)
diff --git a/y2016/actors/drivetrain_action.q b/y2016/actors/drivetrain_action.q
new file mode 100644
index 0000000..2f3eb15
--- /dev/null
+++ b/y2016/actors/drivetrain_action.q
@@ -0,0 +1,29 @@
+package y2014.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/y2016/actors/drivetrain_actor.cc b/y2016/actors/drivetrain_actor.cc
new file mode 100644
index 0000000..4cb69ca
--- /dev/null
+++ b/y2016/actors/drivetrain_actor.cc
@@ -0,0 +1,171 @@
+#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 "frc971/control_loops/drivetrain/drivetrain.q.h"
+
+namespace y2014 {
+namespace actors {
+
+DrivetrainActor::DrivetrainActor(actors::DrivetrainActionQueueGroup* s)
+    : aos::common::actions::ActorBase<actors::DrivetrainActionQueueGroup>(s),
+      loop_(constants::GetValues().make_drivetrain_loop()) {
+  loop_.set_controller_index(3);
+}
+
+bool DrivetrainActor::RunAction(const actors::DrivetrainActionParams &params) {
+  static const auto K = 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(5, 2500);
+
+    ::frc971::control_loops::drivetrain_queue.status.FetchLatest();
+    if (::frc971::control_loops::drivetrain_queue.status.get()) {
+      const auto& status = *::frc971::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);
+    ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
+        .control_loop_driving(true)
+        .highgear(true)
+        .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;
+  ::frc971::control_loops::drivetrain_queue.status.FetchLatest();
+  while (!::frc971::control_loops::drivetrain_queue.status.get()) {
+    LOG(WARNING,
+        "No previous drivetrain status packet, trying to fetch again\n");
+    ::frc971::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(
+        ::frc971::control_loops::drivetrain_queue.status->filtered_left_position -
+        (left_goal_state(0, 0) + params.left_initial_position));
+    const double right_error = ::std::abs(
+        ::frc971::control_loops::drivetrain_queue.status->filtered_right_position -
+        (right_goal_state(0, 0) + params.right_initial_position));
+    const double velocity_error =
+        ::std::abs(::frc971::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);
+    }
+    ::frc971::control_loops::drivetrain_queue.status.FetchNextBlocking();
+  }
+  LOG(INFO, "Done moving\n");
+  return true;
+}
+
+::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
+    const ::y2014::actors::DrivetrainActionParams& params) {
+  return ::std::unique_ptr<DrivetrainAction>(
+      new DrivetrainAction(&::y2014::actors::drivetrain_action, params));
+}
+
+}  // namespace actors
+}  // namespace y2014
diff --git a/y2016/actors/drivetrain_actor.h b/y2016/actors/drivetrain_actor.h
new file mode 100644
index 0000000..2a9e307
--- /dev/null
+++ b/y2016/actors/drivetrain_actor.h
@@ -0,0 +1,36 @@
+#ifndef Y2014_ACTIONS_DRIVETRAIN_ACTION_H_
+#define Y2014_ACTIONS_DRIVETRAIN_ACTION_H_
+
+#include <memory>
+
+#include "aos/common/actions/actor.h"
+#include "aos/common/actions/actions.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+
+#include "y2014/actors/drivetrain_action.q.h"
+
+namespace y2014 {
+namespace actors {
+
+class DrivetrainActor
+    : public ::aos::common::actions::ActorBase<DrivetrainActionQueueGroup> {
+ public:
+  explicit DrivetrainActor(DrivetrainActionQueueGroup* s);
+
+  bool RunAction(const actors::DrivetrainActionParams &params) override;
+
+ private:
+  StateFeedbackLoop<4, 2, 2> loop_;
+};
+
+typedef ::aos::common::actions::TypedAction<DrivetrainActionQueueGroup>
+    DrivetrainAction;
+
+// Makes a new DrivetrainActor action.
+::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
+    const ::y2014::actors::DrivetrainActionParams& params);
+
+}  // namespace actors
+}  // namespace y2014
+
+#endif
diff --git a/y2016/actors/drivetrain_actor_main.cc b/y2016/actors/drivetrain_actor_main.cc
new file mode 100644
index 0000000..4cc0070
--- /dev/null
+++ b/y2016/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(-1);
+
+  ::y2014::actors::DrivetrainActor drivetrain(
+      &::y2014::actors::drivetrain_action);
+  drivetrain.Run();
+
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2016/autonomous/BUILD b/y2016/autonomous/BUILD
new file mode 100644
index 0000000..984b110
--- /dev/null
+++ b/y2016/autonomous/BUILD
@@ -0,0 +1,42 @@
+package(default_visibility = ['//visibility:public'])
+
+cc_library(
+  name = 'auto_lib',
+  srcs = [
+    'auto.cc',
+  ],
+  hdrs = [
+    'auto.h',
+  ],
+  deps = [
+    '//frc971/autonomous:auto_queue',
+    '//aos/common/controls:control_loop',
+    '//frc971/control_loops/drivetrain:drivetrain_queue',
+    '//y2014/control_loops/shooter:shooter_queue',
+    '//y2014/control_loops/claw:claw_queue',
+    '//y2014:constants',
+    '//aos/common:time',
+    '//aos/common/util:phased_loop',
+    '//aos/common/util:trapezoid_profile',
+    '//aos/common/logging',
+    '//aos/common/actions:action_lib',
+    '//y2014/actors:shoot_action_lib',
+    '//y2014/actors:drivetrain_action_lib',
+    '//y2014/queues:hot_goal',
+    '//aos/common/logging:queue_logging',
+    '//y2014/queues:profile_params',
+    '//y2014/queues:auto_mode',
+  ],
+)
+
+cc_binary(
+  name = 'auto',
+  srcs = [
+    'auto_main.cc',
+  ],
+  deps = [
+    '//aos/linux_code:init',
+    '//frc971/autonomous:auto_queue',
+    ':auto_lib',
+  ],
+)
diff --git a/y2016/autonomous/auto.cc b/y2016/autonomous/auto.cc
new file mode 100644
index 0000000..e954637
--- /dev/null
+++ b/y2016/autonomous/auto.cc
@@ -0,0 +1,532 @@
+#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 "aos/common/actions/actions.h"
+
+#include "frc971/autonomous/auto.q.h"
+#include "y2014/constants.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "y2014/control_loops/shooter/shooter.q.h"
+#include "y2014/control_loops/claw/claw.q.h"
+#include "y2014/actors/shoot_actor.h"
+#include "y2014/actors/drivetrain_actor.h"
+#include "y2014/queues/auto_mode.q.h"
+
+#include "y2014/queues/hot_goal.q.h"
+#include "y2014/queues/profile_params.q.h"
+
+using ::aos::time::Time;
+
+namespace y2014 {
+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");
+  frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
+      .control_loop_driving(true)
+      .highgear(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");
+  ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
+      .control_loop_driving(false)
+      .highgear(true)
+      .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(10, 5000);
+    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);
+  ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
+      .control_loop_driving(true)
+      .highgear(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 PositionClawVertically(double intake_power = 0.0, double centering_power = 0.0) {
+  if (!control_loops::claw_queue.goal.MakeWithBuilder()
+           .bottom_angle(0.0)
+           .separation_angle(0.0)
+           .intake(intake_power)
+           .centering(centering_power)
+           .Send()) {
+    LOG(WARNING, "sending claw goal failed\n");
+  }
+}
+
+void PositionClawBackIntake() {
+  if (!control_loops::claw_queue.goal.MakeWithBuilder()
+           .bottom_angle(-2.273474)
+           .separation_angle(0.0)
+           .intake(12.0)
+           .centering(12.0)
+           .Send()) {
+    LOG(WARNING, "sending claw goal failed\n");
+  }
+}
+
+void PositionClawUpClosed() {
+  // Move the claw to where we're going to shoot from but keep it closed until
+  // it gets there.
+  if (!control_loops::claw_queue.goal.MakeWithBuilder()
+           .bottom_angle(0.86)
+           .separation_angle(0.0)
+           .intake(4.0)
+           .centering(1.0)
+           .Send()) {
+    LOG(WARNING, "sending claw goal failed\n");
+  }
+}
+
+void PositionClawForShot() {
+  if (!control_loops::claw_queue.goal.MakeWithBuilder()
+           .bottom_angle(0.86)
+           .separation_angle(0.10)
+           .intake(4.0)
+           .centering(1.0)
+           .Send()) {
+    LOG(WARNING, "sending claw goal failed\n");
+  }
+}
+
+void SetShotPower(double power) {
+  LOG(INFO, "Setting shot power to %f\n", power);
+  if (!control_loops::shooter_queue.goal.MakeWithBuilder()
+           .shot_power(power)
+           .shot_requested(false)
+           .unload_requested(false)
+           .load_requested(false)
+           .Send()) {
+    LOG(WARNING, "sending shooter goal failed\n");
+  }
+}
+
+void WaitUntilNear(double distance) {
+  while (true) {
+    if (ShouldExitAuto()) return;
+    ::frc971::control_loops::drivetrain_queue.status.FetchAnother();
+    double left_error = ::std::abs(
+        left_initial_position -
+        ::frc971::control_loops::drivetrain_queue.status->filtered_left_position);
+    double right_error = ::std::abs(
+        right_initial_position -
+        ::frc971::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 = {3.0, 2.5};
+const ProfileParams kSlowDrive = {2.5, 2.5};
+const ProfileParams kFastWithBallDrive = {3.0, 2.0};
+const ProfileParams kSlowWithBallDrive = {2.5, 2.0};
+const ProfileParams kFastTurn = {3.0, 10.0};
+
+::std::unique_ptr<::y2014::actors::DrivetrainAction> SetDriveGoal(
+    double distance, const ProfileParams drive_params, double theta = 0,
+    const ProfileParams &turn_params = kFastTurn) {
+  LOG(INFO, "Driving to %f\n", distance);
+
+  ::y2014::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 = actors::MakeShootAction();
+  shoot_action->Start();
+  WaitUntilDoneOrCanceled(::std::move(shoot_action));
+}
+
+void InitializeEncoders() {
+  ::frc971::control_loops::drivetrain_queue.status.FetchAnother();
+  left_initial_position =
+      ::frc971::control_loops::drivetrain_queue.status->filtered_left_position;
+  right_initial_position =
+      ::frc971::control_loops::drivetrain_queue.status->filtered_right_position;
+}
+
+void WaitUntilClawDone() {
+  while (true) {
+    // Poll the running bit and auto done bits.
+    ::aos::time::PhasedLoopXMS(10, 5000);
+    control_loops::claw_queue.status.FetchLatest();
+    control_loops::claw_queue.goal.FetchLatest();
+    if (ShouldExitAuto()) {
+      return;
+    }
+    if (control_loops::claw_queue.status.get() == nullptr ||
+        control_loops::claw_queue.goal.get() == nullptr) {
+      continue;
+    }
+    bool ans =
+        control_loops::claw_queue.status->zeroed &&
+        (::std::abs(control_loops::claw_queue.status->bottom_velocity) <
+         1.0) &&
+        (::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);
+    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;
+
+  ::y2014::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;
+  ::y2014::sensors::auto_mode.FetchLatest();
+  if (!::y2014::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 (::y2014::sensors::auto_mode->voltage < kSelectorStep + kSelectorMin) {
+      auto_version = AutoVersion::kSingleHot;
+    } else if (::y2014::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 ProfileParams &drive_params =
+      (auto_version == AutoVersion::kStraight) ? kFastDrive : kSlowDrive;
+  const ProfileParams &drive_with_ball_params =
+      (auto_version == AutoVersion::kStraight) ? kFastWithBallDrive
+                                               : kSlowWithBallDrive;
+
+  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_params);
+    time::SleepFor(time::Time::InSeconds(0.75));
+    PositionClawForShot();
+    LOG(INFO, "Waiting until drivetrain is finished\n");
+    WaitUntilDoneOrCanceled(::std::move(drivetrain_action));
+    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_with_ball_params, first_shot_left ? kTurnAngle : -kTurnAngle);
+    WaitUntilDoneOrCanceled(::std::move(drivetrain_action));
+    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_with_ball_params, first_shot_left ? -kTurnAngle : kTurnAngle);
+    WaitUntilDoneOrCanceled(::std::move(drivetrain_action));
+    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_params);
+    LOG(INFO, "Waiting until drivetrain is finished\n");
+    WaitUntilDoneOrCanceled(::std::move(drivetrain_action));
+    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_params);
+    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(::std::move(drivetrain_action));
+    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_params, second_shot_left ? kTurnAngle : -kTurnAngle);
+    WaitUntilDoneOrCanceled(::std::move(drivetrain_action));
+    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 y2014
diff --git a/y2016/autonomous/auto.h b/y2016/autonomous/auto.h
new file mode 100644
index 0000000..dd00bba
--- /dev/null
+++ b/y2016/autonomous/auto.h
@@ -0,0 +1,12 @@
+#ifndef Y2014_AUTONOMOUS_AUTO_H_
+#define Y2014_AUTONOMOUS_AUTO_H_
+
+namespace y2014 {
+namespace autonomous {
+
+void HandleAuto();
+
+}  // namespace autonomous
+}  // namespace y2014
+
+#endif  // Y2014_AUTONOMOUS_AUTO_H_
diff --git a/y2016/autonomous/auto_main.cc b/y2016/autonomous/auto_main.cc
new file mode 100644
index 0000000..bf3acf8
--- /dev/null
+++ b/y2016/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(-1);
+
+  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();
+    ::y2014::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/y2016/constants.cc b/y2016/constants.cc
new file mode 100644
index 0000000..8cf9076
--- /dev/null
+++ b/y2016/constants.cc
@@ -0,0 +1,221 @@
+#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 y2014 {
+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 kCompLeftDriveShifter{2.61, 2.33, 4.25, 3.28, 0.2, 0.7};
+const ShifterHallEffect kCompRightDriveShifter{2.94, 4.31, 4.32, 3.25, 0.2, 0.7};
+
+const ShifterHallEffect kPracticeLeftDriveShifter{2.80, 3.05, 4.15, 3.2, 0.2, 0.7};
+const ShifterHallEffect kPracticeRightDriveShifter{2.90, 3.75, 3.80, 2.98, 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,
+          ::y2014::control_loops::drivetrain::MakeVelocityDrivetrainLoop,
+          ::y2014::control_loops::drivetrain::MakeDrivetrainLoop,
+          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,
+          ::y2014::control_loops::drivetrain::MakeVelocityDrivetrainLoop,
+          ::y2014::control_loops::drivetrain::MakeDrivetrainLoop,
+          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,
+          ::y2014::control_loops::drivetrain::MakeVelocityDrivetrainLoop,
+          ::y2014::control_loops::drivetrain::MakeDrivetrainLoop,
+          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 + 0.139081, -1.7 * 2.0, -1.547616 * 2.0 + 0.139081+ 0.013636},
+            {-0.115446 * 2.0, 0.030452 * 2.0, -0.120900 * 2.0, 0.023862 * 2.0},
+            {0.977884 * 2.0, 1.4 * 2.0, 0.963113 * 2.0, 1.4 * 2.0}},
+          {-2.451642, 3.107504, -2.273474, 2.750,
+            {-1.5 * 2.0, -1.027199 * 2.0, -1.5 * 2.0, -1.037880 * 2.0},
+            {-0.116355 * 2.0, 0.017726 * 2.0, -0.125673 * 2.0, 0.008636 * 2.0},
+            {2.894792 + 0.122719, 3.2, 2.887974 + 0.122719 - 0.029088, 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 y2014
diff --git a/y2016/constants.h b/y2016/constants.h
new file mode 100644
index 0000000..a31e9c0
--- /dev/null
+++ b/y2016/constants.h
@@ -0,0 +1,146 @@
+#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 y2014 {
+namespace constants {
+
+using ::frc971::constants::ShifterHallEffect;
+
+// 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_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 y2014
+
+#endif  // Y2014_CONSTANTS_H_
diff --git a/y2016/control_loops/drivetrain/BUILD b/y2016/control_loops/drivetrain/BUILD
new file mode 100644
index 0000000..9d7edb6
--- /dev/null
+++ b/y2016/control_loops/drivetrain/BUILD
@@ -0,0 +1,77 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+genrule(
+  name = 'genrule_drivetrain',
+  visibility = ['//visibility:private'],
+  cmd = '$(location //y2014/control_loops/python:drivetrain) $(OUTS)',
+  tools = [
+    '//y2014/control_loops/python:drivetrain',
+  ],
+  outs = [
+    'drivetrain_dog_motor_plant.h',
+    'drivetrain_dog_motor_plant.cc',
+    'kalman_drivetrain_motor_plant.h',
+    'kalman_drivetrain_motor_plant.cc',
+  ],
+)
+
+genrule(
+  name = 'genrule_polydrivetrain',
+  visibility = ['//visibility:private'],
+  cmd = '$(location //y2014/control_loops/python:polydrivetrain) $(OUTS)',
+  tools = [
+    '//y2014/control_loops/python:polydrivetrain',
+  ],
+  outs = [
+    'polydrivetrain_dog_motor_plant.h',
+    'polydrivetrain_dog_motor_plant.cc',
+    'polydrivetrain_cim_plant.h',
+    'polydrivetrain_cim_plant.cc',
+  ],
+)
+
+cc_library(
+  name = 'polydrivetrain_plants',
+  srcs = [
+    'polydrivetrain_dog_motor_plant.cc',
+    'drivetrain_dog_motor_plant.cc',
+    'kalman_drivetrain_motor_plant.cc',
+  ],
+  hdrs = [
+    'polydrivetrain_dog_motor_plant.h',
+    'drivetrain_dog_motor_plant.h',
+    'kalman_drivetrain_motor_plant.h',
+  ],
+  deps = [
+    '//frc971/control_loops:state_feedback_loop',
+  ],
+)
+
+cc_library(
+  name = 'drivetrain_base',
+  srcs = [
+    'drivetrain_base.cc',
+  ],
+  hdrs = [
+    'drivetrain_base.h',
+  ],
+  deps = [
+    ':polydrivetrain_plants',
+    '//y2014:constants',
+    '//frc971/control_loops/drivetrain:drivetrain_config',
+  ],
+)
+
+cc_binary(
+  name = 'drivetrain',
+  srcs = [
+    'drivetrain_main.cc',
+  ],
+  deps = [
+    ':drivetrain_base',
+    '//aos/linux_code:init',
+    '//frc971/control_loops/drivetrain:drivetrain_lib',
+  ],
+)
diff --git a/y2016/control_loops/drivetrain/drivetrain_base.cc b/y2016/control_loops/drivetrain/drivetrain_base.cc
new file mode 100644
index 0000000..b4ef447
--- /dev/null
+++ b/y2016/control_loops/drivetrain/drivetrain_base.cc
@@ -0,0 +1,36 @@
+#include "y2014/control_loops/drivetrain/drivetrain_base.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+#include "y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2014/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+#include "y2014/control_loops/drivetrain/kalman_drivetrain_motor_plant.h"
+#include "y2014/constants.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainConfig;
+
+namespace y2014 {
+namespace control_loops {
+
+const DrivetrainConfig &GetDrivetrainConfig() {
+  static DrivetrainConfig kDrivetrainConfig{
+      ::frc971::control_loops::drivetrain::ShifterType::HALL_EFFECT_SHIFTER,
+
+      ::y2014::control_loops::drivetrain::MakeDrivetrainLoop,
+      ::y2014::control_loops::drivetrain::MakeVelocityDrivetrainLoop,
+      ::y2014::control_loops::drivetrain::MakeKFDrivetrainLoop,
+
+      drivetrain::kDt, drivetrain::kStallTorque, drivetrain::kStallCurrent,
+      drivetrain::kFreeSpeedRPM, drivetrain::kFreeCurrent, drivetrain::kJ,
+      drivetrain::kMass, drivetrain::kRobotRadius, drivetrain::kWheelRadius,
+      drivetrain::kR, drivetrain::kV, drivetrain::kT,
+
+      constants::GetValues().turn_width, constants::GetValues().high_gear_ratio,
+      constants::GetValues().low_gear_ratio,
+      constants::GetValues().left_drive, constants::GetValues().right_drive};
+
+  return kDrivetrainConfig;
+};
+
+}  // namespace control_loops
+}  // namespace y2014
diff --git a/y2016/control_loops/drivetrain/drivetrain_base.h b/y2016/control_loops/drivetrain/drivetrain_base.h
new file mode 100644
index 0000000..3a9d70e
--- /dev/null
+++ b/y2016/control_loops/drivetrain/drivetrain_base.h
@@ -0,0 +1,16 @@
+#ifndef Y2014_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+#define Y2014_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainConfig;
+
+namespace y2014 {
+namespace control_loops {
+
+const DrivetrainConfig &GetDrivetrainConfig();
+
+}  // namespace control_loops
+}  // namespace y2014
+
+#endif  // Y2014_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2016/control_loops/drivetrain/drivetrain_main.cc b/y2016/control_loops/drivetrain/drivetrain_main.cc
new file mode 100644
index 0000000..52dafcc
--- /dev/null
+++ b/y2016/control_loops/drivetrain/drivetrain_main.cc
@@ -0,0 +1,15 @@
+#include "aos/linux_code/init.h"
+
+#include "y2014/control_loops/drivetrain/drivetrain_base.h"
+#include "frc971/control_loops/drivetrain/drivetrain.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainLoop;
+
+int main() {
+  ::aos::Init();
+  DrivetrainLoop drivetrain =
+      DrivetrainLoop(::y2014::control_loops::GetDrivetrainConfig());
+  drivetrain.Run();
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2016/control_loops/python/BUILD b/y2016/control_loops/python/BUILD
new file mode 100644
index 0000000..84e73a5
--- /dev/null
+++ b/y2016/control_loops/python/BUILD
@@ -0,0 +1,64 @@
+package(default_visibility = ['//y2014:__subpackages__'])
+
+py_binary(
+  name = 'drivetrain',
+  srcs = [
+    'drivetrain.py',
+  ],
+  deps = [
+    '//external:python-gflags',
+    '//external:python-glog',
+    '//frc971/control_loops/python:controls',
+  ],
+)
+
+py_binary(
+  name = 'polydrivetrain',
+  srcs = [
+    'polydrivetrain.py',
+    'drivetrain.py',
+  ],
+  deps = [
+    '//external:python-gflags',
+    '//external:python-glog',
+    '//frc971/control_loops/python:controls',
+  ],
+)
+
+py_library(
+  name = 'polydrivetrain_lib',
+  srcs = [
+    'polydrivetrain.py',
+    'drivetrain.py',
+  ],
+  deps = [
+    '//external:python-gflags',
+    '//external:python-glog',
+    '//frc971/control_loops/python:controls',
+  ],
+)
+
+py_binary(
+  name = 'claw',
+  srcs = [
+    'claw.py',
+  ],
+  deps = [
+    ':polydrivetrain_lib',
+    '//external:python-gflags',
+    '//external:python-glog',
+    '//frc971/control_loops/python:controls',
+  ]
+)
+
+py_binary(
+  name = 'shooter',
+  srcs = [
+    'shooter.py',
+  ],
+  deps = [
+    '//external:python-gflags',
+    '//external:python-glog',
+    '//frc971/control_loops/python:controls',
+  ]
+)
diff --git a/y2016/control_loops/python/drivetrain.py b/y2016/control_loops/python/drivetrain.py
new file mode 100755
index 0000000..2a93285
--- /dev/null
+++ b/y2016/control_loops/python/drivetrain.py
@@ -0,0 +1,351 @@
+#!/usr/bin/python
+
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
+import numpy
+import sys
+import argparse
+from matplotlib import pylab
+
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+
+class CIM(control_loop.ControlLoop):
+  def __init__(self):
+    super(CIM, self).__init__("CIM")
+    # 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.resistance = 12.0 / self.stall_current
+    # Motor velocity constant
+    self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
+              (12.0 - self.resistance * 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.resistance)]])
+    self.B_continuous = numpy.matrix(
+        [[self.Kt / (self.J * self.resistance)]])
+    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)
+    # Number of motors per side
+    self.num_motors = 2
+    # Stall Torque in N m
+    self.stall_torque = 2.42 * self.num_motors * 0.60
+    # Stall Current in Amps
+    self.stall_current = 133.0 * self.num_motors
+    # Free Speed in RPM. Used number from last year.
+    self.free_speed = 5500.0
+    # Free Current in Amps
+    self.free_current = 4.7 * self.num_motors
+    # Moment of inertia of the drivetrain in kg m^2
+    self.J = 2.8
+    # Mass of the robot, in kg.
+    self.m = 68
+    # Radius of the robot, in meters (from last year).
+    self.rb = 0.647998644 / 2.0
+    # Radius of the wheels, in meters.
+    self.r = .04445
+    # Resistance of the motor, divided by the number of motors.
+    self.resistance = 12.0 / self.stall_current
+    # Motor velocity constant
+    self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
+               (12.0 - self.resistance * 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.resistance * self.r * self.r)
+    self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.resistance * self.r * self.r)
+    self.mpl = self.Kt / (self.Gl * self.resistance * self.r)
+    self.mpr = self.Kt / (self.Gr * self.resistance * self.r)
+
+    # State feedback matrices
+    # X will be of the format
+    # [[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]])
+
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    q_pos = 0.12
+    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)
+
+    glog.debug('DT K %s', name)
+    glog.debug(str(self.K))
+    glog.debug(str(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()
+
+
+class KFDrivetrain(Drivetrain):
+  def __init__(self, name="KFDrivetrain", left_low=True, right_low=True):
+    super(KFDrivetrain, self).__init__(name, left_low, right_low)
+
+    self.unaugmented_A_continuous = self.A_continuous
+    self.unaugmented_B_continuous = self.B_continuous
+
+    # The states are
+    # The practical voltage applied to the wheels is
+    #   V_left = U_left + left_voltage_error
+    #
+    # [left position, left velocity, right position, right velocity,
+    #  left voltage error, right voltage error, angular_error]
+    self.A_continuous = numpy.matrix(numpy.zeros((7, 7)))
+    self.B_continuous = numpy.matrix(numpy.zeros((7, 2)))
+    self.A_continuous[0:4,0:4] = self.unaugmented_A_continuous
+    self.A_continuous[0:4,4:6] = self.unaugmented_B_continuous
+    self.B_continuous[0:4,0:2] = self.unaugmented_B_continuous
+    self.A_continuous[0,6] = 1
+    self.A_continuous[2,6] = -1
+
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    self.C = numpy.matrix([[1, 0, 0, 0, 0, 0, 0],
+                           [0, 0, 1, 0, 0, 0, 0],
+                           [0, -0.5 / self.rb, 0, 0.5 / self.rb, 0, 0, 0]])
+
+    self.D = numpy.matrix([[0, 0],
+                           [0, 0],
+                           [0, 0]])
+
+    q_pos = 0.05
+    q_vel = 1.00
+    q_voltage = 10.0
+    q_encoder_uncertainty = 2.00
+
+    self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
+                           [0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0],
+                           [0.0, 0.0, (q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0],
+                           [0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0, 0.0],
+                           [0.0, 0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0],
+                           [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, (q_encoder_uncertainty ** 2.0)]])
+
+    r_pos =  0.0001
+    r_gyro = 0.000001
+    self.R = numpy.matrix([[(r_pos ** 2.0), 0.0, 0.0],
+                           [0.0, (r_pos ** 2.0), 0.0],
+                           [0.0, 0.0, (r_gyro ** 2.0)]])
+
+    # Solving for kf gains.
+    self.KalmanGain, self.Q_steady = controls.kalman(
+        A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+    self.L = self.A * self.KalmanGain
+
+    # We need a nothing controller for the autogen code to be happy.
+    self.K = numpy.matrix(numpy.zeros((self.B.shape[1], self.A.shape[0])))
+
+
+def main(argv):
+  argv = FLAGS(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])
+
+  if FLAGS.plot:
+    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])
+
+  if FLAGS.plot:
+    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])
+
+  if FLAGS.plot:
+    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])
+
+  if FLAGS.plot:
+    pylab.plot(range(100), close_loop_left)
+    pylab.plot(range(100), close_loop_right)
+    pylab.show()
+
+  # Write the generated constants out to a file.
+  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)
+
+  kf_drivetrain_low_low = KFDrivetrain(
+      name="KFDrivetrainLowLow", left_low=True, right_low=True)
+  kf_drivetrain_low_high = KFDrivetrain(
+      name="KFDrivetrainLowHigh", left_low=True, right_low=False)
+  kf_drivetrain_high_low = KFDrivetrain(
+      name="KFDrivetrainHighLow", left_low=False, right_low=True)
+  kf_drivetrain_high_high = KFDrivetrain(
+      name="KFDrivetrainHighHigh", left_low=False, right_low=False)
+
+  if len(argv) != 5:
+    print "Expected .h file name and .cc file name"
+  else:
+    namespaces = ['y2014', 'control_loops', 'drivetrain']
+    dog_loop_writer = control_loop.ControlLoopWriter(
+        "Drivetrain", [drivetrain_low_low, drivetrain_low_high,
+                       drivetrain_high_low, drivetrain_high_high],
+        namespaces = namespaces)
+    dog_loop_writer.AddConstant(control_loop.Constant("kDt", "%f",
+          drivetrain_low_low.dt))
+    dog_loop_writer.AddConstant(control_loop.Constant("kStallTorque", "%f",
+          drivetrain_low_low.stall_torque))
+    dog_loop_writer.AddConstant(control_loop.Constant("kStallCurrent", "%f",
+          drivetrain_low_low.stall_current))
+    dog_loop_writer.AddConstant(control_loop.Constant("kFreeSpeedRPM", "%f",
+          drivetrain_low_low.free_speed))
+    dog_loop_writer.AddConstant(control_loop.Constant("kFreeCurrent", "%f",
+          drivetrain_low_low.free_current))
+    dog_loop_writer.AddConstant(control_loop.Constant("kJ", "%f",
+          drivetrain_low_low.J))
+    dog_loop_writer.AddConstant(control_loop.Constant("kMass", "%f",
+          drivetrain_low_low.m))
+    dog_loop_writer.AddConstant(control_loop.Constant("kRobotRadius", "%f",
+          drivetrain_low_low.rb))
+    dog_loop_writer.AddConstant(control_loop.Constant("kWheelRadius", "%f",
+          drivetrain_low_low.r))
+    dog_loop_writer.AddConstant(control_loop.Constant("kR", "%f",
+          drivetrain_low_low.resistance))
+    dog_loop_writer.AddConstant(control_loop.Constant("kV", "%f",
+          drivetrain_low_low.Kv))
+    dog_loop_writer.AddConstant(control_loop.Constant("kT", "%f",
+          drivetrain_low_low.Kt))
+
+    dog_loop_writer.Write(argv[1], argv[2])
+
+    kf_loop_writer = control_loop.ControlLoopWriter(
+        "KFDrivetrain", [kf_drivetrain_low_low, kf_drivetrain_low_high,
+                         kf_drivetrain_high_low, kf_drivetrain_high_high],
+        namespaces = namespaces)
+    kf_loop_writer.Write(argv[3], argv[4])
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/y2016/control_loops/python/polydrivetrain.py b/y2016/control_loops/python/polydrivetrain.py
new file mode 100755
index 0000000..93f3884
--- /dev/null
+++ b/y2016/control_loops/python/polydrivetrain.py
@@ -0,0 +1,512 @@
+#!/usr/bin/python
+
+import numpy
+import sys
+from frc971.control_loops.python import polytope
+from y2014.control_loops.python import drivetrain
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
+from matplotlib import pylab
+
+import gflags
+import glog
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+FLAGS = gflags.FLAGS
+
+try:
+  gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+  pass
+
+def CoerceGoal(region, K, w, R):
+  """Intersects a line with a region, and finds the closest point to R.
+
+  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.005
+    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.7, 0.7])
+    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.005
+
+    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):
+      glog.debug('%s Not in gear.', gear_name)
+      return current_gear
+    else:
+      is_high = current_gear is VelocityDrivetrain.HIGH
+      if is_high != goal_gear_is_high:
+        if goal_gear_is_high:
+          glog.debug('%s Shifting up.', gear_name)
+          return VelocityDrivetrain.SHIFTING_UP
+        else:
+          glog.debug('%s Shifting down.', gear_name)
+          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:
+      glog.debug('Not all in gear')
+      if not self.IsInGear(self.left_gear) and not self.IsInGear(self.right_gear):
+        # TODO(austin): Use battery volts here.
+        R_left = self.MotorRPM(self.left_shifter_position, self.X[0, 0])
+        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)
+
+    glog.debug('U is %s %s', str(self.U[0, 0]), str(self.U[1, 0]))
+    glog.debug('Left shifter %s %d Right shifter %s %d',
+               self.left_gear, self.left_shifter_position,
+               self.right_gear, self.right_shifter_position)
+
+
+def main(argv):
+  argv = FLAGS(argv)
+
+  vdrivetrain = VelocityDrivetrain()
+
+  if len(argv) != 5:
+    glog.fatal('Expected .h file name and .cc file name')
+  else:
+    namespaces = ['y2014', 'control_loops', 'drivetrain']
+    dog_loop_writer = control_loop.ControlLoopWriter(
+        "VelocityDrivetrain", [vdrivetrain.drivetrain_low_low,
+                       vdrivetrain.drivetrain_low_high,
+                       vdrivetrain.drivetrain_high_low,
+                       vdrivetrain.drivetrain_high_high],
+                       namespaces=namespaces)
+
+    dog_loop_writer.Write(argv[1], argv[2])
+
+    cim_writer = control_loop.ControlLoopWriter(
+        "CIM", [drivetrain.CIM()])
+
+    cim_writer.Write(argv[3], argv[4])
+    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
+
+  glog.debug('K is %s', str(vdrivetrain.CurrentDrivetrain().K))
+
+  if vdrivetrain.left_gear is VelocityDrivetrain.HIGH:
+    glog.debug('Left is high')
+  else:
+    glog.debug('Left is low')
+  if vdrivetrain.right_gear is VelocityDrivetrain.HIGH:
+    glog.debug('Right is high')
+  else:
+    glog.debug('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/y2016/control_loops/python/polydrivetrain_test.py b/y2016/control_loops/python/polydrivetrain_test.py
new file mode 100755
index 0000000..434cdca
--- /dev/null
+++ b/y2016/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/y2016/joystick_reader.cc b/y2016/joystick_reader.cc
new file mode 100644
index 0000000..137856f
--- /dev/null
+++ b/y2016/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/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 "frc971/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 y2014 {
+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;
+      }
+
+      ::frc971::control_loops::drivetrain_queue.status.FetchLatest();
+      double goal_angle = goal_angle_;
+      if (::frc971::control_loops::drivetrain_queue.status.get()) {
+        goal_angle += SpeedToAngleOffset(
+            ::frc971::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 ::y2014::constants::Values &values = ::y2014::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 y2014
+
+int main() {
+  ::aos::Init(-1);
+  ::y2014::input::joysticks::Reader reader;
+  reader.Run();
+  ::aos::Cleanup();
+}
diff --git a/y2016/wpilib/BUILD b/y2016/wpilib/BUILD
new file mode 100644
index 0000000..120ff49
--- /dev/null
+++ b/y2016/wpilib/BUILD
@@ -0,0 +1,38 @@
+package(default_visibility = ['//visibility:public'])
+
+cc_binary(
+  name = 'wpilib_interface',
+  srcs = [
+    'wpilib_interface.cc',
+  ],
+  deps = [
+    '//aos/linux_code:init',
+    '//aos/common:stl_mutex',
+    '//aos/common/logging',
+    '//aos/externals:wpilib',
+    '//y2014:constants',
+    '//y2014/queues:auto_mode',
+    '//frc971/control_loops/drivetrain:drivetrain_queue',
+    '//y2014/control_loops/shooter:shooter_queue',
+    '//y2014/control_loops/claw:claw_queue',
+    '//aos/common/controls:control_loop',
+    '//aos/common/util:log_interval',
+    '//aos/common:time',
+    '//aos/common/logging:queue_logging',
+    '//aos/common/messages:robot_state',
+    '//aos/common/util:phased_loop',
+    '//aos/common/util:wrapping_counter',
+    '//frc971/wpilib:joystick_sender',
+    '//frc971/wpilib:loop_output_handler',
+    '//frc971/wpilib:buffered_pcm',
+    '//frc971/wpilib:gyro_sender',
+    '//frc971/wpilib:dma_edge_counting',
+    '//frc971/wpilib:interrupt_edge_counting',
+    '//frc971/wpilib:wpilib_robot_base',
+    '//frc971/wpilib:encoder_and_potentiometer',
+    '//frc971/control_loops:queues',
+    '//frc971/wpilib:logging_queue',
+    '//frc971/wpilib:wpilib_interface',
+    '//frc971/wpilib:pdp_fetcher',
+  ],
+)
diff --git a/y2016/wpilib/wpilib_interface.cc b/y2016/wpilib/wpilib_interface.cc
new file mode 100644
index 0000000..6442a2a
--- /dev/null
+++ b/y2016/wpilib/wpilib_interface.cc
@@ -0,0 +1,814 @@
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+#include <inttypes.h>
+
+#include <thread>
+#include <mutex>
+#include <functional>
+
+#include "Encoder.h"
+#include "Talon.h"
+#include "DriverStation.h"
+#include "AnalogInput.h"
+#include "Compressor.h"
+#include "Relay.h"
+#include "frc971/wpilib/wpilib_robot_base.h"
+#include "dma.h"
+#ifndef WPILIB2015
+#include "DigitalGlitchFilter.h"
+#endif
+#undef ERROR
+
+#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 "frc971/shifter_hall_effect.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "y2014/control_loops/claw/claw.q.h"
+#include "y2014/control_loops/shooter/shooter.q.h"
+#include "y2014/constants.h"
+#include "y2014/queues/auto_mode.q.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 "frc971/wpilib/wpilib_interface.h"
+#include "frc971/wpilib/pdp_fetcher.h"
+
+#ifndef M_PI
+#define M_PI 3.14159265358979323846
+#endif
+
+using ::frc971::control_loops::drivetrain_queue;
+using ::y2014::control_loops::claw_queue;
+using ::y2014::control_loops::shooter_queue;
+
+namespace y2014 {
+namespace wpilib {
+
+// TODO(Brian): Fix the interpretation of the result of GetRaw here and in the
+// DMA stuff and then removing the * 2.0 in *_translate.
+// The low bit is direction.
+
+// 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)...));
+}
+
+double drivetrain_translate(int32_t in) {
+  return -static_cast<double>(in) /
+         (256.0 /*cpr*/ * 4.0 /*4x*/) *
+         constants::GetValues().drivetrain_encoder_ratio *
+         (3.5 /*wheel diameter*/ * 2.54 / 100.0 * M_PI) * 2.0 / 2.0;
+}
+
+double drivetrain_velocity_translate(double in) {
+  return (1.0 / in) / 256.0 /*cpr*/ *
+         constants::GetValues().drivetrain_encoder_ratio *
+         (3.5 /*wheel diameter*/ * 2.54 / 100.0 * M_PI) * 2.0 / 2.0;
+}
+
+float hall_translate(const constants::ShifterHallEffect &k, float in_low,
+                     float in_high) {
+  const float low_ratio =
+      0.5 * (in_low - static_cast<float>(k.low_gear_low)) /
+      static_cast<float>(k.low_gear_middle - k.low_gear_low);
+  const float high_ratio =
+      0.5 + 0.5 * (in_high - static_cast<float>(k.high_gear_middle)) /
+                static_cast<float>(k.high_gear_high - k.high_gear_middle);
+
+  // Return low when we are below 1/2, and high when we are above 1/2.
+  if (low_ratio + high_ratio < 1.0) {
+    return low_ratio;
+  } else {
+    return high_ratio;
+  }
+}
+
+double claw_translate(int32_t in) {
+  return -static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*quad*/) /
+         (18.0 / 48.0 /*encoder gears*/) / (12.0 / 60.0 /*chain reduction*/) *
+         (M_PI / 180.0) * 2.0;
+}
+
+double shooter_translate(int32_t in) {
+  return static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*quad*/) *
+         16 /*sprocket teeth*/ * 0.375 /*chain pitch*/
+         * (2.54 / 100.0 /*in to m*/);
+}
+
+static const double kMaximumEncoderPulsesPerSecond =
+    5600.0 /* free speed RPM */ * 14.0 / 48.0 /* bottom gear reduction */ *
+    18.0 / 32.0 /* big belt reduction */ *
+    18.0 / 66.0 /* top gear reduction */ * 48.0 / 18.0 /* encoder gears */ /
+    60.0 /* seconds / minute */ * 256.0 /* CPR */;
+
+class SensorReader {
+ public:
+  SensorReader() {
+    // Set it to filter out anything shorter than 1/4 of the minimum pulse width
+    // we should ever see.
+    encoder_filter_.SetPeriodNanoSeconds(
+        static_cast<int>(1 / 4.0 / kMaximumEncoderPulsesPerSecond * 1e9 + 0.5));
+    hall_filter_.SetPeriodNanoSeconds(100000);
+  }
+
+  void set_auto_selector_analog(::std::unique_ptr<AnalogInput> analog) {
+    auto_selector_analog_ = ::std::move(analog);
+  }
+
+  void set_drivetrain_left_encoder(::std::unique_ptr<Encoder> encoder) {
+    drivetrain_left_encoder_ = ::std::move(encoder);
+    drivetrain_left_encoder_->SetMaxPeriod(0.005);
+  }
+
+  void set_drivetrain_right_encoder(::std::unique_ptr<Encoder> encoder) {
+    drivetrain_right_encoder_ = ::std::move(encoder);
+    drivetrain_right_encoder_->SetMaxPeriod(0.005);
+  }
+
+  void set_high_left_drive_hall(::std::unique_ptr<AnalogInput> analog) {
+    high_left_drive_hall_ = ::std::move(analog);
+  }
+
+  void set_low_right_drive_hall(::std::unique_ptr<AnalogInput> analog) {
+    low_right_drive_hall_ = ::std::move(analog);
+  }
+
+  void set_high_right_drive_hall(::std::unique_ptr<AnalogInput> analog) {
+    high_right_drive_hall_ = ::std::move(analog);
+  }
+
+  void set_low_left_drive_hall(::std::unique_ptr<AnalogInput> analog) {
+    low_left_drive_hall_ = ::std::move(analog);
+  }
+
+  void set_top_claw_encoder(::std::unique_ptr<Encoder> encoder) {
+    encoder_filter_.Add(encoder.get());
+    top_reader_.set_encoder(::std::move(encoder));
+  }
+
+  void set_top_claw_front_hall(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    top_reader_.set_front_hall(::std::move(hall));
+  }
+
+  void set_top_claw_calibration_hall(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    top_reader_.set_calibration_hall(::std::move(hall));
+  }
+
+  void set_top_claw_back_hall(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    top_reader_.set_back_hall(::std::move(hall));
+  }
+
+  void set_bottom_claw_encoder(::std::unique_ptr<Encoder> encoder) {
+    encoder_filter_.Add(encoder.get());
+    bottom_reader_.set_encoder(::std::move(encoder));
+  }
+
+  void set_bottom_claw_front_hall(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    bottom_reader_.set_front_hall(::std::move(hall));
+  }
+
+  void set_bottom_claw_calibration_hall(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    bottom_reader_.set_calibration_hall(::std::move(hall));
+  }
+
+  void set_bottom_claw_back_hall(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    bottom_reader_.set_back_hall(::std::move(hall));
+  }
+
+  void set_shooter_encoder(::std::unique_ptr<Encoder> encoder) {
+    encoder_filter_.Add(encoder.get());
+    shooter_encoder_ = ::std::move(encoder);
+  }
+
+  void set_shooter_proximal(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    shooter_proximal_ = ::std::move(hall);
+  }
+
+  void set_shooter_distal(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    shooter_distal_ = ::std::move(hall);
+  }
+
+  void set_shooter_plunger(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    shooter_plunger_ = ::std::move(hall);
+    shooter_plunger_reader_ =
+        make_unique<::frc971::wpilib::DMADigitalReader>(shooter_plunger_.get());
+  }
+
+  void set_shooter_latch(::std::unique_ptr<DigitalInput> hall) {
+    hall_filter_.Add(hall.get());
+    shooter_latch_ = ::std::move(hall);
+    shooter_latch_reader_ =
+        make_unique<::frc971::wpilib::DMADigitalReader>(shooter_latch_.get());
+  }
+
+  // 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) {
+    shooter_proximal_counter_ = make_unique<::frc971::wpilib::DMAEdgeCounter>(
+        shooter_encoder_.get(), shooter_proximal_.get());
+    shooter_distal_counter_ = make_unique<::frc971::wpilib::DMAEdgeCounter>(
+        shooter_encoder_.get(), shooter_distal_.get());
+
+    dma_synchronizer_.reset(
+        new ::frc971::wpilib::DMASynchronizer(::std::move(dma)));
+    dma_synchronizer_->Add(shooter_proximal_counter_.get());
+    dma_synchronizer_->Add(shooter_distal_counter_.get());
+    dma_synchronizer_->Add(shooter_plunger_reader_.get());
+    dma_synchronizer_->Add(shooter_latch_reader_.get());
+  }
+
+  void operator()() {
+    ::aos::SetCurrentThreadName("SensorReader");
+
+    my_pid_ = getpid();
+    ds_ =
+#ifdef WPILIB2015
+        DriverStation::GetInstance();
+#else
+        &DriverStation::GetInstance();
+#endif
+
+    top_reader_.Start();
+    bottom_reader_.Start();
+    dma_synchronizer_->Start();
+
+    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+                                        ::aos::time::Time::InMS(4));
+
+    ::aos::SetCurrentThreadRealtimePriority(40);
+    while (run_) {
+      {
+        const int iterations = phased_loop.SleepUntilNext();
+        if (iterations != 1) {
+          LOG(WARNING, "SensorReader skipped %d iterations\n", iterations - 1);
+        }
+      }
+      RunIteration();
+    }
+
+    top_reader_.Quit();
+    bottom_reader_.Quit();
+  }
+
+  void RunIteration() {
+    ::frc971::wpilib::SendRobotState(my_pid_, ds_);
+
+    const auto &values = constants::GetValues();
+
+    {
+      auto drivetrain_message = drivetrain_queue.position.MakeMessage();
+      drivetrain_message->right_encoder =
+          drivetrain_translate(drivetrain_right_encoder_->GetRaw());
+      drivetrain_message->left_encoder =
+          -drivetrain_translate(drivetrain_left_encoder_->GetRaw());
+      drivetrain_message->left_speed =
+          drivetrain_velocity_translate(drivetrain_left_encoder_->GetPeriod());
+      drivetrain_message->right_speed =
+          drivetrain_velocity_translate(drivetrain_right_encoder_->GetPeriod());
+
+      drivetrain_message->low_left_hall = low_left_drive_hall_->GetVoltage();
+      drivetrain_message->high_left_hall = high_left_drive_hall_->GetVoltage();
+      drivetrain_message->left_shifter_position =
+          hall_translate(values.left_drive, drivetrain_message->low_left_hall,
+                         drivetrain_message->high_left_hall);
+
+      drivetrain_message->low_right_hall = low_right_drive_hall_->GetVoltage();
+      drivetrain_message->high_right_hall =
+          high_right_drive_hall_->GetVoltage();
+      drivetrain_message->right_shifter_position =
+          hall_translate(values.right_drive, drivetrain_message->low_right_hall,
+                         drivetrain_message->high_right_hall);
+
+      drivetrain_message.Send();
+    }
+
+    ::y2014::sensors::auto_mode.MakeWithBuilder()
+        .voltage(auto_selector_analog_->GetVoltage())
+        .Send();
+
+    dma_synchronizer_->RunIteration();
+
+    {
+      auto shooter_message = shooter_queue.position.MakeMessage();
+      shooter_message->position = shooter_translate(shooter_encoder_->GetRaw());
+      shooter_message->plunger = !shooter_plunger_reader_->value();
+      shooter_message->latch = !shooter_latch_reader_->value();
+      CopyShooterPosedgeCounts(shooter_proximal_counter_.get(),
+                               &shooter_message->pusher_proximal);
+      CopyShooterPosedgeCounts(shooter_distal_counter_.get(),
+                               &shooter_message->pusher_distal);
+
+      shooter_message.Send();
+    }
+
+    {
+      auto claw_message = claw_queue.position.MakeMessage();
+      top_reader_.RunIteration(&claw_message->top);
+      bottom_reader_.RunIteration(&claw_message->bottom);
+
+      claw_message.Send();
+    }
+  }
+
+  void Quit() { run_ = false; }
+
+ private:
+  class HalfClawReader {
+   public:
+    HalfClawReader(bool reversed) : reversed_(reversed) {}
+
+    void set_encoder(::std::unique_ptr<Encoder> encoder) {
+      encoder_ = ::std::move(encoder);
+    }
+
+    void set_front_hall(::std::unique_ptr<DigitalInput> front_hall) {
+      front_hall_ = ::std::move(front_hall);
+    }
+
+    void set_calibration_hall(
+        ::std::unique_ptr<DigitalInput> calibration_hall) {
+      calibration_hall_ = ::std::move(calibration_hall);
+    }
+
+    void set_back_hall(::std::unique_ptr<DigitalInput> back_hall) {
+      back_hall_ = ::std::move(back_hall);
+    }
+
+    void Start() {
+      front_counter_ = make_unique<::frc971::wpilib::EdgeCounter>(
+          encoder_.get(), front_hall_.get());
+      synchronizer_.Add(front_counter_.get());
+      calibration_counter_ = make_unique<::frc971::wpilib::EdgeCounter>(
+          encoder_.get(), calibration_hall_.get());
+      synchronizer_.Add(calibration_counter_.get());
+      back_counter_ = make_unique<::frc971::wpilib::EdgeCounter>(
+          encoder_.get(), back_hall_.get());
+      synchronizer_.Add(back_counter_.get());
+      synchronized_encoder_ =
+          make_unique<::frc971::wpilib::InterruptSynchronizedEncoder>(
+              encoder_.get());
+      synchronizer_.Add(synchronized_encoder_.get());
+
+      synchronizer_.Start();
+    }
+
+    void Quit() { synchronizer_.Quit(); }
+
+    void RunIteration(control_loops::HalfClawPosition *half_claw_position) {
+      const double multiplier = reversed_ ? -1.0 : 1.0;
+
+      synchronizer_.RunIteration();
+
+      CopyPosition(front_counter_.get(), &half_claw_position->front);
+      CopyPosition(calibration_counter_.get(),
+                   &half_claw_position->calibration);
+      CopyPosition(back_counter_.get(), &half_claw_position->back);
+      half_claw_position->position =
+          multiplier * claw_translate(synchronized_encoder_->get());
+    }
+
+   private:
+    void CopyPosition(const ::frc971::wpilib::EdgeCounter *counter,
+                      ::frc971::HallEffectStruct *out) {
+      const double multiplier = reversed_ ? -1.0 : 1.0;
+
+      out->current = !counter->polled_value();
+      out->posedge_count = counter->negative_interrupt_count();
+      out->negedge_count = counter->positive_interrupt_count();
+      out->negedge_value =
+          multiplier * claw_translate(counter->last_positive_encoder_value());
+      out->posedge_value =
+          multiplier * claw_translate(counter->last_negative_encoder_value());
+    }
+
+    ::frc971::wpilib::InterruptSynchronizer synchronizer_{55};
+
+    ::std::unique_ptr<::frc971::wpilib::EdgeCounter> front_counter_;
+    ::std::unique_ptr<::frc971::wpilib::EdgeCounter> calibration_counter_;
+    ::std::unique_ptr<::frc971::wpilib::EdgeCounter> back_counter_;
+    ::std::unique_ptr<::frc971::wpilib::InterruptSynchronizedEncoder>
+        synchronized_encoder_;
+
+    ::std::unique_ptr<Encoder> encoder_;
+    ::std::unique_ptr<DigitalInput> front_hall_;
+    ::std::unique_ptr<DigitalInput> calibration_hall_;
+    ::std::unique_ptr<DigitalInput> back_hall_;
+
+    const bool reversed_;
+  };
+
+  void CopyShooterPosedgeCounts(
+      const ::frc971::wpilib::DMAEdgeCounter *counter,
+      ::frc971::PosedgeOnlyCountedHallEffectStruct *output) {
+    output->current = !counter->polled_value();
+    // These are inverted because the hall effects give logical false when
+    // there's a magnet in front of them.
+    output->posedge_count = counter->negative_count();
+    output->negedge_count = counter->positive_count();
+    output->posedge_value =
+        shooter_translate(counter->last_negative_encoder_value());
+  }
+
+  int32_t my_pid_;
+  DriverStation *ds_;
+
+  ::std::unique_ptr<::frc971::wpilib::DMASynchronizer> dma_synchronizer_;
+
+  ::std::unique_ptr<AnalogInput> auto_selector_analog_;
+
+  ::std::unique_ptr<Encoder> drivetrain_left_encoder_;
+  ::std::unique_ptr<Encoder> drivetrain_right_encoder_;
+  ::std::unique_ptr<AnalogInput> low_left_drive_hall_;
+  ::std::unique_ptr<AnalogInput> high_left_drive_hall_;
+  ::std::unique_ptr<AnalogInput> low_right_drive_hall_;
+  ::std::unique_ptr<AnalogInput> high_right_drive_hall_;
+
+  HalfClawReader top_reader_{false}, bottom_reader_{true};
+
+  ::std::unique_ptr<Encoder> shooter_encoder_;
+  ::std::unique_ptr<DigitalInput> shooter_proximal_, shooter_distal_;
+  ::std::unique_ptr<DigitalInput> shooter_plunger_, shooter_latch_;
+  ::std::unique_ptr<::frc971::wpilib::DMAEdgeCounter> shooter_proximal_counter_,
+      shooter_distal_counter_;
+  ::std::unique_ptr<::frc971::wpilib::DMADigitalReader> shooter_plunger_reader_,
+      shooter_latch_reader_;
+
+  ::std::atomic<bool> run_{true};
+  DigitalGlitchFilter encoder_filter_, hall_filter_;
+};
+
+class SolenoidWriter {
+ public:
+  SolenoidWriter(const ::std::unique_ptr<::frc971::wpilib::BufferedPcm> &pcm)
+      : pcm_(pcm),
+        shooter_(".y2014.control_loops.shooter_queue.output"),
+        drivetrain_(".frc971.control_loops.drivetrain_queue.output") {}
+
+  void set_pressure_switch(::std::unique_ptr<DigitalInput> 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_drivetrain_left(
+      ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> s) {
+    drivetrain_left_ = ::std::move(s);
+  }
+
+  void set_drivetrain_right(
+      ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> s) {
+    drivetrain_right_ = ::std::move(s);
+  }
+
+  void set_shooter_latch(
+      ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> s) {
+    shooter_latch_ = ::std::move(s);
+  }
+
+  void set_shooter_brake(
+      ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> s) {
+    shooter_brake_ = ::std::move(s);
+  }
+
+  void operator()() {
+    ::aos::SetCurrentThreadName("Solenoids");
+    ::aos::SetCurrentThreadRealtimePriority(27);
+
+    ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
+                                        ::aos::time::Time::InMS(1));
+
+    while (run_) {
+      {
+        const int iterations = phased_loop.SleepUntilNext();
+        if (iterations != 1) {
+          LOG(DEBUG, "Solenoids skipped %d iterations\n", iterations - 1);
+        }
+      }
+
+      {
+        shooter_.FetchLatest();
+        if (shooter_.get()) {
+          LOG_STRUCT(DEBUG, "solenoids", *shooter_);
+          shooter_latch_->Set(!shooter_->latch_piston);
+          shooter_brake_->Set(!shooter_->brake_piston);
+        }
+      }
+
+      {
+        drivetrain_.FetchLatest();
+        if (drivetrain_.get()) {
+          LOG_STRUCT(DEBUG, "solenoids", *drivetrain_);
+          drivetrain_left_->Set(!drivetrain_->left_high);
+          drivetrain_right_->Set(!drivetrain_->right_high);
+        }
+      }
+
+      {
+        ::frc971::wpilib::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<::frc971::wpilib::BufferedPcm> &pcm_;
+
+  ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> drivetrain_left_;
+  ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> drivetrain_right_;
+  ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> shooter_latch_;
+  ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> shooter_brake_;
+
+  ::std::unique_ptr<DigitalInput> pressure_switch_;
+  ::std::unique_ptr<Relay> compressor_relay_;
+
+  ::aos::Queue<::y2014::control_loops::ShooterQueue::Output> shooter_;
+  ::aos::Queue<::frc971::control_loops::DrivetrainQueue::Output> drivetrain_;
+
+  ::std::atomic<bool> run_{true};
+};
+
+class DrivetrainWriter : public ::frc971::wpilib::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 ShooterWriter : public ::frc971::wpilib::LoopOutputHandler {
+ public:
+  void set_shooter_talon(::std::unique_ptr<Talon> t) {
+    shooter_talon_ = ::std::move(t);
+  }
+
+ private:
+  virtual void Read() override {
+    ::y2014::control_loops::shooter_queue.output.FetchAnother();
+  }
+
+  virtual void Write() override {
+    auto &queue = ::y2014::control_loops::shooter_queue.output;
+    LOG_STRUCT(DEBUG, "will output", *queue);
+    shooter_talon_->Set(queue->voltage / 12.0);
+  }
+
+  virtual void Stop() override {
+    LOG(WARNING, "shooter output too old\n");
+    shooter_talon_->Disable();
+  }
+
+  ::std::unique_ptr<Talon> shooter_talon_;
+};
+
+class ClawWriter : public ::frc971::wpilib::LoopOutputHandler {
+ public:
+  void set_top_claw_talon(::std::unique_ptr<Talon> t) {
+    top_claw_talon_ = ::std::move(t);
+  }
+
+  void set_bottom_claw_talon(::std::unique_ptr<Talon> t) {
+    bottom_claw_talon_ = ::std::move(t);
+  }
+
+  void set_left_tusk_talon(::std::unique_ptr<Talon> t) {
+    left_tusk_talon_ = ::std::move(t);
+  }
+
+  void set_right_tusk_talon(::std::unique_ptr<Talon> t) {
+    right_tusk_talon_ = ::std::move(t);
+  }
+
+  void set_intake1_talon(::std::unique_ptr<Talon> t) {
+    intake1_talon_ = ::std::move(t);
+  }
+
+  void set_intake2_talon(::std::unique_ptr<Talon> t) {
+    intake2_talon_ = ::std::move(t);
+  }
+
+ private:
+  virtual void Read() override {
+    ::y2014::control_loops::claw_queue.output.FetchAnother();
+  }
+
+  virtual void Write() override {
+    auto &queue = ::y2014::control_loops::claw_queue.output;
+    LOG_STRUCT(DEBUG, "will output", *queue);
+    intake1_talon_->Set(queue->intake_voltage / 12.0);
+    intake2_talon_->Set(queue->intake_voltage / 12.0);
+    bottom_claw_talon_->Set(-queue->bottom_claw_voltage / 12.0);
+    top_claw_talon_->Set(queue->top_claw_voltage / 12.0);
+    left_tusk_talon_->Set(queue->tusk_voltage / 12.0);
+    right_tusk_talon_->Set(-queue->tusk_voltage / 12.0);
+  }
+
+  virtual void Stop() override {
+    LOG(WARNING, "claw output too old\n");
+    intake1_talon_->Disable();
+    intake2_talon_->Disable();
+    bottom_claw_talon_->Disable();
+    top_claw_talon_->Disable();
+    left_tusk_talon_->Disable();
+    right_tusk_talon_->Disable();
+  }
+
+  ::std::unique_ptr<Talon> top_claw_talon_;
+  ::std::unique_ptr<Talon> bottom_claw_talon_;
+  ::std::unique_ptr<Talon> left_tusk_talon_;
+  ::std::unique_ptr<Talon> right_tusk_talon_;
+  ::std::unique_ptr<Talon> intake1_talon_;
+  ::std::unique_ptr<Talon> intake2_talon_;
+};
+
+class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
+ public:
+  ::std::unique_ptr<Encoder> make_encoder(int index) {
+    return make_unique<Encoder>(10 + index * 2, 11 + index * 2, false,
+                                Encoder::k4X);
+  }
+
+  void Run() override {
+    ::aos::InitNRT();
+    ::aos::SetCurrentThreadName("StartCompetition");
+
+    ::frc971::wpilib::JoystickSender joystick_sender;
+    ::std::thread joystick_thread(::std::ref(joystick_sender));
+
+    ::frc971::wpilib::PDPFetcher pdp_fetcher;
+    ::std::thread pdp_fetcher_thread(::std::ref(pdp_fetcher));
+    SensorReader reader;
+
+    // Create this first to make sure it ends up in one of the lower-numbered
+    // FPGA slots so we can use it with DMA.
+    auto shooter_encoder_temp = make_encoder(2);
+
+    reader.set_auto_selector_analog(make_unique<AnalogInput>(4));
+
+    reader.set_drivetrain_left_encoder(make_encoder(0));
+    reader.set_drivetrain_right_encoder(make_encoder(1));
+    reader.set_high_left_drive_hall(make_unique<AnalogInput>(1));
+    reader.set_low_left_drive_hall(make_unique<AnalogInput>(0));
+    reader.set_high_right_drive_hall(make_unique<AnalogInput>(2));
+    reader.set_low_right_drive_hall(make_unique<AnalogInput>(3));
+
+    reader.set_top_claw_encoder(make_encoder(3));
+    reader.set_top_claw_front_hall(make_unique<DigitalInput>(4));  // R2
+    reader.set_top_claw_calibration_hall(make_unique<DigitalInput>(3));  // R3
+    reader.set_top_claw_back_hall(make_unique<DigitalInput>(5));  // R1
+
+    reader.set_bottom_claw_encoder(make_encoder(4));
+    reader.set_bottom_claw_front_hall(make_unique<DigitalInput>(1));  // L2
+    reader.set_bottom_claw_calibration_hall(make_unique<DigitalInput>(0));  // L3
+    reader.set_bottom_claw_back_hall(make_unique<DigitalInput>(2));  // L1
+
+    reader.set_shooter_encoder(::std::move(shooter_encoder_temp));
+    reader.set_shooter_proximal(make_unique<DigitalInput>(6));  // S1
+    reader.set_shooter_distal(make_unique<DigitalInput>(7));  // S2
+    reader.set_shooter_plunger(make_unique<DigitalInput>(8));  // S3
+    reader.set_shooter_latch(make_unique<DigitalInput>(9));  // S4
+
+    reader.set_dma(make_unique<DMA>());
+    ::std::thread reader_thread(::std::ref(reader));
+
+    ::frc971::wpilib::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(5)));
+    drivetrain_writer.set_right_drivetrain_talon(
+        ::std::unique_ptr<Talon>(new Talon(2)));
+    ::std::thread drivetrain_writer_thread(::std::ref(drivetrain_writer));
+
+    ::y2014::wpilib::ClawWriter claw_writer;
+    claw_writer.set_top_claw_talon(::std::unique_ptr<Talon>(new Talon(1)));
+    claw_writer.set_bottom_claw_talon(::std::unique_ptr<Talon>(new Talon(0)));
+    claw_writer.set_left_tusk_talon(::std::unique_ptr<Talon>(new Talon(4)));
+    claw_writer.set_right_tusk_talon(::std::unique_ptr<Talon>(new Talon(3)));
+    claw_writer.set_intake1_talon(::std::unique_ptr<Talon>(new Talon(7)));
+    claw_writer.set_intake2_talon(::std::unique_ptr<Talon>(new Talon(8)));
+    ::std::thread claw_writer_thread(::std::ref(claw_writer));
+
+    ::y2014::wpilib::ShooterWriter shooter_writer;
+    shooter_writer.set_shooter_talon(::std::unique_ptr<Talon>(new Talon(6)));
+    ::std::thread shooter_writer_thread(::std::ref(shooter_writer));
+
+    ::std::unique_ptr<::frc971::wpilib::BufferedPcm> pcm(
+        new ::frc971::wpilib::BufferedPcm());
+    SolenoidWriter solenoid_writer(pcm);
+    solenoid_writer.set_drivetrain_left(pcm->MakeSolenoid(6));
+    solenoid_writer.set_drivetrain_right(pcm->MakeSolenoid(7));
+    solenoid_writer.set_shooter_latch(pcm->MakeSolenoid(5));
+    solenoid_writer.set_shooter_brake(pcm->MakeSolenoid(4));
+
+    solenoid_writer.set_pressure_switch(make_unique<DigitalInput>(25));
+    solenoid_writer.set_compressor_relay(make_unique<Relay>(0));
+    ::std::thread solenoid_thread(::std::ref(solenoid_writer));
+
+    // Wait forever. Not much else to do...
+    while (true) {
+      const int r = select(0, nullptr, nullptr, nullptr, nullptr);
+      if (r != 0) {
+        PLOG(WARNING, "infinite select failed");
+      } else {
+        PLOG(WARNING, "infinite select succeeded??\n");
+      }
+    }
+
+    LOG(ERROR, "Exiting WPILibRobot\n");
+
+    joystick_sender.Quit();
+    joystick_thread.join();
+    pdp_fetcher.Quit();
+    pdp_fetcher_thread.join();
+    reader.Quit();
+    reader_thread.join();
+    gyro_sender.Quit();
+    gyro_thread.join();
+
+    drivetrain_writer.Quit();
+    drivetrain_writer_thread.join();
+    shooter_writer.Quit();
+    shooter_writer_thread.join();
+    claw_writer.Quit();
+    claw_writer_thread.join();
+    solenoid_writer.Quit();
+    solenoid_thread.join();
+
+    ::aos::Cleanup();
+  }
+};
+
+}  // namespace wpilib
+}  // namespace y2014
+
+
+AOS_ROBOT_CLASS(::y2014::wpilib::WPILibRobot);