Moved bot3 to y2015_bot3

Change-Id: Idebb248ddc3ff658f2404f367dfa4a6dc421e0c1
diff --git a/y2015_bot3/BUILD b/y2015_bot3/BUILD
new file mode 100644
index 0000000..3eebb80
--- /dev/null
+++ b/y2015_bot3/BUILD
@@ -0,0 +1,22 @@
+package(default_visibility = ['//visibility:public'])
+
+cc_binary(
+  name = 'joystick_reader',
+  srcs = [
+    'joystick_reader.cc',
+  ],
+  deps = [
+    '//aos/prime/input:joystick_input',
+    '//aos/linux_code:init',
+    '//aos/common/logging',
+    '//aos/common:time',
+    '//aos/common/util:log_interval',
+    '//aos/common/actions:action_lib',
+    '//frc971/queues:gyro',
+    '//y2015_bot3/control_loops/elevator:elevator_lib',
+    '//y2015_bot3/control_loops/drivetrain:drivetrain_queue',
+    '//y2015_bot3/control_loops/elevator:elevator_queue',
+    '//y2015_bot3/control_loops/intake:intake_queue',
+    '//y2015_bot3/autonomous:auto_queue',
+  ],
+)
diff --git a/y2015_bot3/actors/BUILD b/y2015_bot3/actors/BUILD
new file mode 100644
index 0000000..f2e3841
--- /dev/null
+++ b/y2015_bot3/actors/BUILD
@@ -0,0 +1,56 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+filegroup(
+  name = 'binaries',
+  srcs = [
+    ':drivetrain_action',
+  ],
+)
+
+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',
+    '//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',
+    '//y2015_bot3/control_loops/drivetrain:drivetrain_queue',
+    '//y2015_bot3/control_loops/drivetrain:drivetrain_lib',
+  ],
+)
+
+cc_binary(
+  name = 'drivetrain_action',
+  srcs = [
+    'drivetrain_actor_main.cc',
+  ],
+  deps = [
+    '//aos/linux_code:init',
+    '//aos/common/actions:action_lib',
+    ':drivetrain_action_queue',
+    ':drivetrain_action_lib',
+  ],
+)
diff --git a/y2015_bot3/actors/actors.gyp b/y2015_bot3/actors/actors.gyp
new file mode 100644
index 0000000..8e1c2c6
--- /dev/null
+++ b/y2015_bot3/actors/actors.gyp
@@ -0,0 +1,62 @@
+{
+  'targets': [
+    {
+      'target_name': 'binaries',
+      'type': 'none',
+      'dependencies': [
+        'drivetrain_action_bot3',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_action_queue',
+      'type': 'static_library',
+      'sources': ['drivetrain_action.q'],
+      'variables': {
+        'header_path': 'bot3/actors',
+      },
+      'dependencies': [
+        '<(AOS)/common/actions/actions.gyp:action_queue',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/actions/actions.gyp:action_queue',
+      ],
+      'includes': ['../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'drivetrain_action_lib',
+      'type': 'static_library',
+      'sources': [
+        'drivetrain_actor.cc',
+      ],
+      'dependencies': [
+        'drivetrain_action_queue',
+        '<(AOS)/common/common.gyp:time',
+        '<(AOS)/common/util/util.gyp:phased_loop',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+        '<(EXTERNALS):eigen',
+        '<(AOS)/common/util/util.gyp:trapezoid_profile',
+        '<(DEPTH)/bot3/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
+        '<(DEPTH)/bot3/control_loops/drivetrain/drivetrain.gyp:drivetrain_lib',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+        'drivetrain_action_queue',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_action_bot3',
+      'type': 'executable',
+      'sources': [
+        'drivetrain_actor_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+        'drivetrain_action_queue',
+        'drivetrain_action_lib',
+      ],
+    },
+  ],
+}
diff --git a/y2015_bot3/actors/drivetrain_action.q b/y2015_bot3/actors/drivetrain_action.q
new file mode 100644
index 0000000..9ad55d3
--- /dev/null
+++ b/y2015_bot3/actors/drivetrain_action.q
@@ -0,0 +1,29 @@
+package frc971.actors;
+
+import "aos/common/actions/actions.q";
+
+// Parameters to send with start.
+struct DrivetrainActionParams {
+  double left_initial_position;
+  double right_initial_position;
+  double y_offset;
+  double theta_offset;
+  double maximum_velocity;
+  double maximum_acceleration;
+  double maximum_turn_velocity;
+  double maximum_turn_acceleration;
+};
+
+queue_group DrivetrainActionQueueGroup {
+  implements aos.common.actions.ActionQueueGroup;
+
+  message Goal {
+    uint32_t run;
+    DrivetrainActionParams params;
+  };
+
+  queue Goal goal;
+  queue aos.common.actions.Status status;
+};
+
+queue_group DrivetrainActionQueueGroup drivetrain_action;
diff --git a/y2015_bot3/actors/drivetrain_actor.cc b/y2015_bot3/actors/drivetrain_actor.cc
new file mode 100644
index 0000000..0f9eedd
--- /dev/null
+++ b/y2015_bot3/actors/drivetrain_actor.cc
@@ -0,0 +1,172 @@
+#include "y2015_bot3/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 "y2015_bot3/actors/drivetrain_actor.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.q.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+
+namespace frc971 {
+namespace actors {
+
+using ::y2015_bot3::control_loops::drivetrain_queue;
+using ::y2015_bot3::control_loops::kDrivetrainTurnWidth;
+
+DrivetrainActor::DrivetrainActor(actors::DrivetrainActionQueueGroup* s)
+    : aos::common::actions::ActorBase<actors::DrivetrainActionQueueGroup>(s) {}
+
+bool DrivetrainActor::RunAction(const actors::DrivetrainActionParams &params) {
+  static const auto K = ::y2015_bot3::control_loops::MakeDrivetrainLoop().K();
+
+  const double yoffset = params.y_offset;
+  const double turn_offset =
+      params.theta_offset * kDrivetrainTurnWidth / 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 *
+                                        kDrivetrainTurnWidth /
+                                        2.0);
+  turn_profile.set_maximum_velocity(params.maximum_turn_velocity *
+                                    kDrivetrainTurnWidth / 2.0);
+
+  while (true) {
+    ::aos::time::PhasedLoopXMS(5, 2500);
+
+    drivetrain_queue.status.FetchLatest();
+    if (drivetrain_queue.status.get()) {
+      const auto& status = *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);
+    drivetrain_queue.goal.MakeWithBuilder()
+        .control_loop_driving(true)
+        //.highgear(false)
+        .left_goal(left_goal_state(0, 0) + params.left_initial_position)
+        .right_goal(right_goal_state(0, 0) + params.right_initial_position)
+        .left_velocity_goal(left_goal_state(1, 0))
+        .right_velocity_goal(right_goal_state(1, 0))
+        .Send();
+  }
+  if (ShouldCancel()) return true;
+  drivetrain_queue.status.FetchLatest();
+  while (!drivetrain_queue.status.get()) {
+    LOG(WARNING,
+        "No previous drivetrain status packet, trying to fetch again\n");
+    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(
+        drivetrain_queue.status->filtered_left_position -
+        (left_goal_state(0, 0) + params.left_initial_position));
+    const double right_error = ::std::abs(
+        drivetrain_queue.status->filtered_right_position -
+        (right_goal_state(0, 0) + params.right_initial_position));
+    const double velocity_error =
+        ::std::abs(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);
+    }
+    drivetrain_queue.status.FetchNextBlocking();
+  }
+  LOG(INFO, "Done moving\n");
+  return true;
+}
+
+::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
+    const ::frc971::actors::DrivetrainActionParams& params) {
+  return ::std::unique_ptr<DrivetrainAction>(
+      new DrivetrainAction(&::frc971::actors::drivetrain_action, params));
+}
+
+}  // namespace actors
+}  // namespace frc971
diff --git a/y2015_bot3/actors/drivetrain_actor.h b/y2015_bot3/actors/drivetrain_actor.h
new file mode 100644
index 0000000..0b2b579
--- /dev/null
+++ b/y2015_bot3/actors/drivetrain_actor.h
@@ -0,0 +1,31 @@
+#ifndef Y2015_BOT3_ACTIONS_DRIVETRAIN_ACTION_H_
+#define Y2015_BOT3_ACTIONS_DRIVETRAIN_ACTION_H_
+
+#include <memory>
+
+#include "y2015_bot3/actors/drivetrain_action.q.h"
+#include "aos/common/actions/actor.h"
+#include "aos/common/actions/actions.h"
+
+namespace frc971 {
+namespace actors {
+
+class DrivetrainActor
+    : public aos::common::actions::ActorBase<DrivetrainActionQueueGroup> {
+ public:
+  explicit DrivetrainActor(DrivetrainActionQueueGroup* s);
+
+  bool RunAction(const actors::DrivetrainActionParams &params) override;
+};
+
+typedef aos::common::actions::TypedAction<DrivetrainActionQueueGroup>
+    DrivetrainAction;
+
+// Makes a new DrivetrainActor action.
+::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
+    const ::frc971::actors::DrivetrainActionParams& params);
+
+}  // namespace actors
+}  // namespace frc971
+
+#endif  // Y2015_BOT3_ACTIONS_DRIVETRAIN_ACTION_H_
diff --git a/y2015_bot3/actors/drivetrain_actor_main.cc b/y2015_bot3/actors/drivetrain_actor_main.cc
new file mode 100644
index 0000000..68b860b
--- /dev/null
+++ b/y2015_bot3/actors/drivetrain_actor_main.cc
@@ -0,0 +1,18 @@
+#include <stdio.h>
+
+#include "aos/linux_code/init.h"
+#include "y2015_bot3/actors/drivetrain_action.q.h"
+#include "y2015_bot3/actors/drivetrain_actor.h"
+
+using ::aos::time::Time;
+
+int main(int /*argc*/, char * /*argv*/[]) {
+  ::aos::Init();
+
+  frc971::actors::DrivetrainActor drivetrain(
+      &::frc971::actors::drivetrain_action);
+  drivetrain.Run();
+
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2015_bot3/autonomous/BUILD b/y2015_bot3/autonomous/BUILD
new file mode 100644
index 0000000..042dbf3
--- /dev/null
+++ b/y2015_bot3/autonomous/BUILD
@@ -0,0 +1,46 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+queue_library(
+  name = 'auto_queue',
+  srcs = [
+    'auto.q',
+  ],
+)
+
+cc_library(
+  name = 'auto_lib',
+  srcs = [
+    'auto.cc',
+  ],
+  hdrs = [
+    'auto.h',
+  ],
+  deps = [
+    ':auto_queue',
+    '//aos/common/controls:control_loop',
+    '//y2015_bot3/control_loops/drivetrain:drivetrain_queue',
+    '//y2015_bot3/control_loops/drivetrain:drivetrain_lib',
+    '//y2015_bot3/actors:drivetrain_action_lib',
+    '//y2015_bot3/control_loops/elevator:elevator_queue',
+    '//y2015_bot3/control_loops/intake:intake_queue',
+    '//aos/common:time',
+    '//aos/common/util:phased_loop',
+    '//aos/common/util:trapezoid_profile',
+    '//aos/common/logging',
+    '//aos/common/logging:queue_logging',
+  ],
+)
+
+cc_binary(
+  name = 'auto',
+  srcs = [
+    'auto_main.cc',
+  ],
+  deps = [
+    '//aos/linux_code:init',
+    ':auto_queue',
+    ':auto_lib',
+  ],
+)
diff --git a/y2015_bot3/autonomous/auto.cc b/y2015_bot3/autonomous/auto.cc
new file mode 100644
index 0000000..9dd2892
--- /dev/null
+++ b/y2015_bot3/autonomous/auto.cc
@@ -0,0 +1,456 @@
+#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 "y2015_bot3/autonomous/auto.q.h"
+#include "y2015_bot3/actors/drivetrain_actor.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.q.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.h"
+#include "y2015_bot3/control_loops/elevator/elevator.q.h"
+#include "y2015_bot3/control_loops/intake/intake.q.h"
+
+using ::aos::time::Time;
+using ::y2015_bot3::control_loops::drivetrain_queue;
+using ::y2015_bot3::control_loops::intake_queue;
+using ::y2015_bot3::control_loops::elevator_queue;
+using ::y2015_bot3::control_loops::kDrivetrainTurnWidth;
+
+namespace y2015_bot3 {
+namespace autonomous {
+
+struct ProfileParams {
+  double velocity;
+  double acceleration;
+};
+
+namespace time = ::aos::time;
+namespace actors = ::frc971::actors;
+
+const ProfileParams kFastDrive = {3.0, 3.5};
+const ProfileParams kLastDrive = {4.0, 4.0};
+const ProfileParams kStackingFirstTurn = {3.0, 7.0};
+const ProfileParams kFinalDriveTurn = {3.0, 5.0};
+const ProfileParams kSlowFirstDriveTurn = {0.75, 1.5};
+const ProfileParams kSlowSecondDriveTurn = {0.6, 1.5};
+const ProfileParams kCanPickupDrive = {1.3, 3.0};
+
+static double left_initial_position, right_initial_position;
+
+bool ShouldExitAuto() {
+  ::y2015_bot3::autonomous::autonomous.FetchLatest();
+  bool ans = !::y2015_bot3::autonomous::autonomous->run_auto;
+  if (ans) {
+    LOG(INFO, "Time to exit auto mode\n");
+  }
+  return ans;
+}
+
+void ResetDrivetrain() {
+  LOG(INFO, "resetting the drivetrain\n");
+  control_loops::drivetrain_queue.goal.MakeWithBuilder()
+      .control_loop_driving(false)
+      .steering(0.0)
+      .throttle(0.0)
+      .left_goal(left_initial_position)
+      .left_velocity_goal(0)
+      .right_goal(right_initial_position)
+      .right_velocity_goal(0)
+      .Send();
+}
+
+void InitializeEncoders() {
+  control_loops::drivetrain_queue.status.FetchAnother();
+  left_initial_position =
+      control_loops::drivetrain_queue.status->filtered_left_position;
+  right_initial_position =
+      control_loops::drivetrain_queue.status->filtered_right_position;
+}
+
+::std::unique_ptr< ::frc971::actors::DrivetrainAction> SetDriveGoal(
+    double distance, const ProfileParams drive_params, double theta,
+    const ProfileParams &turn_params) {
+  LOG(INFO, "Driving to %f\n", distance);
+
+  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 * kDrivetrainTurnWidth / 2.0;
+  right_initial_position += distance + theta * kDrivetrainTurnWidth / 2.0;
+  return ::std::move(drivetrain_action);
+}
+void WaitUntilDoneOrCanceled(
+    ::std::unique_ptr<aos::common::actions::Action> action) {
+  if (!action) {
+    LOG(ERROR, "No action, not waiting\n");
+    return;
+  }
+  while (true) {
+    // Poll the running bit and auto done bits.
+    ::aos::time::PhasedLoopXMS(5, 2500);
+    if (!action->Running() || ShouldExitAuto()) {
+      return;
+    }
+  }
+}
+
+void WaitUntilNear(double distance) {
+  while (true) {
+    if (ShouldExitAuto()) return;
+    control_loops::drivetrain_queue.status.FetchAnother();
+    double left_error = ::std::abs(
+        left_initial_position -
+        control_loops::drivetrain_queue.status->filtered_left_position);
+    double right_error = ::std::abs(
+        right_initial_position -
+        control_loops::drivetrain_queue.status->filtered_right_position);
+    const double kPositionThreshold = 0.05 + distance;
+    if (right_error < kPositionThreshold && left_error < kPositionThreshold) {
+      LOG(INFO, "At the goal\n");
+      return;
+    }
+  }
+}
+
+void GrabberForTime(double voltage, double wait_time) {
+  ::aos::time::Time now = ::aos::time::Time::Now();
+  ::aos::time::Time end_time = now + time::Time::InSeconds(wait_time);
+  LOG(INFO, "Starting to grab at %f for %f seconds\n", voltage, wait_time);
+
+  while (true) {
+    autonomous::can_grabber_control.MakeWithBuilder()
+        .can_grabber_voltage(voltage).can_grabbers(false).Send();
+
+    // Poll the running bit and auto done bits.
+    if (ShouldExitAuto()) {
+      return;
+    }
+    if (::aos::time::Time::Now() > end_time) {
+      LOG(INFO, "Done grabbing\n");
+      return;
+    }
+    ::aos::time::PhasedLoopXMS(5, 2500);
+  }
+}
+
+// Auto methods.
+void CanGrabberAuto() {
+  ResetDrivetrain();
+
+  // Launch can grabbers.
+  //GrabberForTime(12.0, 0.26);
+  GrabberForTime(6.0, 0.40);
+  if (ShouldExitAuto()) return;
+  InitializeEncoders();
+  ResetDrivetrain();
+  if (ShouldExitAuto()) return;
+  // Send our intake goals.
+  if (!intake_queue.goal.MakeWithBuilder().movement(0.0).claw_closed(true)
+          .Send()) {
+    LOG(ERROR, "Sending intake goal failed.\n");
+  }
+  {
+    auto new_elevator_goal = elevator_queue.goal.MakeMessage();
+    new_elevator_goal->max_velocity = 0.0;
+    new_elevator_goal->max_acceleration = 0.0;
+    new_elevator_goal->height = 0.030;
+    new_elevator_goal->velocity = 0.0;
+    new_elevator_goal->passive_support = true;
+    new_elevator_goal->can_support = false;
+
+    if (new_elevator_goal.Send()) {
+      LOG(DEBUG, "sending goals: elevator: %f\n", 0.03);
+    } else {
+      LOG(ERROR, "Sending elevator goal failed.\n");
+    }
+  }
+
+  const double kMoveBackDistance = 1.75;
+  //const double kMoveBackDistance = 0.0;
+
+  // Drive backwards, and pulse the can grabbers again to tip the cans.
+  control_loops::drivetrain_queue.goal.MakeWithBuilder()
+      .control_loop_driving(true)
+      .steering(0.0)
+      .throttle(0.0)
+      .left_goal(left_initial_position + kMoveBackDistance)
+      .left_velocity_goal(0)
+      .right_goal(right_initial_position + kMoveBackDistance)
+      .right_velocity_goal(0)
+      .Send();
+  GrabberForTime(12.0, 0.02);
+  if (ShouldExitAuto()) return;
+
+  // We shouldn't need as much power at this point, so lower the can grabber
+  // voltages to avoid damaging the motors due to stalling.
+  GrabberForTime(4.0, 0.75);
+  if (ShouldExitAuto()) return;
+  GrabberForTime(-3.0, 0.25);
+  if (ShouldExitAuto()) return;
+  GrabberForTime(-12.0, 1.0);
+  if (ShouldExitAuto()) return;
+  GrabberForTime(-3.0, 12.0);
+}
+
+const ProfileParams kElevatorProfile = {1.0, 5.0};
+
+static double elevator_goal_height = 0.0;
+
+void SetElevatorHeight(double height, const ProfileParams params,
+                       bool can_open = false, bool support_open = true) {
+  // Send our elevator goals, with limits set in the profile params.
+  auto new_elevator_goal = elevator_queue.goal.MakeMessage();
+  elevator_goal_height = height;
+  new_elevator_goal->max_velocity = params.velocity;
+  new_elevator_goal->max_acceleration = params.acceleration;
+  new_elevator_goal->height = elevator_goal_height;
+  new_elevator_goal->velocity = 0.0;
+  new_elevator_goal->passive_support = support_open;
+  new_elevator_goal->can_support = can_open;
+
+  if (new_elevator_goal.Send()) {
+    LOG(DEBUG, "sending goals: elevator: %f\n", elevator_goal_height);
+  } else {
+    LOG(ERROR, "Sending elevator goal failed.\n");
+  }
+}
+
+void WaitForElevator() {
+  while (true) {
+    if (ShouldExitAuto()) return;
+    control_loops::elevator_queue.status.FetchAnother();
+
+    constexpr double kProfileError = 1e-5;
+    constexpr double kEpsilon = 0.03;
+
+    if (::std::abs(control_loops::elevator_queue.status->goal_height -
+                   elevator_goal_height) <
+            kProfileError &&
+        ::std::abs(control_loops::elevator_queue.status->goal_velocity) <
+            kProfileError) {
+      LOG(INFO, "Profile done.\n");
+      if (::std::abs(control_loops::elevator_queue.status->height -
+                     elevator_goal_height) <
+          kEpsilon) {
+        LOG(INFO, "Near goal, done.\n");
+        return;
+      }
+    }
+  }
+}
+
+void WaitUntilElevatorBelow(double height) {
+  while (true) {
+    if (ShouldExitAuto()) return;
+    control_loops::elevator_queue.status.FetchAnother();
+
+    if (control_loops::elevator_queue.status->goal_height < height) {
+      LOG(INFO, "Profile below.\n");
+      if (control_loops::elevator_queue.status->height < height) {
+        LOG(INFO, "Elevator below goal, done.\n");
+        return;
+      }
+    }
+  }
+}
+
+void WaitUntilElevatorAbove(double height) {
+  while (true) {
+    if (ShouldExitAuto()) return;
+    control_loops::elevator_queue.status.FetchAnother();
+
+    if (control_loops::elevator_queue.status->goal_height > height) {
+      LOG(INFO, "Profile above.\n");
+      if (control_loops::elevator_queue.status->height > height) {
+        LOG(INFO, "Elevator above goal, done.\n");
+        return;
+      }
+    }
+  }
+}
+
+void LiftTote(double final_height = 0.48) {
+  // Send our intake goals.
+  if (!intake_queue.goal.MakeWithBuilder().movement(10.0).claw_closed(true)
+          .Send()) {
+    LOG(ERROR, "Sending intake goal failed.\n");
+  }
+
+  while (true) {
+    elevator_queue.status.FetchAnother();
+    if (!elevator_queue.status.get()) {
+      LOG(ERROR, "Got no elevator status packet.\n");
+    }
+    if (ShouldExitAuto()) return;
+    if (elevator_queue.status->has_tote) {
+      break;
+    }
+  }
+  if (!intake_queue.goal.MakeWithBuilder().movement(0.0).claw_closed(true)
+          .Send()) {
+    LOG(ERROR, "Sending intake goal failed.\n");
+  }
+  SetElevatorHeight(0.02, kElevatorProfile, false, false);
+  WaitUntilElevatorBelow(0.05);
+  if (ShouldExitAuto()) return;
+
+  SetElevatorHeight(final_height, kElevatorProfile, false, false);
+}
+
+void TripleCanAuto() {
+  ::aos::time::Time start_time = ::aos::time::Time::Now();
+
+  ::std::unique_ptr<::frc971::actors::DrivetrainAction> drive;
+  InitializeEncoders();
+  ResetDrivetrain();
+
+  SetElevatorHeight(0.03, kElevatorProfile, false, true);
+
+
+  LiftTote();
+  if (ShouldExitAuto()) return;
+
+  // The amount to turn out for going around the first can.
+  const double kFirstTurn = 0.5;
+
+  drive = SetDriveGoal(0.0, kFastDrive, kFirstTurn, kStackingFirstTurn);
+
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  drive = SetDriveGoal(2.0, kFastDrive, -kFirstTurn * 2.0, kSlowFirstDriveTurn);
+
+  WaitUntilNear(1.5);
+  if (ShouldExitAuto()) return;
+
+  if (!intake_queue.goal.MakeWithBuilder().movement(0.0).claw_closed(false)
+          .Send()) {
+    LOG(ERROR, "Sending intake goal failed.\n");
+  }
+
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  drive = SetDriveGoal(0.0, kFastDrive, kFirstTurn, kStackingFirstTurn);
+  LiftTote();
+  if (ShouldExitAuto()) return;
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  // The amount to turn out for going around the second can.
+  const double kSecondTurn = 0.35;
+  const double kSecondTurnExtraOnSecond = 0.10;
+
+  drive = SetDriveGoal(0.0, kFastDrive, kSecondTurn, kStackingFirstTurn);
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  drive =
+      SetDriveGoal(2.05, kFastDrive, -kSecondTurn * 2.0 - kSecondTurnExtraOnSecond, kSlowSecondDriveTurn);
+  WaitUntilNear(1.5);
+
+  if (!intake_queue.goal.MakeWithBuilder().movement(0.0).claw_closed(false)
+          .Send()) {
+    LOG(ERROR, "Sending intake goal failed.\n");
+  }
+
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  drive = SetDriveGoal(0.0, kFastDrive, kSecondTurn + kSecondTurnExtraOnSecond, kStackingFirstTurn);
+
+  LiftTote(0.18);
+
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  drive = SetDriveGoal(0.3, kFastDrive, -1.7, kFinalDriveTurn);
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  if (!intake_queue.goal.MakeWithBuilder().movement(0.0).claw_closed(false)
+          .Send()) {
+    LOG(ERROR, "Sending intake goal failed.\n");
+  }
+
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+  drive = SetDriveGoal(2.95, kLastDrive, 0.0, kFinalDriveTurn);
+
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  SetElevatorHeight(0.03, kElevatorProfile, true, true);
+  WaitForElevator();
+  if (ShouldExitAuto()) return;
+
+  drive = SetDriveGoal(-2.25, kFastDrive, 0.0, kFinalDriveTurn);
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  drive = SetDriveGoal(0.0, kFastDrive, 1.80, kFinalDriveTurn);
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  if (!intake_queue.goal.MakeWithBuilder().movement(10.0).claw_closed(true)
+          .Send()) {
+    LOG(ERROR, "Sending intake goal failed.\n");
+  }
+  SetElevatorHeight(0.03, kElevatorProfile, false, true);
+
+  drive = SetDriveGoal(1.0, kCanPickupDrive, 0.0, kFinalDriveTurn);
+  WaitUntilDoneOrCanceled(::std::move(drive));
+  if (ShouldExitAuto()) return;
+
+  SetElevatorHeight(0.03, kElevatorProfile, true, true);
+
+  while (true) {
+    elevator_queue.status.FetchAnother();
+    if (!elevator_queue.status.get()) {
+      LOG(ERROR, "Got no elevator status packet.\n");
+    }
+    if (ShouldExitAuto()) return;
+    if (elevator_queue.status->has_tote) {
+      LOG(INFO, "Got the tote!\n");
+      break;
+    }
+    if ((::aos::time::Time::Now() - start_time) > time::Time::InSeconds(15.0)) {
+      LOG(INFO, "Out of time\n");
+      break;
+    }
+  }
+
+  ::aos::time::Time end_time = ::aos::time::Time::Now();
+  LOG(INFO, "Ended auto with %f to spare\n",
+      (time::Time::InSeconds(15.0) - (end_time - start_time)).ToSeconds());
+  if (!intake_queue.goal.MakeWithBuilder().movement(0.0).claw_closed(true)
+          .Send()) {
+    LOG(ERROR, "Sending intake goal failed.\n");
+  }
+}
+
+void HandleAuto() {
+  ::aos::time::Time start_time = ::aos::time::Time::Now();
+  LOG(INFO, "Starting auto mode at %f\n", start_time.ToSeconds());
+
+  // TODO(comran): Add various options for different autos down below.
+  //CanGrabberAuto();
+  TripleCanAuto();
+}
+
+}  // namespace autonomous
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/autonomous/auto.h b/y2015_bot3/autonomous/auto.h
new file mode 100644
index 0000000..bbc5d32
--- /dev/null
+++ b/y2015_bot3/autonomous/auto.h
@@ -0,0 +1,12 @@
+#ifndef Y2015_BOT3_AUTONOMOUS_AUTO_H_
+#define Y2015_BOT3_AUTONOMOUS_AUTO_H_
+
+namespace y2015_bot3 {
+namespace autonomous {
+
+void HandleAuto();
+
+}  // namespace autonomous
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_AUTONOMOUS_AUTO_H_
diff --git a/y2015_bot3/autonomous/auto.q b/y2015_bot3/autonomous/auto.q
new file mode 100644
index 0000000..2fbf41b
--- /dev/null
+++ b/y2015_bot3/autonomous/auto.q
@@ -0,0 +1,15 @@
+package y2015_bot3.autonomous;
+
+message AutoControl {
+  // True if auto mode should be running, false otherwise.
+  bool run_auto;
+};
+queue AutoControl autonomous;
+
+message CanGrabberControl {
+  // Voltage to send out to can grabbers.
+  double can_grabber_voltage;
+  // Can grabbers fired
+  bool can_grabbers;
+};
+queue CanGrabberControl can_grabber_control;
diff --git a/y2015_bot3/autonomous/auto_main.cc b/y2015_bot3/autonomous/auto_main.cc
new file mode 100644
index 0000000..1556561
--- /dev/null
+++ b/y2015_bot3/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 "y2015_bot3/autonomous/auto.q.h"
+#include "y2015_bot3/autonomous/auto.h"
+
+using ::aos::time::Time;
+
+int main(int /*argc*/, char * /*argv*/[]) {
+  ::aos::Init();
+
+  LOG(INFO, "Auto main started\n");
+  ::y2015_bot3::autonomous::autonomous.FetchLatest();
+  while (!::y2015_bot3::autonomous::autonomous.get()) {
+    ::y2015_bot3::autonomous::autonomous.FetchNextBlocking();
+    LOG(INFO, "Got another auto packet\n");
+  }
+
+  while (true) {
+    while (!::y2015_bot3::autonomous::autonomous->run_auto) {
+      ::y2015_bot3::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();
+    ::y2015_bot3::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 (::y2015_bot3::autonomous::autonomous->run_auto) {
+      ::y2015_bot3::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/y2015_bot3/autonomous/autonomous.gyp b/y2015_bot3/autonomous/autonomous.gyp
new file mode 100644
index 0000000..11dd524
--- /dev/null
+++ b/y2015_bot3/autonomous/autonomous.gyp
@@ -0,0 +1,49 @@
+{
+  'targets': [
+    {
+      'target_name': 'auto_queue',
+      'type': 'static_library',
+      'sources': ['auto.q'],
+      'variables': {
+        'header_path': 'bot3/autonomous',
+      },
+      'includes': ['../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'auto_lib',
+      'type': 'static_library',
+      'sources': [
+        'auto.cc',
+      ],
+      'dependencies': [
+        'auto_queue',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(DEPTH)/bot3/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
+        '<(DEPTH)/bot3/control_loops/drivetrain/drivetrain.gyp:drivetrain_lib',
+        '<(DEPTH)/bot3/actors/actors.gyp:drivetrain_action_lib',
+        '<(DEPTH)/bot3/control_loops/elevator/elevator.gyp:elevator_queue',
+        '<(DEPTH)/bot3/control_loops/intake/intake.gyp:intake_queue',
+        '<(AOS)/common/common.gyp:time',
+        '<(AOS)/common/util/util.gyp:phased_loop',
+        '<(AOS)/common/util/util.gyp:trapezoid_profile',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+      ],
+    },
+    {
+      'target_name': 'auto_bot3',
+      'type': 'executable',
+      'sources': [
+        'auto_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'auto_queue',
+        'auto_lib',
+      ],
+    },
+  ],
+}
diff --git a/y2015_bot3/bot3.gyp b/y2015_bot3/bot3.gyp
new file mode 100644
index 0000000..1a710d9
--- /dev/null
+++ b/y2015_bot3/bot3.gyp
@@ -0,0 +1,26 @@
+{
+  'targets': [
+    {
+      'target_name': 'joystick_reader_bot3',
+      'type': 'executable',
+      'sources': [
+        'joystick_reader.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/prime/input/input.gyp:joystick_input',
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(AOS)/common/common.gyp:time',
+        '<(AOS)/common/util/util.gyp:log_interval',
+        '<(AOS)/common/actions/actions.gyp:action_lib',
+
+        '<(DEPTH)/frc971/queues/queues.gyp:gyro',
+        '<(DEPTH)/bot3/control_loops/elevator/elevator.gyp:elevator_lib',
+        '<(DEPTH)/bot3/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
+        '<(DEPTH)/bot3/control_loops/elevator/elevator.gyp:elevator_queue',
+        '<(DEPTH)/bot3/control_loops/intake/intake.gyp:intake_queue',
+        '<(DEPTH)/bot3/autonomous/autonomous.gyp:auto_queue',
+      ],
+    },
+  ],
+}
diff --git a/y2015_bot3/control_loops/BUILD b/y2015_bot3/control_loops/BUILD
new file mode 100644
index 0000000..02315af
--- /dev/null
+++ b/y2015_bot3/control_loops/BUILD
@@ -0,0 +1,14 @@
+package(default_visibility = ['//visibility:public'])
+
+cc_library(
+  name = 'position_sensor_sim',
+  srcs = [
+    'position_sensor_sim.cc',
+  ],
+  hdrs = [
+    'position_sensor_sim.h',
+  ],
+  deps = [
+    '//y2015_bot3/control_loops/elevator:elevator_queue',
+  ],
+)
diff --git a/y2015_bot3/control_loops/control_loops.gyp b/y2015_bot3/control_loops/control_loops.gyp
new file mode 100644
index 0000000..0c49272
--- /dev/null
+++ b/y2015_bot3/control_loops/control_loops.gyp
@@ -0,0 +1,12 @@
+{
+  'targets': [
+    {
+      'target_name': 'position_sensor_sim',
+      'type': 'static_library',
+      'sources': ['position_sensor_sim.cc'],
+      'dependencies': [
+        '<(DEPTH)/bot3/control_loops/elevator/elevator.gyp:elevator_queue',
+      ],
+    },
+  ],
+}
diff --git a/y2015_bot3/control_loops/drivetrain/BUILD b/y2015_bot3/control_loops/drivetrain/BUILD
new file mode 100644
index 0000000..ad1ec39
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/BUILD
@@ -0,0 +1,98 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+cc_binary(
+  name = 'replay_drivetrain',
+  srcs = [
+    'replay_drivetrain.cc',
+  ],
+  deps = [
+    ':drivetrain_queue',
+    '//aos/common/controls:replay_control_loop',
+    '//aos/linux_code:init',
+  ],
+)
+
+queue_library(
+  name = 'drivetrain_queue',
+  srcs = [
+    'drivetrain.q',
+  ],
+  deps = [
+    '//aos/common/controls:control_loop_queues',
+  ],
+)
+
+cc_library(
+  name = 'polydrivetrain_plants',
+  srcs = [
+    'polydrivetrain_dog_motor_plant.cc',
+    'drivetrain_dog_motor_plant.cc',
+  ],
+  hdrs = [
+    'polydrivetrain_dog_motor_plant.h',
+    'drivetrain_dog_motor_plant.h',
+  ],
+  deps = [
+    '//frc971/control_loops:state_feedback_loop',
+  ],
+)
+
+cc_library(
+  name = 'drivetrain_lib',
+  srcs = [
+    'drivetrain.cc',
+    'polydrivetrain_cim_plant.cc',
+    'drivetrain_dog_motor_plant.cc',
+    'polydrivetrain_dog_motor_plant.cc',
+  ],
+  hdrs = [
+    'drivetrain.h',
+    'polydrivetrain_cim_plant.h',
+    'drivetrain_dog_motor_plant.h',
+    'polydrivetrain_dog_motor_plant.h',
+  ],
+  deps = [
+    ':drivetrain_queue',
+    '//aos/common/controls:control_loop',
+    '//aos/common/controls:polytope',
+    '//frc971/control_loops:state_feedback_loop',
+    '//frc971/control_loops:coerce_goal',
+    '//frc971/queues:gyro',
+    '//frc971:shifter_hall_effect',
+    '//aos/common/util:log_interval',
+    '//aos/common:math',
+    '//aos/common/logging:queue_logging',
+    '//aos/common/logging:matrix_logging',
+  ],
+)
+
+cc_binary(
+  name = 'drivetrain_lib_test',
+  srcs = [
+    'drivetrain_lib_test.cc',
+  ],
+  deps = [
+    '//third_party/googletest',
+    ':drivetrain_queue',
+    ':drivetrain_lib',
+    '//aos/common/controls:control_loop_test',
+    '//frc971/control_loops:state_feedback_loop',
+    '//frc971/queues:gyro',
+    '//aos/common:queues',
+    '//aos/common/network:team_number',
+  ],
+)
+
+cc_binary(
+  name = 'drivetrain',
+  srcs = [
+    'drivetrain_main.cc',
+  ],
+  deps = [
+    '//aos/linux_code:init',
+    ':drivetrain_lib',
+    ':drivetrain_queue',
+  ],
+)
diff --git a/y2015_bot3/control_loops/drivetrain/drivetrain.cc b/y2015_bot3/control_loops/drivetrain/drivetrain.cc
new file mode 100644
index 0000000..b126ad2
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/drivetrain.cc
@@ -0,0 +1,764 @@
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.h"
+
+#include <stdio.h>
+#include <sched.h>
+#include <cmath>
+#include <memory>
+#include "Eigen/Dense"
+
+#include "aos/common/logging/logging.h"
+#include "aos/common/controls/polytope.h"
+#include "aos/common/commonmath.h"
+#include "aos/common/logging/queue_logging.h"
+#include "aos/common/logging/matrix_logging.h"
+
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/coerce_goal.h"
+#include "y2015_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/queues/gyro.q.h"
+#include "frc971/shifter_hall_effect.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2015_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+
+// A consistent way to mark code that goes away without shifters.
+#define HAVE_SHIFTERS 0
+
+using ::frc971::sensors::gyro_reading;
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+class DrivetrainMotorsSS {
+ public:
+  class LimitedDrivetrainLoop : public StateFeedbackLoop<4, 2, 2> {
+   public:
+    LimitedDrivetrainLoop(StateFeedbackLoop<4, 2, 2> &&loop)
+        : StateFeedbackLoop<4, 2, 2>(::std::move(loop)),
+          U_Poly_((Eigen::Matrix<double, 4, 2>() << 1, 0, -1, 0, 0, 1, 0, -1)
+                      .finished(),
+                  (Eigen::Matrix<double, 4, 1>() << 12.0, 12.0, 12.0, 12.0)
+                      .finished()) {
+      ::aos::controls::HPolytope<0>::Init();
+      T << 1, -1, 1, 1;
+      T_inverse = T.inverse();
+    }
+
+    bool output_was_capped() const { return output_was_capped_; }
+
+   private:
+    virtual void CapU() {
+      const Eigen::Matrix<double, 4, 1> error = R() - X_hat();
+
+      if (::std::abs(U(0, 0)) > 12.0 || ::std::abs(U(1, 0)) > 12.0) {
+        mutable_U() =
+            U() * 12.0 / ::std::max(::std::abs(U(0, 0)), ::std::abs(U(1, 0)));
+        LOG_MATRIX(DEBUG, "U is now", U());
+        // TODO(Austin): Figure out why the polytope stuff wasn't working and
+        // remove this hack.
+        output_was_capped_ = true;
+        return;
+
+        LOG_MATRIX(DEBUG, "U at start", U());
+        LOG_MATRIX(DEBUG, "R at start", R());
+        LOG_MATRIX(DEBUG, "Xhat at start", X_hat());
+
+        Eigen::Matrix<double, 2, 2> position_K;
+        position_K << K(0, 0), K(0, 2), K(1, 0), K(1, 2);
+        Eigen::Matrix<double, 2, 2> velocity_K;
+        velocity_K << K(0, 1), K(0, 3), K(1, 1), K(1, 3);
+
+        Eigen::Matrix<double, 2, 1> position_error;
+        position_error << error(0, 0), error(2, 0);
+        const auto drive_error = T_inverse * position_error;
+        Eigen::Matrix<double, 2, 1> velocity_error;
+        velocity_error << error(1, 0), error(3, 0);
+        LOG_MATRIX(DEBUG, "error", error);
+
+        const auto &poly = U_Poly_;
+        const Eigen::Matrix<double, 4, 2> pos_poly_H =
+            poly.H() * position_K * T;
+        const Eigen::Matrix<double, 4, 1> pos_poly_k =
+            poly.k() - poly.H() * velocity_K * velocity_error;
+        const ::aos::controls::HPolytope<2> pos_poly(pos_poly_H, pos_poly_k);
+
+        Eigen::Matrix<double, 2, 1> adjusted_pos_error;
+        {
+          const auto &P = drive_error;
+
+          Eigen::Matrix<double, 1, 2> L45;
+          L45 << ::aos::sign(P(1, 0)), -::aos::sign(P(0, 0));
+          const double w45 = 0;
+
+          Eigen::Matrix<double, 1, 2> LH;
+          if (::std::abs(P(0, 0)) > ::std::abs(P(1, 0))) {
+            LH << 0, 1;
+          } else {
+            LH << 1, 0;
+          }
+          const double wh = LH.dot(P);
+
+          Eigen::Matrix<double, 2, 2> standard;
+          standard << L45, LH;
+          Eigen::Matrix<double, 2, 1> W;
+          W << w45, wh;
+          const Eigen::Matrix<double, 2, 1> intersection =
+              standard.inverse() * W;
+
+          bool is_inside_h;
+          const auto adjusted_pos_error_h = frc971::control_loops::DoCoerceGoal(
+              pos_poly, LH, wh, drive_error, &is_inside_h);
+          const auto adjusted_pos_error_45 =
+              frc971::control_loops::DoCoerceGoal(pos_poly, L45, w45,
+                                                  intersection, nullptr);
+          if (pos_poly.IsInside(intersection)) {
+            adjusted_pos_error = adjusted_pos_error_h;
+          } else {
+            if (is_inside_h) {
+              if (adjusted_pos_error_h.norm() > adjusted_pos_error_45.norm()) {
+                adjusted_pos_error = adjusted_pos_error_h;
+              } else {
+                adjusted_pos_error = adjusted_pos_error_45;
+              }
+            } else {
+              adjusted_pos_error = adjusted_pos_error_45;
+            }
+          }
+        }
+
+        LOG_MATRIX(DEBUG, "adjusted_pos_error", adjusted_pos_error);
+        mutable_U() =
+            velocity_K * velocity_error + position_K * T * adjusted_pos_error;
+        LOG_MATRIX(DEBUG, "U is now", U());
+      } else {
+        output_was_capped_ = false;
+      }
+    }
+
+    const ::aos::controls::HPolytope<2> U_Poly_;
+    Eigen::Matrix<double, 2, 2> T, T_inverse;
+    bool output_was_capped_ = false;
+    ;
+  };
+
+  DrivetrainMotorsSS()
+      : loop_(new LimitedDrivetrainLoop(
+            ::y2015_bot3::control_loops::MakeDrivetrainLoop())),
+        filtered_offset_(0.0),
+        gyro_(0.0),
+        left_goal_(0.0),
+        right_goal_(0.0),
+        raw_left_(0.0),
+        raw_right_(0.0) {
+    // Low gear on both.
+    loop_->set_controller_index(0);
+  }
+
+  void SetGoal(double left, double left_velocity, double right,
+               double right_velocity) {
+    left_goal_ = left;
+    right_goal_ = right;
+    loop_->mutable_R() << left, left_velocity, right, right_velocity;
+  }
+  void SetRawPosition(double left, double right) {
+    raw_right_ = right;
+    raw_left_ = left;
+    Eigen::Matrix<double, 2, 1> Y;
+    Y << left + filtered_offset_, right - filtered_offset_;
+    loop_->Correct(Y);
+  }
+  void SetPosition(double left, double right, double gyro) {
+    // Decay the offset quickly because this gyro is great.
+    const double offset = (right - left - gyro * kDrivetrainTurnWidth) / 2.0;
+    filtered_offset_ = 0.25 * offset + 0.75 * filtered_offset_;
+    gyro_ = gyro;
+    SetRawPosition(left, right);
+  }
+
+  void SetExternalMotors(double left_voltage, double right_voltage) {
+    loop_->mutable_U() << left_voltage, right_voltage;
+  }
+
+  void Update(bool stop_motors, bool enable_control_loop) {
+    if (enable_control_loop) {
+      loop_->Update(stop_motors);
+    } else {
+      if (stop_motors) {
+        loop_->mutable_U().setZero();
+        loop_->mutable_U_uncapped().setZero();
+      }
+      loop_->UpdateObserver();
+    }
+    ::Eigen::Matrix<double, 4, 1> E = loop_->R() - loop_->X_hat();
+    LOG_MATRIX(DEBUG, "E", E);
+  }
+
+  double GetEstimatedRobotSpeed() const {
+    // lets just call the average of left and right velocities close enough
+    return (loop_->X_hat(1, 0) + loop_->X_hat(3, 0)) / 2;
+  }
+
+  double GetEstimatedLeftEncoder() const { return loop_->X_hat(0, 0); }
+
+  double GetEstimatedRightEncoder() const { return loop_->X_hat(2, 0); }
+
+  bool OutputWasCapped() const { return loop_->output_was_capped(); }
+
+  void SendMotors(DrivetrainQueue::Output *output) const {
+    if (output) {
+      output->left_voltage = loop_->U(0, 0);
+      output->right_voltage = loop_->U(1, 0);
+      output->left_high = false;
+      output->right_high = false;
+    }
+  }
+
+  const LimitedDrivetrainLoop &loop() const { return *loop_; }
+
+ private:
+  ::std::unique_ptr<LimitedDrivetrainLoop> loop_;
+
+  double filtered_offset_;
+  double gyro_;
+  double left_goal_;
+  double right_goal_;
+  double raw_left_;
+  double raw_right_;
+};
+
+class PolyDrivetrain {
+ public:
+  enum Gear { HIGH, LOW, SHIFTING_UP, SHIFTING_DOWN };
+  // Stall Torque in N m
+  static constexpr double kStallTorque = 2.42;
+  // Stall Current in Amps
+  static constexpr double kStallCurrent = 133.0;
+  // Free Speed in RPM. Used number from last year.
+  static constexpr double kFreeSpeed = 4650.0;
+  // Free Current in Amps
+  static constexpr double kFreeCurrent = 2.7;
+  // Moment of inertia of the drivetrain in kg m^2
+  // Just borrowed from last year.
+  static constexpr double J = 10;
+  // Mass of the robot, in kg.
+  static constexpr double m = 68;
+  // Radius of the robot, in meters (from last year).
+  static constexpr double rb = 0.66675 / 2.0;
+  static constexpr double kWheelRadius = 0.0515938;
+  // Resistance of the motor, divided by the number of motors.
+  static constexpr double kR =
+      (12.0 / kStallCurrent / 4 + 0.03) / (0.93 * 0.93);
+  // Motor velocity constant
+  static constexpr double Kv =
+      ((kFreeSpeed / 60.0 * 2.0 * M_PI) / (12.0 - kR * kFreeCurrent));
+  // Torque constant
+  static constexpr double Kt = kStallTorque / kStallCurrent;
+
+  PolyDrivetrain()
+      : U_Poly_((Eigen::Matrix<double, 4, 2>() << /*[[*/ 1, 0 /*]*/,
+                 /*[*/ -1, 0 /*]*/,
+                 /*[*/ 0, 1 /*]*/,
+                 /*[*/ 0, -1 /*]]*/).finished(),
+                (Eigen::Matrix<double, 4, 1>() << /*[[*/ 12 /*]*/,
+                 /*[*/ 12 /*]*/,
+                 /*[*/ 12 /*]*/,
+                 /*[*/ 12 /*]]*/).finished()),
+        loop_(new StateFeedbackLoop<2, 2, 2>(
+            ::y2015_bot3::control_loops::MakeVelocityDrivetrainLoop())),
+        ttrust_(1.1),
+        wheel_(0.0),
+        throttle_(0.0),
+        quickturn_(false),
+        stale_count_(0),
+        position_time_delta_(0.01),
+        left_gear_(LOW),
+        right_gear_(LOW),
+        counter_(0) {
+    last_position_.Zero();
+    position_.Zero();
+  }
+  static bool IsInGear(Gear gear) { return gear == LOW || gear == HIGH; }
+
+  static double MotorSpeed(
+      const frc971::constants::ShifterHallEffect &hall_effect,
+      double shifter_position, double velocity) {
+    // TODO(austin): G_high, G_low and kWheelRadius
+    const double avg_hall_effect =
+        (hall_effect.clear_high + hall_effect.clear_low) / 2.0;
+
+    if (shifter_position > avg_hall_effect) {
+      return velocity / kDrivetrainHighGearRatio / kWheelRadius;
+    } else {
+      return velocity / kDrivetrainLowGearRatio / kWheelRadius;
+    }
+  }
+
+  Gear ComputeGear(const frc971::constants::ShifterHallEffect &hall_effect,
+                   double velocity, Gear current) {
+    const double low_omega = MotorSpeed(hall_effect, 0.0, ::std::abs(velocity));
+    const double high_omega =
+        MotorSpeed(hall_effect, 1.0, ::std::abs(velocity));
+
+    double high_torque = ((12.0 - high_omega / Kv) * Kt / kR);
+    double low_torque = ((12.0 - low_omega / Kv) * Kt / kR);
+    double high_power = high_torque * high_omega;
+    double low_power = low_torque * low_omega;
+
+    // TODO(aschuh): Do this right!
+    if ((current == HIGH || high_power > low_power + 160) &&
+        ::std::abs(velocity) > 0.14) {
+      return HIGH;
+    } else {
+      return LOW;
+    }
+  }
+
+  void SetGoal(double wheel, double throttle, bool quickturn, bool highgear) {
+    const double kWheelNonLinearity = 0.5;
+    // Apply a sin function that's scaled to make it feel better.
+    const double angular_range = M_PI_2 * kWheelNonLinearity;
+
+    quickturn_ = quickturn;
+    wheel_ = sin(angular_range * wheel) / sin(angular_range);
+    wheel_ = sin(angular_range * wheel_) / sin(angular_range);
+    if (!quickturn_) {
+      wheel_ *= 1.5;
+    }
+
+    static const double kThrottleDeadband = 0.05;
+    if (::std::abs(throttle) < kThrottleDeadband) {
+      throttle_ = 0;
+    } else {
+      throttle_ = copysign((::std::abs(throttle) - kThrottleDeadband) /
+                               (1.0 - kThrottleDeadband),
+                           throttle);
+    }
+
+    // TODO(austin): Fix the upshift logic to include states.
+    Gear requested_gear;
+    if (false) {
+      const double current_left_velocity =
+          (position_.left_encoder - last_position_.left_encoder) /
+          position_time_delta_;
+      const double current_right_velocity =
+          (position_.right_encoder - last_position_.right_encoder) /
+          position_time_delta_;
+
+      Gear left_requested = ComputeGear(kDrivetrainLeftShifter,
+                                        current_left_velocity, left_gear_);
+      Gear right_requested = ComputeGear(kDrivetrainRightShifter,
+                                         current_right_velocity, right_gear_);
+      requested_gear =
+          (left_requested == HIGH || right_requested == HIGH) ? HIGH : LOW;
+    } else {
+      requested_gear = highgear ? HIGH : LOW;
+    }
+
+    const Gear shift_up = kDrivetrainClutchTransmission ? HIGH : SHIFTING_UP;
+    const Gear shift_down = kDrivetrainClutchTransmission ? LOW : SHIFTING_DOWN;
+
+    if (left_gear_ != requested_gear) {
+      if (IsInGear(left_gear_)) {
+        if (requested_gear == HIGH) {
+          left_gear_ = shift_up;
+        } else {
+          left_gear_ = shift_down;
+        }
+      } else {
+        if (requested_gear == HIGH && left_gear_ == SHIFTING_DOWN) {
+          left_gear_ = SHIFTING_UP;
+        } else if (requested_gear == LOW && left_gear_ == SHIFTING_UP) {
+          left_gear_ = SHIFTING_DOWN;
+        }
+      }
+    }
+    if (right_gear_ != requested_gear) {
+      if (IsInGear(right_gear_)) {
+        if (requested_gear == HIGH) {
+          right_gear_ = shift_up;
+        } else {
+          right_gear_ = shift_down;
+        }
+      } else {
+        if (requested_gear == HIGH && right_gear_ == SHIFTING_DOWN) {
+          right_gear_ = SHIFTING_UP;
+        } else if (requested_gear == LOW && right_gear_ == SHIFTING_UP) {
+          right_gear_ = SHIFTING_DOWN;
+        }
+      }
+    }
+  }
+  void SetPosition(const DrivetrainQueue::Position *position) {
+    if (position == NULL) {
+      ++stale_count_;
+    } else {
+      last_position_ = position_;
+      position_ = *position;
+      position_time_delta_ = (stale_count_ + 1) * 0.01;
+      stale_count_ = 0;
+    }
+
+#if HAVE_SHIFTERS
+    if (position) {
+      GearLogging gear_logging;
+      // Switch to the correct controller.
+      const double left_middle_shifter_position =
+          (kDrivetrainLeftShifter.clear_high +
+           kDrivetrainLeftShifter.clear_low) /
+          2.0;
+      const double right_middle_shifter_position =
+          (kDrivetrainRightShifter.clear_high +
+           kDrivetrainRightShifter.clear_low) /
+          2.0;
+
+      if (position->left_shifter_position < left_middle_shifter_position ||
+          left_gear_ == LOW) {
+        if (position->right_shifter_position < right_middle_shifter_position ||
+            right_gear_ == LOW) {
+          gear_logging.left_loop_high = false;
+          gear_logging.right_loop_high = false;
+          loop_->set_controller_index(gear_logging.controller_index = 0);
+        } else {
+          gear_logging.left_loop_high = false;
+          gear_logging.right_loop_high = true;
+          loop_->set_controller_index(gear_logging.controller_index = 1);
+        }
+      } else {
+        if (position->right_shifter_position < right_middle_shifter_position ||
+            right_gear_ == LOW) {
+          gear_logging.left_loop_high = true;
+          gear_logging.right_loop_high = false;
+          loop_->set_controller_index(gear_logging.controller_index = 2);
+        } else {
+          gear_logging.left_loop_high = true;
+          gear_logging.right_loop_high = true;
+          loop_->set_controller_index(gear_logging.controller_index = 3);
+        }
+      }
+
+      // TODO(austin): Constants.
+      if (position->left_shifter_position > kDrivetrainLeftShifter.clear_high &&
+          left_gear_ == SHIFTING_UP) {
+        left_gear_ = HIGH;
+      }
+      if (position->left_shifter_position < kDrivetrainLeftShifter.clear_low &&
+          left_gear_ == SHIFTING_DOWN) {
+        left_gear_ = LOW;
+      }
+      if (position->right_shifter_position >
+              kDrivetrainRightShifter.clear_high &&
+          right_gear_ == SHIFTING_UP) {
+        right_gear_ = HIGH;
+      }
+      if (position->right_shifter_position <
+              kDrivetrainRightShifter.clear_low &&
+          right_gear_ == SHIFTING_DOWN) {
+        right_gear_ = LOW;
+      }
+
+      gear_logging.left_state = left_gear_;
+      gear_logging.right_state = right_gear_;
+      LOG_STRUCT(DEBUG, "state", gear_logging);
+    }
+#endif
+  }
+
+  double FilterVelocity(double throttle) {
+    const Eigen::Matrix<double, 2, 2> FF =
+        loop_->B().inverse() *
+        (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
+
+    constexpr int kHighGearController = 3;
+    const Eigen::Matrix<double, 2, 2> FF_high =
+        loop_->controller(kHighGearController).plant.B().inverse() *
+        (Eigen::Matrix<double, 2, 2>::Identity() -
+         loop_->controller(kHighGearController).plant.A());
+
+    ::Eigen::Matrix<double, 1, 2> FF_sum = FF.colwise().sum();
+    int min_FF_sum_index;
+    const double min_FF_sum = FF_sum.minCoeff(&min_FF_sum_index);
+    const double min_K_sum = loop_->K().col(min_FF_sum_index).sum();
+    const double high_min_FF_sum = FF_high.col(0).sum();
+
+    const double adjusted_ff_voltage = ::aos::Clip(
+        throttle * 12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0);
+    return (adjusted_ff_voltage +
+            ttrust_ * min_K_sum * (loop_->X_hat(0, 0) + loop_->X_hat(1, 0)) /
+                2.0) /
+           (ttrust_ * min_K_sum + min_FF_sum);
+  }
+
+  double MaxVelocity() {
+    const Eigen::Matrix<double, 2, 2> FF =
+        loop_->B().inverse() *
+        (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
+
+    constexpr int kHighGearController = 3;
+    const Eigen::Matrix<double, 2, 2> FF_high =
+        loop_->controller(kHighGearController).plant.B().inverse() *
+        (Eigen::Matrix<double, 2, 2>::Identity() -
+         loop_->controller(kHighGearController).plant.A());
+
+    ::Eigen::Matrix<double, 1, 2> FF_sum = FF.colwise().sum();
+    int min_FF_sum_index;
+    const double min_FF_sum = FF_sum.minCoeff(&min_FF_sum_index);
+    // const double min_K_sum = loop_->K().col(min_FF_sum_index).sum();
+    const double high_min_FF_sum = FF_high.col(0).sum();
+
+    const double adjusted_ff_voltage =
+        ::aos::Clip(12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0);
+    return adjusted_ff_voltage / min_FF_sum;
+  }
+
+  void Update() {
+    // TODO(austin): Observer for the current velocity instead of difference
+    // calculations.
+    ++counter_;
+#if HAVE_SHIFTERS
+    const double current_left_velocity =
+        (position_.left_encoder - last_position_.left_encoder) /
+        position_time_delta_;
+    const double current_right_velocity =
+        (position_.right_encoder - last_position_.right_encoder) /
+        position_time_delta_;
+    const double left_motor_speed =
+        MotorSpeed(kDrivetrainLeftShifter, position_.left_shifter_position,
+                   current_left_velocity);
+    const double right_motor_speed =
+        MotorSpeed(kDrivetrainRightShifter, position_.right_shifter_position,
+                   current_right_velocity);
+
+    {
+      CIMLogging logging;
+
+      // Reset the CIM model to the current conditions to be ready for when we
+      // shift.
+      if (IsInGear(left_gear_)) {
+        logging.left_in_gear = true;
+      } else {
+        logging.left_in_gear = false;
+      }
+      logging.left_motor_speed = left_motor_speed;
+      logging.left_velocity = current_left_velocity;
+      if (IsInGear(right_gear_)) {
+        logging.right_in_gear = true;
+      } else {
+        logging.right_in_gear = false;
+      }
+      logging.right_motor_speed = right_motor_speed;
+      logging.right_velocity = current_right_velocity;
+
+      LOG_STRUCT(DEBUG, "currently", logging);
+    }
+#endif
+
+#if HAVE_SHIFTERS
+    if (IsInGear(left_gear_) && IsInGear(right_gear_)) {
+#else
+    {
+#endif
+      // FF * X = U (steady state)
+      const Eigen::Matrix<double, 2, 2> FF =
+          loop_->B().inverse() *
+          (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
+
+      // Invert the plant to figure out how the velocity filter would have to
+      // work
+      // out in order to filter out the forwards negative inertia.
+      // This math assumes that the left and right power and velocity are
+      // equals,
+      // and that the plant is the same on the left and right.
+      const double fvel = FilterVelocity(throttle_);
+
+      const double sign_svel = wheel_ * ((fvel > 0.0) ? 1.0 : -1.0);
+      double steering_velocity;
+      if (quickturn_) {
+        steering_velocity = wheel_ * MaxVelocity();
+      } else {
+        steering_velocity = ::std::abs(fvel) * wheel_;
+      }
+      const double left_velocity = fvel - steering_velocity;
+      const double right_velocity = fvel + steering_velocity;
+      LOG(DEBUG, "l=%f r=%f\n", left_velocity, right_velocity);
+
+      // Integrate velocity to get the position.
+      // This position is used to get integral control.
+      loop_->mutable_R() << left_velocity, right_velocity;
+
+      if (!quickturn_) {
+        // K * R = w
+        Eigen::Matrix<double, 1, 2> equality_k;
+        equality_k << 1 + sign_svel, -(1 - sign_svel);
+        const double equality_w = 0.0;
+
+        // Construct a constraint on R by manipulating the constraint on U
+        ::aos::controls::HPolytope<2> R_poly = ::aos::controls::HPolytope<2>(
+            U_Poly_.H() * (loop_->K() + FF),
+            U_Poly_.k() + U_Poly_.H() * loop_->K() * loop_->X_hat());
+
+        // Limit R back inside the box.
+        loop_->mutable_R() = frc971::control_loops::CoerceGoal(
+            R_poly, equality_k, equality_w, loop_->R());
+      }
+
+      const Eigen::Matrix<double, 2, 1> FF_volts = FF * loop_->R();
+      const Eigen::Matrix<double, 2, 1> U_ideal =
+          loop_->K() * (loop_->R() - loop_->X_hat()) + FF_volts;
+
+      for (int i = 0; i < 2; i++) {
+        loop_->mutable_U()[i] = ::aos::Clip(U_ideal[i], -12, 12);
+      }
+
+      // TODO(austin): Model this better.
+      // TODO(austin): Feed back?
+      loop_->mutable_X_hat() =
+          loop_->A() * loop_->X_hat() + loop_->B() * loop_->U();
+#if HAVE_SHIFTERS
+    } else {
+      // Any motor is not in gear.  Speed match.
+      ::Eigen::Matrix<double, 1, 1> R_left;
+      ::Eigen::Matrix<double, 1, 1> R_right;
+      R_left(0, 0) = left_motor_speed;
+      R_right(0, 0) = right_motor_speed;
+
+      const double wiggle =
+          (static_cast<double>((counter_ % 20) / 10) - 0.5) * 5.0;
+
+      loop_->mutable_U(0, 0) =
+          ::aos::Clip((R_left / Kv)(0, 0) + (IsInGear(left_gear_) ? 0 : wiggle),
+                      -12.0, 12.0);
+      loop_->mutable_U(1, 0) = ::aos::Clip(
+          (R_right / Kv)(0, 0) + (IsInGear(right_gear_) ? 0 : wiggle), -12.0,
+          12.0);
+      loop_->mutable_U() *= 12.0 / ::aos::robot_state->voltage_battery;
+#endif
+    }
+  }
+
+  void SendMotors(DrivetrainQueue::Output *output) {
+    if (output != NULL) {
+      output->left_voltage = loop_->U(0, 0);
+      output->right_voltage = loop_->U(1, 0);
+      output->left_high = left_gear_ == HIGH || left_gear_ == SHIFTING_UP;
+      output->right_high = right_gear_ == HIGH || right_gear_ == SHIFTING_UP;
+    }
+  }
+
+ private:
+  const ::aos::controls::HPolytope<2> U_Poly_;
+
+  ::std::unique_ptr<StateFeedbackLoop<2, 2, 2>> loop_;
+
+  const double ttrust_;
+  double wheel_;
+  double throttle_;
+  bool quickturn_;
+  int stale_count_;
+  double position_time_delta_;
+  Gear left_gear_;
+  Gear right_gear_;
+  DrivetrainQueue::Position last_position_;
+  DrivetrainQueue::Position position_;
+  int counter_;
+};
+constexpr double PolyDrivetrain::kStallTorque;
+constexpr double PolyDrivetrain::kStallCurrent;
+constexpr double PolyDrivetrain::kFreeSpeed;
+constexpr double PolyDrivetrain::kFreeCurrent;
+constexpr double PolyDrivetrain::J;
+constexpr double PolyDrivetrain::m;
+constexpr double PolyDrivetrain::rb;
+constexpr double PolyDrivetrain::kWheelRadius;
+constexpr double PolyDrivetrain::kR;
+constexpr double PolyDrivetrain::Kv;
+constexpr double PolyDrivetrain::Kt;
+
+void DrivetrainLoop::RunIteration(const DrivetrainQueue::Goal *goal,
+                                  const DrivetrainQueue::Position *position,
+                                  DrivetrainQueue::Output *output,
+                                  DrivetrainQueue::Status *status) {
+  // TODO(aschuh): These should be members of the class.
+  static DrivetrainMotorsSS dt_closedloop;
+  static PolyDrivetrain dt_openloop;
+
+  bool bad_pos = false;
+  if (position == nullptr) {
+    LOG_INTERVAL(no_position_);
+    bad_pos = true;
+  }
+  no_position_.Print();
+
+  bool control_loop_driving = false;
+  if (goal) {
+    double wheel = goal->steering;
+    double throttle = goal->throttle;
+    bool quickturn = goal->quickturn;
+#if HAVE_SHIFTERS
+    bool highgear = goal->highgear;
+#endif
+
+    control_loop_driving = goal->control_loop_driving;
+    double left_goal = goal->left_goal;
+    double right_goal = goal->right_goal;
+
+    dt_closedloop.SetGoal(left_goal, goal->left_velocity_goal, right_goal,
+                          goal->right_velocity_goal);
+#if HAVE_SHIFTERS
+    dt_openloop.SetGoal(wheel, throttle, quickturn, highgear);
+#else
+    dt_openloop.SetGoal(wheel, throttle, quickturn, false);
+#endif
+  }
+
+  if (!bad_pos) {
+    const double left_encoder = position->left_encoder;
+    const double right_encoder = position->right_encoder;
+    if (gyro_reading.FetchLatest()) {
+      LOG_STRUCT(DEBUG, "using", *gyro_reading.get());
+      dt_closedloop.SetPosition(left_encoder, right_encoder,
+                                gyro_reading->angle);
+    } else {
+      dt_closedloop.SetRawPosition(left_encoder, right_encoder);
+    }
+  }
+  dt_openloop.SetPosition(position);
+  dt_openloop.Update();
+
+  if (control_loop_driving) {
+    dt_closedloop.Update(output == NULL, true);
+    dt_closedloop.SendMotors(output);
+  } else {
+    dt_openloop.SendMotors(output);
+    if (output) {
+      dt_closedloop.SetExternalMotors(output->left_voltage,
+                                      output->right_voltage);
+    }
+    dt_closedloop.Update(output == NULL, false);
+  }
+
+  // set the output status of the control loop state
+  if (status) {
+    bool done = false;
+    if (goal) {
+      done = ((::std::abs(goal->left_goal -
+                          dt_closedloop.GetEstimatedLeftEncoder()) <
+               kDrivetrainDoneDistance) &&
+              (::std::abs(goal->right_goal -
+                          dt_closedloop.GetEstimatedRightEncoder()) <
+               kDrivetrainDoneDistance));
+    }
+    status->is_done = done;
+    status->robot_speed = dt_closedloop.GetEstimatedRobotSpeed();
+    status->filtered_left_position = dt_closedloop.GetEstimatedLeftEncoder();
+    status->filtered_right_position = dt_closedloop.GetEstimatedRightEncoder();
+
+    status->filtered_left_velocity = dt_closedloop.loop().X_hat(1, 0);
+    status->filtered_right_velocity = dt_closedloop.loop().X_hat(3, 0);
+    status->output_was_capped = dt_closedloop.OutputWasCapped();
+    status->uncapped_left_voltage = dt_closedloop.loop().U_uncapped(0, 0);
+    status->uncapped_right_voltage = dt_closedloop.loop().U_uncapped(1, 0);
+  }
+}
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/drivetrain/drivetrain.gyp b/y2015_bot3/control_loops/drivetrain/drivetrain.gyp
new file mode 100644
index 0000000..92678d1
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/drivetrain.gyp
@@ -0,0 +1,105 @@
+{
+  'targets': [
+    {
+      'target_name': 'replay_drivetrain_bot3',
+      'type': 'executable',
+      'variables': {
+        'no_rsync': 1,
+      },
+      'sources': [
+        'replay_drivetrain.cc',
+      ],
+      'dependencies': [
+        'drivetrain_queue',
+        '<(AOS)/common/controls/controls.gyp:replay_control_loop',
+        '<(AOS)/linux_code/linux_code.gyp:init',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_queue',
+      'type': 'static_library',
+      'sources': ['drivetrain.q'],
+      'variables': {
+        'header_path': 'bot3/control_loops/drivetrain',
+      },
+      'dependencies': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+      ],
+      'includes': ['../../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'polydrivetrain_plants',
+      'type': 'static_library',
+      'sources': [
+        'polydrivetrain_dog_motor_plant.cc',
+        'drivetrain_dog_motor_plant.cc',
+      ],
+      'dependencies': [
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+      'export_dependent_settings': [
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_lib',
+      'type': 'static_library',
+      'sources': [
+        'drivetrain.cc',
+        'polydrivetrain_cim_plant.cc',
+        'drivetrain_dog_motor_plant.cc',
+        'polydrivetrain_dog_motor_plant.cc',
+      ],
+      'dependencies': [
+        'drivetrain_queue',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(AOS)/common/controls/controls.gyp:polytope',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
+        '<(DEPTH)/frc971/queues/queues.gyp:gyro',
+        '<(AOS)/common/util/util.gyp:log_interval',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+        '<(AOS)/common/logging/logging.gyp:matrix_logging',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:polytope',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        'drivetrain_queue',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_lib_test_bot3',
+      'type': 'executable',
+      'sources': [
+        'drivetrain_lib_test.cc',
+      ],
+      'dependencies': [
+        '<(EXTERNALS):gtest',
+        'drivetrain_queue',
+        'drivetrain_lib',
+        '<(AOS)/common/controls/controls.gyp:control_loop_test',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(DEPTH)/frc971/queues/queues.gyp:gyro',
+        '<(AOS)/common/common.gyp:queues',
+        '<(AOS)/common/network/network.gyp:team_number',
+      ],
+    },
+    {
+      'target_name': 'drivetrain_bot3',
+      'type': 'executable',
+      'sources': [
+        'drivetrain_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'drivetrain_lib',
+        'drivetrain_queue',
+      ],
+    },
+  ],
+}
diff --git a/y2015_bot3/control_loops/drivetrain/drivetrain.h b/y2015_bot3/control_loops/drivetrain/drivetrain.h
new file mode 100644
index 0000000..b89c1dd
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/drivetrain.h
@@ -0,0 +1,60 @@
+#ifndef Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_H_
+#define Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_H_
+
+#include "Eigen/Dense"
+
+#include "aos/common/controls/polytope.h"
+#include "aos/common/controls/control_loop.h"
+#include "aos/common/controls/polytope.h"
+#include "aos/common/util/log_interval.h"
+
+#include "frc971/shifter_hall_effect.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.q.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+// Constants
+// TODO(comran): Get actual constants.
+constexpr double kDrivetrainTurnWidth = 0.63;
+constexpr double kDrivetrainDoneDistance = 0.02;
+constexpr double kDrivetrainEncoderRatio = 18.0 / 44.0;
+constexpr double kDrivetrainHighGearRatio =
+    kDrivetrainEncoderRatio * 18.0 / 60.0;
+constexpr double kDrivetrainLowGearRatio = kDrivetrainHighGearRatio;
+const bool kDrivetrainClutchTransmission = false;
+const ::frc971::constants::ShifterHallEffect kDrivetrainRightShifter{
+    555, 657, 660, 560, 0.2, 0.7};
+const ::frc971::constants::ShifterHallEffect kDrivetrainLeftShifter{
+    555, 660, 644, 552, 0.2, 0.7};
+// End constants
+
+class DrivetrainLoop
+    : public aos::controls::ControlLoop<control_loops::DrivetrainQueue> {
+ public:
+  // Constructs a control loop which can take a Drivetrain or defaults to the
+  // drivetrain at y2015_bot3::control_loops::drivetrain
+  explicit DrivetrainLoop(control_loops::DrivetrainQueue *my_drivetrain =
+                              &control_loops::drivetrain_queue)
+      : aos::controls::ControlLoop<control_loops::DrivetrainQueue>(
+            my_drivetrain) {
+    ::aos::controls::HPolytope<0>::Init();
+  }
+
+ protected:
+  // Executes one cycle of the control loop.
+  virtual void RunIteration(
+      const control_loops::DrivetrainQueue::Goal *goal,
+      const control_loops::DrivetrainQueue::Position *position,
+      control_loops::DrivetrainQueue::Output *output,
+      control_loops::DrivetrainQueue::Status *status);
+
+  typedef ::aos::util::SimpleLogInterval SimpleLogInterval;
+  SimpleLogInterval no_position_ = SimpleLogInterval(
+      ::aos::time::Time::InSeconds(0.25), WARNING, "no position");
+};
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/y2015_bot3/control_loops/drivetrain/drivetrain.q b/y2015_bot3/control_loops/drivetrain/drivetrain.q
new file mode 100644
index 0000000..5bbbb25
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/drivetrain.q
@@ -0,0 +1,71 @@
+package y2015_bot3.control_loops;
+
+import "aos/common/controls/control_loops.q";
+
+struct GearLogging {
+  int8_t controller_index;
+  bool left_loop_high;
+  bool right_loop_high;
+  int8_t left_state;
+  int8_t right_state;
+};
+
+struct CIMLogging {
+  bool left_in_gear;
+  bool right_in_gear;
+  double left_motor_speed;
+  double right_motor_speed;
+  double left_velocity;
+  double right_velocity;
+};
+
+queue_group DrivetrainQueue {
+  implements aos.control_loops.ControlLoop;
+
+  message Goal {
+    double steering;
+    double throttle;
+    //bool highgear;
+    bool quickturn;
+    bool control_loop_driving;
+    double left_goal;
+    double left_velocity_goal;
+    double right_goal;
+    double right_velocity_goal;
+  };
+
+  message Position {
+    double left_encoder;
+    double right_encoder;
+    //double left_shifter_position;
+    //double right_shifter_position;
+  };
+
+  message Output {
+    double left_voltage;
+    double right_voltage;
+    bool left_high;
+    bool right_high;
+  };
+
+  message Status {
+    double robot_speed;
+    double filtered_left_position;
+    double filtered_right_position;
+    double filtered_left_velocity;
+    double filtered_right_velocity;
+
+    double uncapped_left_voltage;
+    double uncapped_right_voltage;
+    bool output_was_capped;
+
+    bool is_done;
+  };
+
+  queue Goal goal;
+  queue Position position;
+  queue Output output;
+  queue Status status;
+};
+
+queue_group DrivetrainQueue drivetrain_queue;
diff --git a/y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.cc b/y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
new file mode 100644
index 0000000..25e728a
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
@@ -0,0 +1,133 @@
+#include "y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowLowPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.0048650405221, 0.0, 4.30452834469e-05, 0.0, 0.946557122299, 0.0, 0.0169038781857, 0.0, 4.30452834469e-05, 1.0, 0.0048650405221, 0.0, 0.0169038781857, 0.0, 0.946557122299;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 3.44936607298e-05, -1.10017423477e-05, 0.0136592147549, -0.00432038303814, -1.10017423477e-05, 3.44936607298e-05, -0.00432038303814, 0.0136592147549;
+  Eigen::Matrix<double, 2, 4> C;
+  C << 1, 0, 0, 0, 0, 0, 1, 0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0, 0, 0, 0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowHighPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.0048650405221, 0.0, 4.30452834469e-05, 0.0, 0.946557122299, 0.0, 0.0169038781857, 0.0, 4.30452834469e-05, 1.0, 0.0048650405221, 0.0, 0.0169038781857, 0.0, 0.946557122299;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 3.44936607298e-05, -1.10017423477e-05, 0.0136592147549, -0.00432038303814, -1.10017423477e-05, 3.44936607298e-05, -0.00432038303814, 0.0136592147549;
+  Eigen::Matrix<double, 2, 4> C;
+  C << 1, 0, 0, 0, 0, 0, 1, 0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0, 0, 0, 0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighLowPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.0048650405221, 0.0, 4.30452834469e-05, 0.0, 0.946557122299, 0.0, 0.0169038781857, 0.0, 4.30452834469e-05, 1.0, 0.0048650405221, 0.0, 0.0169038781857, 0.0, 0.946557122299;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 3.44936607298e-05, -1.10017423477e-05, 0.0136592147549, -0.00432038303814, -1.10017423477e-05, 3.44936607298e-05, -0.00432038303814, 0.0136592147549;
+  Eigen::Matrix<double, 2, 4> C;
+  C << 1, 0, 0, 0, 0, 0, 1, 0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0, 0, 0, 0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighHighPlantCoefficients() {
+  Eigen::Matrix<double, 4, 4> A;
+  A << 1.0, 0.0048650405221, 0.0, 4.30452834469e-05, 0.0, 0.946557122299, 0.0, 0.0169038781857, 0.0, 4.30452834469e-05, 1.0, 0.0048650405221, 0.0, 0.0169038781857, 0.0, 0.946557122299;
+  Eigen::Matrix<double, 4, 2> B;
+  B << 3.44936607298e-05, -1.10017423477e-05, 0.0136592147549, -0.00432038303814, -1.10017423477e-05, 3.44936607298e-05, -0.00432038303814, 0.0136592147549;
+  Eigen::Matrix<double, 2, 4> C;
+  C << 1, 0, 0, 0, 0, 0, 1, 0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0, 0, 0, 0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowLowController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.2465571223, 0.0169038781857, 72.6644245424, 3.50262182277, 0.0169038781857, 1.2465571223, 3.50262182277, 72.6644245424;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 156.707528421, 12.1845100817, 3.29243225373, 1.51015663937, 3.29243225372, 1.51015663937, 156.707528421, 12.1845100817;
+  Eigen::Matrix<double, 4, 4> A_inv;
+  A_inv << 1.0, -0.00514054935697, 0.0, 4.63257162805e-05, 0.0, 1.0567973091, 0.0, -0.01887257785, 0.0, 4.63257162805e-05, 1.0, -0.00514054935697, 0.0, -0.01887257785, 0.0, 1.0567973091;
+  return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainLowLowPlantCoefficients());
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowHighController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.2465571223, 0.0169038781857, 72.6644245424, 3.50262182277, 0.0169038781857, 1.2465571223, 3.50262182277, 72.6644245424;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 156.707528421, 12.1845100817, 3.29243225373, 1.51015663937, 3.29243225372, 1.51015663937, 156.707528421, 12.1845100817;
+  Eigen::Matrix<double, 4, 4> A_inv;
+  A_inv << 1.0, -0.00514054935697, 0.0, 4.63257162805e-05, 0.0, 1.0567973091, 0.0, -0.01887257785, 0.0, 4.63257162805e-05, 1.0, -0.00514054935697, 0.0, -0.01887257785, 0.0, 1.0567973091;
+  return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainLowHighPlantCoefficients());
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighLowController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.2465571223, 0.0169038781857, 72.6644245424, 3.50262182277, 0.0169038781857, 1.2465571223, 3.50262182277, 72.6644245424;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 156.707528421, 12.1845100817, 3.29243225373, 1.51015663937, 3.29243225372, 1.51015663937, 156.707528421, 12.1845100817;
+  Eigen::Matrix<double, 4, 4> A_inv;
+  A_inv << 1.0, -0.00514054935697, 0.0, 4.63257162805e-05, 0.0, 1.0567973091, 0.0, -0.01887257785, 0.0, 4.63257162805e-05, 1.0, -0.00514054935697, 0.0, -0.01887257785, 0.0, 1.0567973091;
+  return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainHighLowPlantCoefficients());
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighHighController() {
+  Eigen::Matrix<double, 4, 2> L;
+  L << 1.2465571223, 0.0169038781857, 72.6644245424, 3.50262182277, 0.0169038781857, 1.2465571223, 3.50262182277, 72.6644245424;
+  Eigen::Matrix<double, 2, 4> K;
+  K << 156.707528421, 12.1845100817, 3.29243225373, 1.51015663937, 3.29243225372, 1.51015663937, 156.707528421, 12.1845100817;
+  Eigen::Matrix<double, 4, 4> A_inv;
+  A_inv << 1.0, -0.00514054935697, 0.0, 4.63257162805e-05, 0.0, 1.0567973091, 0.0, -0.01887257785, 0.0, 4.63257162805e-05, 1.0, -0.00514054935697, 0.0, -0.01887257785, 0.0, 1.0567973091;
+  return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainHighHighPlantCoefficients());
+}
+
+StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>> plants(4);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainLowLowPlantCoefficients()));
+  plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainLowHighPlantCoefficients()));
+  plants[2] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainHighLowPlantCoefficients()));
+  plants[3] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainHighHighPlantCoefficients()));
+  return StateFeedbackPlant<4, 2, 2>(&plants);
+}
+
+StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<4, 2, 2>>> controllers(4);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainLowLowController()));
+  controllers[1] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainLowHighController()));
+  controllers[2] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainHighLowController()));
+  controllers[3] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainHighHighController()));
+  return StateFeedbackLoop<4, 2, 2>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h b/y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h
new file mode 100644
index 0000000..041e06e
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h
@@ -0,0 +1,32 @@
+#ifndef Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
+#define Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowLowPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowLowController();
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowHighPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowHighController();
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighLowPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighLowController();
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighHighPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighHighController();
+
+StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant();
+
+StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop();
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/y2015_bot3/control_loops/drivetrain/drivetrain_lib_test.cc b/y2015_bot3/control_loops/drivetrain/drivetrain_lib_test.cc
new file mode 100644
index 0000000..8848535
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -0,0 +1,296 @@
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/network/team_number.h"
+#include "aos/common/queue_testutils.h"
+#include "aos/common/controls/polytope.h"
+#include "aos/common/controls/control_loop_test.h"
+
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.q.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/coerce_goal.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "frc971/queues/gyro.q.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+namespace testing {
+
+class Environment : public ::testing::Environment {
+ public:
+  virtual ~Environment() {}
+  // how to set up the environment.
+  virtual void SetUp() {
+    aos::controls::HPolytope<0>::Init();
+  }
+};
+::testing::Environment* const holder_env =
+  ::testing::AddGlobalTestEnvironment(new Environment);
+
+class TeamNumberEnvironment : public ::testing::Environment {
+ public:
+  // Override this to define how to set up the environment.
+  virtual void SetUp() { aos::network::OverrideTeamNumber(971); }
+};
+
+::testing::Environment* const team_number_env =
+    ::testing::AddGlobalTestEnvironment(new TeamNumberEnvironment);
+
+// Class which simulates the drivetrain and sends out queue messages containing
+// the position.
+class DrivetrainSimulation {
+ public:
+  // Constructs a motor simulation.
+  // TODO(aschuh) Do we want to test the clutch one too?
+  DrivetrainSimulation()
+      : drivetrain_plant_(
+            new StateFeedbackPlant<4, 2, 2>(MakeDrivetrainPlant())),
+        my_drivetrain_queue_(".y2015_bot3.control_loops.drivetrain", 0x8a8dde77,
+                             ".y2015_bot3.control_loops.drivetrain.goal",
+                             ".y2015_bot3.control_loops.drivetrain.position",
+                             ".y2015_bot3.control_loops.drivetrain.output",
+                             ".y2015_bot3.control_loops.drivetrain.status") {
+    Reinitialize();
+  }
+
+  // Resets the plant.
+  void Reinitialize() {
+    drivetrain_plant_->mutable_X(0, 0) = 0.0;
+    drivetrain_plant_->mutable_X(1, 0) = 0.0;
+    drivetrain_plant_->mutable_Y() =
+        drivetrain_plant_->C() * drivetrain_plant_->X();
+    last_left_position_ = drivetrain_plant_->Y(0, 0);
+    last_right_position_ = drivetrain_plant_->Y(1, 0);
+  }
+
+  // Returns the position of the drivetrain.
+  double GetLeftPosition() const { return drivetrain_plant_->Y(0, 0); }
+  double GetRightPosition() const { return drivetrain_plant_->Y(1, 0); }
+
+  // Sends out the position queue messages.
+  void SendPositionMessage() {
+    const double left_encoder = GetLeftPosition();
+    const double right_encoder = GetRightPosition();
+
+    ::aos::ScopedMessagePtr<control_loops::DrivetrainQueue::Position> position =
+        my_drivetrain_queue_.position.MakeMessage();
+    position->left_encoder = left_encoder;
+    position->right_encoder = right_encoder;
+    position.Send();
+  }
+
+  // Simulates the drivetrain moving for one timestep.
+  void Simulate() {
+    last_left_position_ = drivetrain_plant_->Y(0, 0);
+    last_right_position_ = drivetrain_plant_->Y(1, 0);
+    EXPECT_TRUE(my_drivetrain_queue_.output.FetchLatest());
+    drivetrain_plant_->mutable_U() << my_drivetrain_queue_.output->left_voltage,
+        my_drivetrain_queue_.output->right_voltage;
+    drivetrain_plant_->Update();
+  }
+
+  ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> drivetrain_plant_;
+ private:
+  DrivetrainQueue my_drivetrain_queue_;
+  double last_left_position_;
+  double last_right_position_;
+};
+
+class DrivetrainTest : public ::aos::testing::ControlLoopTest {
+ protected:
+  // Create a new instance of the test queue so that it invalidates the queue
+  // that it points to.  Otherwise, we will have a pointer to shared memory that
+  // is no longer valid.
+  DrivetrainQueue my_drivetrain_queue_;
+
+  // Create a loop and simulation plant.
+  DrivetrainLoop drivetrain_motor_;
+  DrivetrainSimulation drivetrain_motor_plant_;
+
+  DrivetrainTest()
+      : my_drivetrain_queue_(".y2015_bot3.control_loops.drivetrain", 0x8a8dde77,
+                             ".y2015_bot3.control_loops.drivetrain.goal",
+                             ".y2015_bot3.control_loops.drivetrain.position",
+                             ".y2015_bot3.control_loops.drivetrain.output",
+                             ".y2015_bot3.control_loops.drivetrain.status"),
+        drivetrain_motor_(&my_drivetrain_queue_),
+        drivetrain_motor_plant_() {
+    ::frc971::sensors::gyro_reading.Clear();
+  }
+
+  void VerifyNearGoal() {
+    my_drivetrain_queue_.goal.FetchLatest();
+    my_drivetrain_queue_.position.FetchLatest();
+    EXPECT_NEAR(my_drivetrain_queue_.goal->left_goal,
+                drivetrain_motor_plant_.GetLeftPosition(),
+                1e-2);
+    EXPECT_NEAR(my_drivetrain_queue_.goal->right_goal,
+                drivetrain_motor_plant_.GetRightPosition(),
+                1e-2);
+  }
+
+  virtual ~DrivetrainTest() {
+    ::frc971::sensors::gyro_reading.Clear();
+  }
+};
+
+// Tests that the drivetrain converges on a goal.
+TEST_F(DrivetrainTest, ConvergesCorrectly) {
+  my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
+      .left_goal(-1.0)
+      .right_goal(1.0).Send();
+  for (int i = 0; i < 200; ++i) {
+    drivetrain_motor_plant_.SendPositionMessage();
+    drivetrain_motor_.Iterate();
+    drivetrain_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+  VerifyNearGoal();
+}
+
+// Tests that it survives disabling.
+TEST_F(DrivetrainTest, SurvivesDisabling) {
+  my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
+      .left_goal(-1.0)
+      .right_goal(1.0).Send();
+  for (int i = 0; i < 500; ++i) {
+    drivetrain_motor_plant_.SendPositionMessage();
+    drivetrain_motor_.Iterate();
+    drivetrain_motor_plant_.Simulate();
+    if (i > 20 && i < 200) {
+      SimulateTimestep(false);
+    } else {
+      SimulateTimestep(true);
+    }
+  }
+  VerifyNearGoal();
+}
+
+// Tests that never having a goal doesn't break.
+TEST_F(DrivetrainTest, NoGoalStart) {
+  for (int i = 0; i < 20; ++i) {
+    drivetrain_motor_plant_.SendPositionMessage();
+    drivetrain_motor_.Iterate();
+    drivetrain_motor_plant_.Simulate();
+  }
+}
+
+// Tests that never having a goal, but having driver's station messages, doesn't
+// break.
+TEST_F(DrivetrainTest, NoGoalWithRobotState) {
+  for (int i = 0; i < 20; ++i) {
+    drivetrain_motor_plant_.SendPositionMessage();
+    drivetrain_motor_.Iterate();
+    drivetrain_motor_plant_.Simulate();
+    SimulateTimestep(true);
+  }
+}
+
+::aos::controls::HPolytope<2> MakeBox(double x1_min, double x1_max,
+                                      double x2_min, double x2_max) {
+  Eigen::Matrix<double, 4, 2> box_H;
+  box_H << /*[[*/ 1.0, 0.0 /*]*/,
+            /*[*/-1.0, 0.0 /*]*/,
+            /*[*/ 0.0, 1.0 /*]*/,
+            /*[*/ 0.0,-1.0 /*]]*/;
+  Eigen::Matrix<double, 4, 1> box_k;
+  box_k << /*[[*/ x1_max /*]*/,
+            /*[*/-x1_min /*]*/,
+            /*[*/ x2_max /*]*/,
+            /*[*/-x2_min /*]]*/;
+  ::aos::controls::HPolytope<2> t_poly(box_H, box_k);
+  return t_poly;
+}
+
+class CoerceGoalTest : public ::testing::Test {
+ public:
+  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
+};
+
+// WHOOOHH!
+TEST_F(CoerceGoalTest, Inside) {
+  ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << /*[[*/ 1, -1 /*]]*/;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << /*[[*/ 1.5, 1.5 /*]]*/;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(R(0, 0), output(0, 0));
+  EXPECT_EQ(R(1, 0), output(1, 0));
+}
+
+TEST_F(CoerceGoalTest, Outside_Inside_Intersect) {
+  ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << 1, -1;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << 5, 5;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(2.0, output(0, 0));
+  EXPECT_EQ(2.0, output(1, 0));
+}
+
+TEST_F(CoerceGoalTest, Outside_Inside_no_Intersect) {
+  ::aos::controls::HPolytope<2> box = MakeBox(3, 4, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << 1, -1;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << 5, 5;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(3.0, output(0, 0));
+  EXPECT_EQ(2.0, output(1, 0));
+}
+
+TEST_F(CoerceGoalTest, Middle_Of_Edge) {
+  ::aos::controls::HPolytope<2> box = MakeBox(0, 4, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << -1, 1;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << 5, 5;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(2.0, output(0, 0));
+  EXPECT_EQ(2.0, output(1, 0));
+}
+
+TEST_F(CoerceGoalTest, PerpendicularLine) {
+  ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
+
+  Eigen::Matrix<double, 1, 2> K;
+  K << 1, 1;
+
+  Eigen::Matrix<double, 2, 1> R;
+  R << 5, 5;
+
+  Eigen::Matrix<double, 2, 1> output =
+      ::frc971::control_loops::CoerceGoal(box, K, 0, R);
+
+  EXPECT_EQ(1.0, output(0, 0));
+  EXPECT_EQ(1.0, output(1, 0));
+}
+
+}  // namespace testing
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/drivetrain/drivetrain_main.cc b/y2015_bot3/control_loops/drivetrain/drivetrain_main.cc
new file mode 100644
index 0000000..eef49a8
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/drivetrain_main.cc
@@ -0,0 +1,11 @@
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+  ::aos::Init();
+  ::y2015_bot3::control_loops::DrivetrainLoop drivetrain;
+  drivetrain.Run();
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2015_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.cc b/y2015_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.cc
new file mode 100644
index 0000000..b1ce57f
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.cc
@@ -0,0 +1,49 @@
+#include "y2015_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<1, 1, 1> MakeCIMPlantCoefficients() {
+  Eigen::Matrix<double, 1, 1> A;
+  A << 0.783924473544;
+  Eigen::Matrix<double, 1, 1> B;
+  B << 8.94979586973;
+  Eigen::Matrix<double, 1, 1> C;
+  C << 1;
+  Eigen::Matrix<double, 1, 1> D;
+  D << 0;
+  Eigen::Matrix<double, 1, 1> U_max;
+  U_max << 12.0;
+  Eigen::Matrix<double, 1, 1> U_min;
+  U_min << -12.0;
+  return StateFeedbackPlantCoefficients<1, 1, 1>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<1, 1, 1> MakeCIMController() {
+  Eigen::Matrix<double, 1, 1> L;
+  L << 0.773924473544;
+  Eigen::Matrix<double, 1, 1> K;
+  K << 0.086473980503;
+  Eigen::Matrix<double, 1, 1> A_inv;
+  A_inv << 1.2756330919;
+  return StateFeedbackController<1, 1, 1>(L, K, A_inv, MakeCIMPlantCoefficients());
+}
+
+StateFeedbackPlant<1, 1, 1> MakeCIMPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>> plants(1);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>(new StateFeedbackPlantCoefficients<1, 1, 1>(MakeCIMPlantCoefficients()));
+  return StateFeedbackPlant<1, 1, 1>(&plants);
+}
+
+StateFeedbackLoop<1, 1, 1> MakeCIMLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<1, 1, 1>>> controllers(1);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<1, 1, 1>>(new StateFeedbackController<1, 1, 1>(MakeCIMController()));
+  return StateFeedbackLoop<1, 1, 1>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h b/y2015_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h
new file mode 100644
index 0000000..ebddeff
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h
@@ -0,0 +1,20 @@
+#ifndef Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
+#define Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<1, 1, 1> MakeCIMPlantCoefficients();
+
+StateFeedbackController<1, 1, 1> MakeCIMController();
+
+StateFeedbackPlant<1, 1, 1> MakeCIMPlant();
+
+StateFeedbackLoop<1, 1, 1> MakeCIMLoop();
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
diff --git a/y2015_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc b/y2015_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
new file mode 100644
index 0000000..da0e9b4
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
@@ -0,0 +1,133 @@
+#include "y2015_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowLowPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.909050248724, 0.0192068507303, 0.0192068507303, 0.909050248724;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0232454208683, -0.00490898900238, -0.00490898900238, 0.0232454208683;
+  Eigen::Matrix<double, 2, 2> C;
+  C << 1.0, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0.0, 0.0, 0.0, 0.0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.909050248724, 0.0192068507303, 0.0192068507303, 0.909050248724;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0232454208683, -0.00490898900238, -0.00490898900238, 0.0232454208683;
+  Eigen::Matrix<double, 2, 2> C;
+  C << 1.0, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0.0, 0.0, 0.0, 0.0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.909050248724, 0.0192068507303, 0.0192068507303, 0.909050248724;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0232454208683, -0.00490898900238, -0.00490898900238, 0.0232454208683;
+  Eigen::Matrix<double, 2, 2> C;
+  C << 1.0, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0.0, 0.0, 0.0, 0.0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 0.909050248724, 0.0192068507303, 0.0192068507303, 0.909050248724;
+  Eigen::Matrix<double, 2, 2> B;
+  B << 0.0232454208683, -0.00490898900238, -0.00490898900238, 0.0232454208683;
+  Eigen::Matrix<double, 2, 2> C;
+  C << 1.0, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 2, 2> D;
+  D << 0.0, 0.0, 0.0, 0.0;
+  Eigen::Matrix<double, 2, 1> U_max;
+  U_max << 12.0, 12.0;
+  Eigen::Matrix<double, 2, 1> U_min;
+  U_min << -12.0, -12.0;
+  return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.889050248724, 0.0192068507303, 0.0192068507303, 0.889050248724;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 14.0983425164, 3.80356456422, 3.80356456422, 14.0983425164;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.1005404965, -0.0232527487546, -0.0232527487546, 1.1005404965;
+  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.889050248724, 0.0192068507303, 0.0192068507303, 0.889050248724;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 14.0983425164, 3.80356456422, 3.80356456422, 14.0983425164;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.1005404965, -0.0232527487546, -0.0232527487546, 1.1005404965;
+  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowHighPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.889050248724, 0.0192068507303, 0.0192068507303, 0.889050248724;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 14.0983425164, 3.80356456422, 3.80356456422, 14.0983425164;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.1005404965, -0.0232527487546, -0.0232527487546, 1.1005404965;
+  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController() {
+  Eigen::Matrix<double, 2, 2> L;
+  L << 0.889050248724, 0.0192068507303, 0.0192068507303, 0.889050248724;
+  Eigen::Matrix<double, 2, 2> K;
+  K << 14.0983425164, 3.80356456422, 3.80356456422, 14.0983425164;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.1005404965, -0.0232527487546, -0.0232527487546, 1.1005404965;
+  return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighHighPlantCoefficients());
+}
+
+StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>> plants(4);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowLowPlantCoefficients()));
+  plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowHighPlantCoefficients()));
+  plants[2] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighLowPlantCoefficients()));
+  plants[3] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighHighPlantCoefficients()));
+  return StateFeedbackPlant<2, 2, 2>(&plants);
+}
+
+StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<2, 2, 2>>> controllers(4);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowLowController()));
+  controllers[1] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowHighController()));
+  controllers[2] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighLowController()));
+  controllers[3] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighHighController()));
+  return StateFeedbackLoop<2, 2, 2>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h b/y2015_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
new file mode 100644
index 0000000..a6afeaf
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
@@ -0,0 +1,32 @@
+#ifndef Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
+#define Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowLowPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController();
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients();
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController();
+
+StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant();
+
+StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop();
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/y2015_bot3/control_loops/drivetrain/replay_drivetrain.cc b/y2015_bot3/control_loops/drivetrain/replay_drivetrain.cc
new file mode 100644
index 0000000..fb14f1f
--- /dev/null
+++ b/y2015_bot3/control_loops/drivetrain/replay_drivetrain.cc
@@ -0,0 +1,25 @@
+#include "aos/common/controls/replay_control_loop.h"
+#include "aos/linux_code/init.h"
+
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.q.h"
+
+// Reads one or more log files and sends out all the queue messages (in the
+// correct order and at the correct time) to feed a "live" drivetrain process.
+
+int main(int argc, char **argv) {
+  if (argc <= 1) {
+    fprintf(stderr, "Need at least one file to replay!\n");
+    return EXIT_FAILURE;
+  }
+
+  ::aos::InitNRT();
+
+  ::aos::controls::ControlLoopReplayer<
+      ::y2015_bot3::control_loops::DrivetrainQueue>
+      replayer(&::y2015_bot3::control_loops::drivetrain_queue, "drivetrain");
+  for (int i = 1; i < argc; ++i) {
+    replayer.ProcessFile(argv[i]);
+  }
+
+  ::aos::Cleanup();
+}
diff --git a/y2015_bot3/control_loops/elevator/BUILD b/y2015_bot3/control_loops/elevator/BUILD
new file mode 100644
index 0000000..b249477
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/BUILD
@@ -0,0 +1,63 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+queue_library(
+  name = 'elevator_queue',
+  srcs = [
+    'elevator.q',
+  ],
+  deps = [
+    '//aos/common/controls:control_loop_queues',
+    '//frc971/control_loops:queues',
+  ],
+)
+
+cc_library(
+  name = 'elevator_lib',
+  srcs = [
+    'elevator.cc',
+    'elevator_motor_plant.cc',
+    'integral_elevator_motor_plant.cc',
+  ],
+  hdrs = [
+    'elevator.h',
+    'elevator_motor_plant.h',
+    'integral_elevator_motor_plant.h',
+  ],
+  deps = [
+    ':elevator_queue',
+    '//aos/common/logging',
+    '//aos/common/controls:control_loop_queues',
+    '//aos/common/controls:control_loop',
+    '//aos/common/util:trapezoid_profile',
+    '//frc971/control_loops:state_feedback_loop',
+    '//frc971/control_loops/voltage_cap:voltage_cap',
+  ],
+)
+
+cc_test(
+  name = 'elevator_lib_test',
+  srcs = [
+    'elevator_lib_test.cc',
+  ],
+  deps = [
+    '//third_party/googletest',
+    ':elevator_lib',
+    '//y2015_bot3/control_loops:position_sensor_sim',
+    '//frc971/control_loops:state_feedback_loop',
+    '//aos/common/controls:control_loop_test',
+    '//aos/common:time',
+  ],
+)
+
+cc_binary(
+  name = 'elevator',
+  srcs = [
+    'elevator_main.cc',
+  ],
+  deps = [
+    '//aos/linux_code:init',
+    ':elevator_lib',
+  ],
+)
diff --git a/y2015_bot3/control_loops/elevator/elevator.cc b/y2015_bot3/control_loops/elevator/elevator.cc
new file mode 100644
index 0000000..2fef56f
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/elevator.cc
@@ -0,0 +1,285 @@
+#include "y2015_bot3/control_loops/elevator/elevator.h"
+
+#include <cmath>
+
+#include "aos/common/controls/control_loops.q.h"
+#include "aos/common/logging/logging.h"
+
+#include "y2015_bot3/control_loops/elevator/integral_elevator_motor_plant.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+void SimpleCappedStateFeedbackLoop::CapU() {
+  mutable_U(0, 0) = ::std::min(U(0, 0), max_voltage_);
+  mutable_U(0, 0) = ::std::max(U(0, 0), -max_voltage_);
+}
+
+double SimpleCappedStateFeedbackLoop::UnsaturateOutputGoalChange() {
+  // Compute K matrix to compensate for position errors.
+  double Kp = K(0, 0);
+
+  // Compute how much we need to change R in order to achieve the change in U
+  // that was observed.
+  return -(1.0 / Kp) * (U_uncapped() - U())(0, 0);
+}
+
+Elevator::Elevator(control_loops::ElevatorQueue *elevator)
+    : aos::controls::ControlLoop<control_loops::ElevatorQueue>(elevator),
+      loop_(new SimpleCappedStateFeedbackLoop(MakeIntegralElevatorLoop())),
+      profile_(::aos::controls::kLoopFrequency) {}
+
+bool Elevator::CheckZeroed() {
+  return state_ == RUNNING;
+}
+
+void Elevator::Correct() {
+  Eigen::Matrix<double, 1, 1> Y;
+  Y << current_position();
+  loop_->Correct(Y);
+}
+
+double Elevator::current_position() {
+  return current_position_.encoder + offset_;
+}
+
+double Elevator::GetZeroingVelocity() {
+  return zeroing_velocity_;
+}
+
+// If the hall_effect is true that means we need to move up until is false.
+// Then we should move down.
+double Elevator::FindZeroingVelocity() {
+  if (glitch_filter_.filtered_value()) {
+    zeroing_velocity_ = kZeroingSlowVelocity;
+  } else {
+    zeroing_velocity_ = -kZeroingVelocity;
+  }
+
+  return zeroing_velocity_;
+}
+
+double Elevator::UseUnlessZero(double target_value, double default_value) {
+  if (target_value != 0.0) {
+    return target_value;
+  } else {
+    return default_value;
+  }
+}
+
+void Elevator::SetOffset(double offset) {
+  LOG(INFO, "Changing Elevator offset from %f to %f\n", offset_, offset);
+  double doffset = offset - offset_;
+
+  loop_->mutable_X_hat(0, 0) += doffset;
+
+  // Modify the zeroing goal.
+  goal_ += doffset;
+
+  // Update the cached offset values to the actual values.
+  offset_ = offset;
+}
+
+void Elevator::RunIteration(
+    const control_loops::ElevatorQueue::Goal *unsafe_goal,
+    const control_loops::ElevatorQueue::Position *position,
+    control_loops::ElevatorQueue::Output *output,
+    control_loops::ElevatorQueue::Status *status) {
+  if (WasReset()) {
+    LOG(ERROR, "WPILib reset, restarting\n");
+    state_ = UNINITIALIZED;
+  }
+  glitch_filter_.Update(position->bottom_hall_effect, position->encoder);
+
+  // Bool to track if we should turn the motors on or not.
+  bool disable = output == nullptr;
+
+  // Save the current position so it can be used easily in the class.
+  current_position_ = *position;
+
+  if (state_ != UNINITIALIZED) {
+    Correct();
+  }
+
+  switch (state_) {
+    case UNINITIALIZED:
+      LOG(DEBUG, "Uninitialized\n");
+      // Startup.  Assume that we are at the origin everywhere.
+      offset_ = -position->encoder;
+      loop_->mutable_X_hat().setZero();
+      LOG(INFO, "Initializing elevator offset to %f\n", offset_);
+      Correct();
+      state_ = ZEROING;
+      disable = true;
+      glitch_filter_.Reset(position->bottom_hall_effect);
+      break;
+
+    case ZEROING:
+      LOG(DEBUG, "Zeroing elevator\n");
+
+      if (glitch_filter_.negedge()) {
+        state_ = RUNNING;
+        SetOffset(-glitch_filter_.negedge_value() + kHallEffectPosition);
+      }
+
+      // We need to check FindZeroingVelocity() every time
+      // in order for zeroing to work.
+      {
+        double zeroing_velocity_temp = FindZeroingVelocity();
+        if (state_ != RUNNING && !disable) {
+          // Move the elevator either up or down based on where the zeroing hall
+          // effect is located.
+
+          goal_velocity_ = zeroing_velocity_temp; 
+          goal_ += goal_velocity_ * ::aos::controls::kLoopFrequency.ToSeconds();
+        }
+      }
+
+      // Bypass motion profiles while we are zeroing.
+      // This is also an important step right after the elevator is zeroed and
+      // we reach into the elevator's state matrix and change it based on the
+      // newly-obtained offset.
+      {
+        Eigen::Matrix<double, 2, 1> current;
+        current.setZero();
+        current << goal_, goal_velocity_;
+        profile_.MoveCurrentState(current);
+      }
+      break;
+
+    case RUNNING:
+      if (unsafe_goal) {
+        profile_.set_maximum_velocity(
+            UseUnlessZero(unsafe_goal->max_velocity, 0.50));
+        profile_.set_maximum_acceleration(
+            UseUnlessZero(unsafe_goal->max_acceleration, 2.0));
+
+        // Use the profiles to limit the elevator's movements.
+        const double unfiltered_goal = ::std::max(
+            ::std::min(unsafe_goal->height, kElevUpperLimit), kElevLowerLimit);
+        ::Eigen::Matrix<double, 2, 1> goal_state =
+            profile_.Update(unfiltered_goal, unsafe_goal->velocity);
+        goal_ = goal_state(0, 0);
+        goal_velocity_ = goal_state(1, 0);
+      }
+
+      if (state_ != RUNNING && state_ != ESTOP) {
+        state_ = UNINITIALIZED;
+      }
+      break;
+
+    case ESTOP:
+      LOG(ERROR, "Estop\n");
+      disable = true;
+      break;
+  }
+
+  // Limit the goals so we can't exceed the hardware limits if we are RUNNING.
+  if (state_ == RUNNING) {
+    // Limit the elevator goal to min/max allowable heights.
+    if (goal_ >= kElevUpperLimit) {
+      LOG(WARNING, "Elevator goal above limit, %f > %f\n", goal_,
+          kElevUpperLimit);
+      goal_ = kElevUpperLimit;
+    }
+
+    if (goal_ <= kElevLowerLimit) {
+      LOG(WARNING, "Elevator goal below limit, %f < %f\n", goal_,
+          kElevLowerLimit);
+      goal_ = kElevLowerLimit;
+    }
+  }
+
+  // Check the hard limits.
+  if (state_ == RUNNING) {
+    if (current_position() >= kElevUpperHardLimit) {
+      LOG(ERROR, "Elevator at %f out of bounds [%f, %f], ESTOPing\n",
+          current_position(), kElevLowerHardLimit, kElevUpperHardLimit);
+      if (output) {
+        state_ = ESTOP;
+      }
+    }
+
+    if (current_position() <= kElevLowerHardLimit) {
+      LOG(ERROR, "Elevator at %f out of bounds [%f, %f], ESTOPing\n",
+          current_position(), kElevLowerHardLimit, kElevUpperHardLimit);
+      if (output) {
+        state_ = ESTOP;
+      }
+    }
+  }
+
+  // Set the goals.
+  loop_->mutable_R() << goal_, goal_velocity_, 0.0;
+
+  const double max_voltage = state_ == RUNNING ? 12.0 : kZeroingVoltage;
+  loop_->set_max_voltage(max_voltage);
+
+  if (state_ == ESTOP) {
+    disable = true;
+  }
+  loop_->Update(disable);
+
+  if (state_ == ZEROING || state_ == RUNNING) {
+    if (loop_->U() != loop_->U_uncapped()) {
+      double deltaR = loop_->UnsaturateOutputGoalChange();
+
+      // Move the elevator goal by the amount observed.
+      LOG(WARNING, "Moving elevator goal by %f to handle saturation\n", deltaR);
+      goal_ += deltaR;
+
+      Eigen::Matrix<double, 2, 1> current;
+      current.setZero();
+      current << goal_, goal_velocity_;
+      profile_.MoveCurrentState(current);
+    }
+  }
+
+  if (output) {
+    output->elevator = loop_->U(0, 0);
+    if(unsafe_goal) {
+      output->passive_support = unsafe_goal->passive_support;
+      output->can_support = unsafe_goal->can_support;
+    }
+  }
+
+  status->zeroed = state_ == RUNNING;
+
+  status->height = loop_->X_hat(0, 0);
+  status->velocity = loop_->X_hat(1, 0);
+
+  status->goal_height = goal_;
+  status->goal_velocity = goal_velocity_;
+
+  status->estopped = (state_ == ESTOP);
+  status->state = state_;
+  status->has_tote = position->has_tote;
+}
+
+void GlitchFilter::Update(bool hall_effect, double encoder) {
+  posedge_ = false;
+  negedge_ = false;
+  if (hall_effect != accepted_value_) {
+    if (count_ == 0) {
+      first_encoder_ = encoder;
+    }
+    ++count_;
+  } else {
+    last_encoder_ = encoder;
+    count_ = 0;
+  }
+  if (count_ >= 2) {
+    if (hall_effect) {
+      posedge_ = true;
+      posedge_value_ = (first_encoder_ + last_encoder_) / 2.0;
+    } else {
+      negedge_ = true;
+      negedge_value_ = (first_encoder_ + last_encoder_) / 2.0;
+    }
+    accepted_value_ = hall_effect;
+    count_ = 0;
+  }
+}
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/elevator/elevator.gyp b/y2015_bot3/control_loops/elevator/elevator.gyp
new file mode 100644
index 0000000..c184429
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/elevator.gyp
@@ -0,0 +1,71 @@
+{
+  'targets': [
+    {
+      'target_name': 'elevator_queue',
+      'type': 'static_library',
+      'sources': ['elevator.q'],
+      'variables': {
+        'header_path': 'bot3/control_loops/elevator',
+      },
+      'dependencies': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+      ],
+      'includes': ['../../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'elevator_lib',
+      'type': 'static_library',
+      'sources': [
+        'elevator.cc',
+        'elevator_motor_plant.cc',
+        'integral_elevator_motor_plant.cc',
+      ],
+      'dependencies': [
+        'elevator_queue',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(AOS)/common/util/util.gyp:trapezoid_profile',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(DEPTH)/frc971/control_loops/voltage_cap/voltage_cap.gyp:voltage_cap',
+      ],
+      'export_dependent_settings': [
+        'elevator_queue',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(AOS)/common/util/util.gyp:trapezoid_profile',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+    },
+    {
+      'target_name': 'elevator_lib_test',
+      'type': 'executable',
+      'sources': [
+        'elevator_lib_test.cc',
+      ],
+      'dependencies': [
+        '<(EXTERNALS):gtest',
+        'elevator_lib',
+        '<(DEPTH)/bot3/control_loops/control_loops.gyp:position_sensor_sim',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(AOS)/common/controls/controls.gyp:control_loop_test',
+        '<(AOS)/common/common.gyp:time',
+      ],
+    },
+    {
+      'target_name': 'elevator',
+      'type': 'executable',
+      'sources': [
+        'elevator_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'elevator_lib',
+      ],
+    },
+  ],
+}
diff --git a/y2015_bot3/control_loops/elevator/elevator.h b/y2015_bot3/control_loops/elevator/elevator.h
new file mode 100644
index 0000000..e6cd483
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/elevator.h
@@ -0,0 +1,191 @@
+#ifndef Y2015_BOT3_CONTROL_LOOPS_ELEVATOR_H_
+#define Y2015_BOT3_CONTROL_LOOPS_ELEVATOR_H_
+
+#include <memory>
+
+#include "aos/common/controls/control_loop.h"
+#include "aos/common/util/trapezoid_profile.h"
+
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "y2015_bot3/control_loops/elevator/elevator.q.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+namespace testing {
+class ElevatorTest_DisabledGoalTest_Test;
+class ElevatorTest_ElevatorGoalPositiveWindupTest_Test;
+class ElevatorTest_ElevatorGoalNegativeWindupTest_Test;
+class ElevatorTest_PositiveRunawayProfileTest_Test;
+class ElevatorTest_NegativeRunawayProfileTest_Test;
+}  // namespace testing
+
+// Constants
+constexpr double kZeroingVoltage = 4.0;
+// TODO(austin): Slow down the zeroing velocity.
+constexpr double kZeroingVelocity = 0.05;
+constexpr double kZeroingSlowVelocity = 0.01;
+
+// Game pieces
+constexpr double kToteHeight = 0.3;
+
+// Gearing
+constexpr double kElevEncoderRatio = 18.0 / 48.0;
+constexpr double kElevChainReduction = 16.0 / 22.0;
+const int kElevGearboxOutputPulleyTeeth = 22;
+constexpr double kElevGearboxOutputPitch = 0.25 * 0.0254; // 25 pitch chain.
+
+constexpr double kElevGearboxOutputRadianDistance =
+    kElevGearboxOutputPulleyTeeth * kElevGearboxOutputPitch / (2.0 * M_PI);
+
+// Limits
+constexpr double kElevLowerHardLimit = -0.010;
+constexpr double kElevUpperHardLimit = 1.387;
+constexpr double kElevLowerLimit = 0.010;
+constexpr double kElevUpperLimit = 1.350;
+
+// Zeroing
+namespace {
+constexpr double kHallEffectPosition = 0.025;
+}  // namespace
+// End constants
+
+class SimpleCappedStateFeedbackLoop : public StateFeedbackLoop<3, 1, 1> {
+ public:
+  SimpleCappedStateFeedbackLoop(StateFeedbackLoop<3, 1, 1> &&loop)
+      : StateFeedbackLoop<3, 1, 1>(::std::move(loop)), max_voltage_(12.0) {}
+
+  void set_max_voltage(double max_voltage) {
+    max_voltage_ = ::std::max(0.0, ::std::min(12.0, max_voltage));
+  }
+
+  void CapU() override;
+
+  // Returns the amount to change the position goal in order to no longer
+  // saturate the controller.
+  double UnsaturateOutputGoalChange();
+
+ private:
+  double max_voltage_;
+};
+
+// The GlitchFilter filters out single cycle changes in order to filter out
+// sensor noise.  It also captures the sensor value at the time that the
+// original transition happens (not the de-bounced transition) to remove delay
+// caused by this filter.
+class GlitchFilter {
+ public:
+  void Reset(bool hall_effect) {
+    accepted_value_ = hall_effect;
+    posedge_ = false;
+    negedge_ = false;
+    count_ = 0;
+  }
+
+  // Updates the filter state with new observations.
+  void Update(bool hall_effect, double encoder);
+
+  // Returns a debounced hall effect value.
+  bool filtered_value() const { return accepted_value_; }
+
+  // Returns true if last cycle had a posedge.
+  bool posedge() const { return posedge_; }
+  // Returns the encoder value across the last posedge.
+  double posedge_value() const { return posedge_value_; }
+
+  // Returns true if last cycle had a negedge.
+  bool negedge() const { return negedge_; }
+  // Returns the encoder value across the last negedge.
+  double negedge_value() const { return negedge_value_; }
+
+ private:
+  int count_ = 0;
+  bool accepted_value_ = false;
+  bool posedge_ = false;
+  bool negedge_ = false;
+  double posedge_value_ = 0;
+  double negedge_value_ = 0;
+
+  double first_encoder_ = 0;
+  double last_encoder_ = 0;
+};
+
+class Elevator
+    : public aos::controls::ControlLoop<control_loops::ElevatorQueue> {
+ public:
+  explicit Elevator(control_loops::ElevatorQueue *elevator_queue =
+                        &control_loops::elevator_queue);
+
+  bool CheckZeroed();
+
+  // Getter for the current elevator positions with zeroed offset.
+  double current_position();
+
+  double GetZeroingVelocity();
+
+  enum State {
+    // Waiting to receive data before doing anything.
+    UNINITIALIZED = 0,
+    // Moving the elevator to find an index pulse.
+    ZEROING = 2,
+    // All good!
+    RUNNING = 3,
+    // Internal error caused the elevator to abort.
+    ESTOP = 4,
+  };
+
+  State state() const { return state_; }
+
+ protected:
+  void RunIteration(const control_loops::ElevatorQueue::Goal *goal,
+                    const control_loops::ElevatorQueue::Position *position,
+                    control_loops::ElevatorQueue::Output *output,
+                    control_loops::ElevatorQueue::Status *status) override;
+
+ private:
+  friend class testing::ElevatorTest_DisabledGoalTest_Test;
+  friend class testing::ElevatorTest_ElevatorGoalPositiveWindupTest_Test;
+  friend class testing::ElevatorTest_ElevatorGoalNegativeWindupTest_Test;
+  friend class testing::ElevatorTest_PositiveRunawayProfileTest_Test;
+  friend class testing::ElevatorTest_NegativeRunawayProfileTest_Test;
+
+  void SetOffset(double offset);
+
+  // Returns the current elevator zeroing velocity.
+  double FindZeroingVelocity();
+
+  // Corrects the Observer with the current position.
+  void Correct();
+
+  double UseUnlessZero(double target_value, double default_value);
+
+  // The state feedback control loop or loops to talk to.
+  ::std::unique_ptr<SimpleCappedStateFeedbackLoop> loop_;
+
+  // Offsets from the encoder position to the absolute position.  Add these to
+  // the encoder position to get the absolute position.
+  double offset_ = 0.0;
+
+  bool zeroed_ = false;
+  State state_ = State::UNINITIALIZED;
+
+  // Variables for detecting the zeroing hall effect edge.
+  bool zeroing_hall_effect_edge_detector_initialized_ = false;
+  bool zeroing_hall_effect_previous_reading_ = false;
+
+  // Current velocity to move at while zeroing.
+  double zeroing_velocity_ = 0.0;
+
+  // The goals for the elevator.
+  double goal_ = 0.0;
+  double goal_velocity_ = 0.0;
+
+  control_loops::ElevatorQueue::Position current_position_;
+
+  aos::util::TrapezoidProfile profile_;
+  GlitchFilter glitch_filter_;
+};
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_CONTROL_LOOPS_ELEVATOR_H_
diff --git a/y2015_bot3/control_loops/elevator/elevator.q b/y2015_bot3/control_loops/elevator/elevator.q
new file mode 100644
index 0000000..1492f1f
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/elevator.q
@@ -0,0 +1,85 @@
+package y2015_bot3.control_loops;
+
+import "aos/common/controls/control_loops.q";
+import "frc971/control_loops/control_loops.q";
+
+queue_group ElevatorQueue {
+  implements aos.control_loops.ControlLoop;
+
+  // Elevator heights are the vertical distance (in meters) from a defined zero.
+
+  message Goal {
+    // Height of the elevator.
+    double height;
+
+    // Linear velocity of the elevator.
+    float velocity;
+
+    // Maximum elevator profile velocity or 0 for the default.
+    float max_velocity;
+
+    // Maximum elevator profile acceleration or 0 for the default.
+    float max_acceleration;
+
+    // Whether the passive elevator is supporting the stack/can; true means it
+    // is supporting; false means it is not.
+    bool passive_support;
+    // Whether the can support is restraining the can; true means it
+    // is supporting; false means it is not.
+    bool can_support;
+  };
+
+  message Position {
+    double encoder;
+
+    // bottom hall effect sensor for zeroing purposes.
+    bool bottom_hall_effect;
+
+    // True if there is a tote inside the elevator.
+    bool has_tote;
+  };
+
+  message Status {
+    // Is the elevator zeroed?
+    bool zeroed;
+
+    // Estimated height of the elevator.
+    double height;
+
+    // Estimated velocity of the elevator.
+    float velocity;
+
+    // Goal height and velocity of the elevator.
+    double goal_height;
+    float goal_velocity;
+
+    // True if there is a tote inside the elevator.
+    bool has_tote;
+
+    // If true, we have aborted.
+    bool estopped;
+
+    // The internal state of the state machine.
+    int32_t state;
+  };
+
+  message Output {
+    // Voltage for the active elevator.
+    double elevator;
+
+    // Toggle for the passive elevator that supports the stack in the robot.
+    // True means support the stack, false means release the support from the
+    // stack.
+    bool passive_support;
+    // Toggle for the that supports the can in the robot.
+    // True means support the can, false means release the can.
+    bool can_support;
+  };
+
+  queue Goal goal;
+  queue Position position;
+  queue Output output;
+  queue Status status;
+};
+
+queue_group ElevatorQueue elevator_queue;
diff --git a/y2015_bot3/control_loops/elevator/elevator_lib_test.cc b/y2015_bot3/control_loops/elevator/elevator_lib_test.cc
new file mode 100644
index 0000000..2f6b019
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/elevator_lib_test.cc
@@ -0,0 +1,598 @@
+#include "y2015_bot3/control_loops/elevator/elevator.h"
+
+#include <math.h>
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/queue.h"
+#include "aos/common/time.h"
+#include "aos/common/controls/control_loop_test.h"
+#include "y2015_bot3/control_loops/position_sensor_sim.h"
+#include "y2015_bot3/control_loops/elevator/elevator_motor_plant.h"
+#include "y2015_bot3/control_loops/elevator/elevator.q.h"
+
+using ::aos::time::Time;
+using ::y2015_bot3::control_loops::PositionSensorSimulator;
+
+namespace y2015_bot3 {
+namespace control_loops {
+namespace testing {
+
+
+// TODO(comran+adam): Check these over with Austin, Ben, Brian, and others to
+// make sure we didn't forget anything -- especially the zeroing tests!!!
+
+class ElevatorSimulator {
+ public:
+  ElevatorSimulator()
+      : plant_(new StateFeedbackPlant<2, 1, 1>(MakeElevatorPlant())),
+        position_sim_(),
+        queue_(".y2015_bot3.control_loops.elevator_queue", 0xca8daa3b,
+               ".y2015_bot3.control_loops.elevator_queue.goal",
+               ".y2015_bot3.control_loops.elevator_queue.position",
+               ".y2015_bot3.control_loops.elevator_queue.output",
+               ".y2015_bot3.control_loops.elevator_queue.status") {
+    // Initialize the elevator.
+    InitializePosition(kElevLowerLimit);
+  }
+
+  void InitializePosition(double start_pos) {
+    InitializePosition(start_pos, kHallEffectPosition);
+  }
+
+  void InitializePosition(double start_pos, double hall_effect_position) {
+    plant_->mutable_X(0, 0) = start_pos;
+    plant_->mutable_X(1, 0) = 0.0;
+    position_sim_.Initialize(start_pos, hall_effect_position);
+  }
+
+  void SendPositionMessage() {
+    ::aos::ScopedMessagePtr<control_loops::ElevatorQueue::Position> position =
+        queue_.position.MakeMessage();
+    position_sim_.GetSensorValues(position.get());
+    position.Send();
+  }
+
+  void set_acceleration_offset(double acceleration_offset) {
+    acceleration_offset_ = acceleration_offset;
+  }
+
+  double height() const { return plant_->Y(0, 0); }
+
+  void Simulate() {
+    EXPECT_TRUE(queue_.output.FetchLatest());
+
+    plant_->mutable_U() << queue_.output->elevator;
+
+    plant_->Update();
+    plant_->mutable_X()(1, 0) += acceleration_offset_ * 0.005;
+
+    const double height = plant_->Y(0, 0);
+
+    position_sim_.MoveTo(height);
+
+    EXPECT_GE(height, kElevLowerHardLimit);
+    EXPECT_LE(height, kElevUpperHardLimit);
+  }
+
+  void MoveTo(double position) { position_sim_.MoveTo(position); }
+
+  double GetVoltage() const { return plant_->U()(0,0); }
+
+ private:
+  ::std::unique_ptr<StateFeedbackPlant<2, 1, 1>> plant_;
+
+  PositionSensorSimulator position_sim_;
+
+  ElevatorQueue queue_;
+  double acceleration_offset_ = 0.0;
+};
+
+class ElevatorTest : public ::aos::testing::ControlLoopTest {
+ protected:
+  ElevatorTest()
+      : queue_(".y2015_bot3.control_loops.elevator_queue", 0xca8daa3b,
+               ".y2015_bot3.control_loops.elevator_queue.goal",
+               ".y2015_bot3.control_loops.elevator_queue.position",
+               ".y2015_bot3.control_loops.elevator_queue.output",
+               ".y2015_bot3.control_loops.elevator_queue.status"),
+        elevator_(&queue_),
+        plant_() {}
+
+  // Checks to see if fetching position/status from queues does not return null
+  // pointers.
+  void VerifyNearGoal() {
+    queue_.goal.FetchLatest();
+    queue_.status.FetchLatest();
+    EXPECT_TRUE(queue_.goal.get() != nullptr);
+    EXPECT_TRUE(queue_.status.get() != nullptr);
+    EXPECT_NEAR(queue_.goal->height, queue_.status->height, 0.001);
+    EXPECT_NEAR(queue_.goal->height, plant_.height(), 0.001);
+  }
+
+  // Runs one iteration of the whole simulation.
+  void RunIteration(bool enabled = true) {
+    SendMessages(enabled);
+    plant_.SendPositionMessage();
+    elevator_.Iterate();
+    plant_.Simulate();
+
+    TickTime();
+  }
+
+  // Runs iterations until the specified amount of simulated time has elapsed.
+  void RunForTime(const Time &run_for, bool enabled = true) {
+    const auto start_time = Time::Now();
+    while (Time::Now() < start_time + run_for) {
+      RunIteration(enabled);
+    }
+  }
+
+  // Create a new instance of the test queue so that it invalidates the queue
+  // that it points to. Otherwise, we will have a pointed to shared memory that
+  // is no longer valid.
+  ElevatorQueue queue_;
+
+  // Create a control loop and simulation.
+  Elevator elevator_;
+  ElevatorSimulator plant_;
+};
+
+// Tests that the loop does nothing when the goal is zero.
+TEST_F(ElevatorTest, DoesNothing) {
+  // Set the goals to the starting values. This should theoretically guarantee
+  // that the controller does nothing.
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder()
+                  .height(kElevLowerLimit)
+                  .max_velocity(20)
+                  .max_acceleration(20)
+                  .Send());
+
+  // Run a few iterations.
+  RunForTime(Time::InSeconds(5));
+
+  VerifyNearGoal();
+}
+
+// Tests that the loop can reach a goal.
+TEST_F(ElevatorTest, ReachesGoal) {
+  // Set a reasonable goal.
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder()
+                  .height(kElevLowerLimit + 0.5)
+                  .max_velocity(20)
+                  .max_acceleration(20)
+                  .Send());
+
+  // Give it a lot of time to get there.
+  RunForTime(Time::InSeconds(5));
+
+  VerifyNearGoal();
+}
+
+// Tests that the loop doesn't try and go beyond the physical range of the
+// mechanisms.
+TEST_F(ElevatorTest, RespectsRange) {
+  // We're going to send the elevator to -5, which should be significantly too
+  // low.
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder()
+                  .height(-5.0)
+                  .max_velocity(20)
+                  .max_acceleration(20)
+                  .Send());
+
+  RunForTime(Time::InSeconds(10));
+
+  // Check that we are near our soft limit.
+  queue_.status.FetchLatest();
+  EXPECT_NEAR(kElevLowerLimit, queue_.status->height, 0.001);
+
+  // We're going to give the elevator some ridiculously high goal.
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder()
+                  .height(50.0)
+                  .max_velocity(20)
+                  .max_acceleration(20)
+                  .Send());
+
+  RunForTime(Time::InSeconds(10));
+
+  // Check that we are near our soft limit.
+  queue_.status.FetchLatest();
+  EXPECT_NEAR(kElevUpperLimit, queue_.status->height, 0.001);
+}
+
+// Tests that the loop zeroes when run for a while.
+TEST_F(ElevatorTest, ZeroTest) {
+  queue_.goal.MakeWithBuilder()
+      .height(0.5)
+      .max_velocity(20)
+      .max_acceleration(20)
+      .Send();
+  RunForTime(Time::InSeconds(5));
+
+  VerifyNearGoal();
+}
+
+// Tests that starting at the lower hardstops doesn't cause an abort.
+TEST_F(ElevatorTest, LowerHardstopStartup) {
+  plant_.InitializePosition(kElevLowerHardLimit);
+  queue_.goal.MakeWithBuilder().height(0.4).Send();
+  RunForTime(Time::InMS(5000));
+
+  VerifyNearGoal();
+}
+
+// Tests that starting at the upper hardstops doesn't cause an abort.
+TEST_F(ElevatorTest, UpperHardstopStartup) {
+  plant_.InitializePosition(kElevUpperHardLimit);
+  queue_.goal.MakeWithBuilder().height(0.4).Send();
+  RunForTime(Time::InMS(30000));
+
+  VerifyNearGoal();
+}
+
+// Tests that resetting WPILib results in a rezero.
+TEST_F(ElevatorTest, ResetTest) {
+  plant_.InitializePosition(kElevLowerLimit);
+  queue_.goal.MakeWithBuilder().height(0.05).Send();
+  RunForTime(Time::InMS(5000));
+
+  EXPECT_EQ(Elevator::RUNNING, elevator_.state());
+  VerifyNearGoal();
+  SimulateSensorReset();
+  RunForTime(Time::InMS(100));
+  EXPECT_NE(Elevator::RUNNING, elevator_.state());
+  RunForTime(Time::InMS(10000));
+  EXPECT_EQ(Elevator::RUNNING, elevator_.state());
+  VerifyNearGoal();
+}
+
+// Tests that the internal goals don't change while disabled.
+TEST_F(ElevatorTest, DisabledGoalTest) {
+  queue_.goal.MakeWithBuilder().height(0.45).Send();
+
+  RunForTime(Time::InMS(100), false);
+  EXPECT_EQ(0.0, elevator_.goal_);
+
+  // Now make sure they move correctly
+  RunForTime(Time::InMS(4000), true);
+  EXPECT_NE(0.0, elevator_.goal_);
+}
+
+// Tests that the elevator zeroing goals don't wind up too far.
+TEST_F(ElevatorTest, ElevatorGoalPositiveWindupTest) {
+  plant_.InitializePosition(0.0, kHallEffectPosition);
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder().height(0.45).Send());
+
+  while (elevator_.state() != Elevator::ZEROING) {
+    RunIteration();
+  }
+
+  // Kick it.
+  RunForTime(Time::InMS(50));
+  double orig_goal = elevator_.goal_;
+  elevator_.goal_ += 100.0;
+
+  RunIteration();
+  EXPECT_NEAR(orig_goal, elevator_.goal_, 0.05);
+
+  RunIteration();
+  EXPECT_EQ(elevator_.loop_->U(), elevator_.loop_->U_uncapped());
+
+  EXPECT_EQ(elevator_.state(), Elevator::ZEROING);
+}
+
+// Tests that the elevator zeroing goals don't wind up too far.
+TEST_F(ElevatorTest, ElevatorGoalNegativeWindupTest) {
+  plant_.InitializePosition(0.0, kHallEffectPosition);
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder().height(0.45).Send());
+
+  while (elevator_.state() != Elevator::ZEROING) {
+    RunIteration();
+  }
+
+  // Kick it.
+  RunForTime(Time::InMS(50));
+  double orig_goal = elevator_.goal_;
+  elevator_.goal_ -= 100.0;
+
+  RunIteration();
+  EXPECT_NEAR(orig_goal, elevator_.goal_, 0.05);
+
+  RunIteration();
+  EXPECT_EQ(elevator_.loop_->U(), elevator_.loop_->U_uncapped());
+
+  EXPECT_EQ(elevator_.state(), Elevator::ZEROING);
+}
+
+// Tests that the loop zeroes when run for a while.
+TEST_F(ElevatorTest, ZeroNoGoal) {
+  RunForTime(Time::InSeconds(5));
+
+  EXPECT_EQ(Elevator::RUNNING, elevator_.state());
+}
+
+// Zeroing tests
+// TODO(comran+adam): The following tests don't look like they are complete, so
+// we will need to get these tests checked & passed before running the elevator
+// control loop.
+
+// Tests that starting in the middle zeros correctly.
+TEST_F(ElevatorTest, CasualStart) {
+  const double start_position = (kElevUpperLimit + kElevLowerLimit) / 2.0;
+  plant_.InitializePosition(start_position, kHallEffectPosition);
+
+  while (elevator_.state() != Elevator::RUNNING) {
+    RunIteration();
+  }
+
+  EXPECT_TRUE(elevator_.CheckZeroed());
+  queue_.goal.MakeWithBuilder().height(0.5).Send();
+
+  // Find a reasonable value for the time.
+  RunForTime(Time::InSeconds(5));
+  VerifyNearGoal();
+}
+
+// Tests that a start position above the upper soft limit zeros correctly.
+TEST_F(ElevatorTest, AboveSoftLimitStart) {
+  const double start_position = (kElevUpperHardLimit + kElevUpperLimit) / 2.0;
+  plant_.InitializePosition(start_position, kHallEffectPosition);
+  while (elevator_.state() != Elevator::RUNNING) {
+    RunIteration();
+  }
+
+  EXPECT_TRUE(elevator_.CheckZeroed());
+  queue_.goal.MakeWithBuilder().height(0.5).Send();
+  RunForTime(Time::InSeconds(5));
+  VerifyNearGoal();
+}
+
+// Tests that a start position below the lower soft limit zeros correctly.
+TEST_F(ElevatorTest, BelowSoftLimitStart) {
+  const double start_position = (kElevLowerHardLimit + kElevLowerLimit) / 2;
+  plant_.InitializePosition(start_position, kHallEffectPosition);
+  while (elevator_.state() != Elevator::RUNNING) {
+    RunIteration();
+  }
+
+  EXPECT_TRUE(elevator_.CheckZeroed());
+  queue_.goal.MakeWithBuilder().height(0.4).Send();
+  RunForTime(Time::InSeconds(5));
+  VerifyNearGoal();
+}
+
+// Tests it zeroes when we start above the hall effect sensor.
+TEST_F(ElevatorTest, OverHallEffect) {
+  const double start_position = kHallEffectPosition;
+  plant_.InitializePosition(start_position, kHallEffectPosition);
+  while (elevator_.state() != Elevator::RUNNING) {
+    RunIteration();
+  }
+
+  EXPECT_TRUE(elevator_.CheckZeroed());
+  queue_.goal.MakeWithBuilder().height(0.4).Send();
+  RunForTime(Time::InSeconds(5));
+  VerifyNearGoal();
+}
+
+// Tests that we go down fast, up slow, and then get zeroed.
+TEST_F(ElevatorTest, DownAndUp) {
+  const double start_position = (kElevUpperLimit + kElevLowerLimit) / 2.0;
+  plant_.InitializePosition(start_position, kHallEffectPosition);
+
+  while (elevator_.state() != Elevator::RUNNING) {
+    RunIteration();
+  }
+
+  EXPECT_TRUE(elevator_.CheckZeroed());
+
+  // Make sure we ended off the hall effect.
+  queue_.position.FetchLatest();
+  EXPECT_TRUE(queue_.position.get() != nullptr);
+  EXPECT_FALSE(queue_.position->bottom_hall_effect);
+}
+
+// Verify that we can zero while disabled.
+TEST_F(ElevatorTest, ZeroWhileDisabled) {
+  const double start_position = (kElevUpperLimit + kElevLowerLimit) / 2.0;
+  plant_.InitializePosition(start_position, kHallEffectPosition);
+
+  // Running iteration while disabled
+  RunIteration(false);
+  RunIteration(false);
+
+  // Move elevator below hall effect.
+  plant_.MoveTo(kHallEffectPosition - 0.1);
+  RunIteration(false);
+  plant_.MoveTo(kHallEffectPosition - 0.1);
+  RunIteration(false);
+  // Make sure it only zeroes while going up.
+  EXPECT_TRUE(!elevator_.CheckZeroed());
+  // Move above the hall effect.
+  plant_.MoveTo(kHallEffectPosition + 0.1);
+  RunIteration(false);
+  RunIteration(false);
+  // Make sure we are zeroed.
+  EXPECT_TRUE(elevator_.CheckZeroed());
+}
+
+// Tests that the loop can reach a goal with a constant force.
+TEST_F(ElevatorTest, ReachesGoalWithIntegral) {
+  // Set a reasonable goal.
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder()
+                  .height(kElevLowerLimit + 0.5)
+                  .max_velocity(20)
+                  .max_acceleration(20)
+                  .Send());
+
+  plant_.set_acceleration_offset(0.1);
+  // Give it a lot of time to get there.
+  RunForTime(Time::InSeconds(5));
+
+  VerifyNearGoal();
+}
+
+// Tests that the goal (with motion profile) doesn't run away from the elevator
+TEST_F(ElevatorTest, PositiveRunawayProfileTest) {
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder().height(0.45).Send());
+
+  while (elevator_.state() != Elevator::RUNNING) {
+    RunIteration();
+  }
+
+  // Kick it.
+  RunForTime(Time::InMS(50));
+
+
+  double orig_goal = elevator_.goal_;
+  {
+    Eigen::Matrix<double, 2, 1> current;
+    current.setZero();
+    current << elevator_.goal_ + 100.0, elevator_.goal_velocity_;
+    elevator_.profile_.MoveCurrentState(current);
+  }
+  RunIteration();
+  EXPECT_NEAR(orig_goal, elevator_.goal_, 0.05);
+
+  RunIteration();
+  EXPECT_EQ(elevator_.loop_->U(), elevator_.loop_->U_uncapped());
+
+  EXPECT_EQ(elevator_.state(), Elevator::RUNNING);
+}
+
+// Tests that the goal (with motion profile) doesn't run away from the elevator
+TEST_F(ElevatorTest, NegativeRunawayProfileTest) {
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder().height(0.45).Send());
+
+  while (elevator_.state() != Elevator::RUNNING) {
+    RunIteration();
+  }
+
+  // Kick it.
+  RunForTime(Time::InMS(50));
+
+
+  double orig_goal = elevator_.goal_;
+  {
+    Eigen::Matrix<double, 2, 1> current;
+    current.setZero();
+    current << elevator_.goal_ - 100.0, elevator_.goal_velocity_;
+    elevator_.profile_.MoveCurrentState(current);
+  }
+  RunIteration();
+  EXPECT_NEAR(orig_goal, elevator_.goal_, 0.05);
+
+  RunIteration();
+  EXPECT_EQ(elevator_.loop_->U(), elevator_.loop_->U_uncapped());
+
+  EXPECT_EQ(elevator_.state(), Elevator::RUNNING);
+}
+
+// Tests that the glitch filter handles positive edges.
+TEST(GlitchFilterTest, PosedgeDetect) {
+  GlitchFilter filter;
+  filter.Reset(false);
+  EXPECT_FALSE(filter.filtered_value());
+  EXPECT_FALSE(filter.posedge());
+
+  filter.Update(false, 0.0);
+  EXPECT_FALSE(filter.filtered_value());
+  EXPECT_FALSE(filter.posedge());
+
+  filter.Update(true, 1.0);
+  EXPECT_FALSE(filter.filtered_value());
+  EXPECT_FALSE(filter.posedge());
+
+  filter.Update(true, 2.0);
+  EXPECT_TRUE(filter.filtered_value());
+  EXPECT_TRUE(filter.posedge());
+
+  filter.Update(true, 3.0);
+  EXPECT_TRUE(filter.filtered_value());
+  EXPECT_FALSE(filter.posedge());
+  EXPECT_EQ(0.5, filter.posedge_value());
+}
+
+// Tests that the glitch filter handles negative edges.
+TEST(GlitchFilterTest, NegedgeDetect) {
+  GlitchFilter filter;
+  filter.Reset(true);
+  EXPECT_TRUE(filter.filtered_value());
+  EXPECT_FALSE(filter.negedge());
+
+  filter.Update(true, 0.0);
+  EXPECT_TRUE(filter.filtered_value());
+  EXPECT_FALSE(filter.negedge());
+
+  filter.Update(false, 1.0);
+  EXPECT_TRUE(filter.filtered_value());
+  EXPECT_FALSE(filter.negedge());
+
+  filter.Update(false, 2.0);
+  EXPECT_FALSE(filter.filtered_value());
+  EXPECT_TRUE(filter.negedge());
+
+  filter.Update(false, 3.0);
+  EXPECT_FALSE(filter.filtered_value());
+  EXPECT_FALSE(filter.negedge());
+  EXPECT_EQ(0.5, filter.negedge_value());
+}
+
+// Motion Profile Tests
+
+
+// Makes sure low Accel. and TopSpeed don't output high voltage
+TEST_F(ElevatorTest, VeryLowMotionVeryLowVolt) {
+  while (elevator_.state() != Elevator::RUNNING) {
+    RunIteration();
+  }
+
+  // Height guarantees it's not the current position
+  queue_.goal.MakeWithBuilder()
+      .height(kElevUpperLimit)
+      .max_velocity(0.2)
+      .max_acceleration(0.2)
+      .Send();
+
+  // Checks voltage is not crazy
+  // Runs for enough time to move to position
+  const auto start_time = Time::Now();
+  const Time run_for = Time::InSeconds(5);
+  // Acceptable range for voltage
+  double voltage_range = 5.5;
+  while (Time::Now() < start_time + run_for) {
+    RunIteration(true);
+    EXPECT_NEAR(0.0, plant_.GetVoltage(), voltage_range);
+  }
+}
+
+// Makes sure low Accel. and TopSpeed don't output high voltage
+TEST_F(ElevatorTest, LowMotionLowVolt) {
+  while (elevator_.state() != Elevator::RUNNING) {
+    RunIteration();
+  }
+
+  // Height guarantees it's not the current position
+  queue_.goal.MakeWithBuilder()
+      .height(kElevUpperLimit)
+      .max_velocity(0.5)
+      .max_acceleration(0.5)
+      .Send();
+
+  // Checks voltage is not crazy
+  // Runs for enough time to move to position
+  const auto start_time = Time::Now();
+  const Time run_for = Time::InSeconds(5);
+  // Acceptable range for voltage
+  double voltage_range = 7.5;
+  while (Time::Now() < start_time + run_for) {
+    RunIteration(true);
+    EXPECT_NEAR(0.0, plant_.GetVoltage(), voltage_range);
+  }
+}
+
+}  // namespace testing
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/elevator/elevator_main.cc b/y2015_bot3/control_loops/elevator/elevator_main.cc
new file mode 100644
index 0000000..a6c95dd
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/elevator_main.cc
@@ -0,0 +1,11 @@
+#include "y2015_bot3/control_loops/elevator/elevator.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+  ::aos::Init();
+  ::y2015_bot3::control_loops::Elevator elevator;
+  elevator.Run();
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2015_bot3/control_loops/elevator/elevator_motor_plant.cc b/y2015_bot3/control_loops/elevator/elevator_motor_plant.cc
new file mode 100644
index 0000000..7fff4ff
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/elevator_motor_plant.cc
@@ -0,0 +1,49 @@
+#include "y2015_bot3/control_loops/elevator/elevator_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 1, 1> MakeElevatorPlantCoefficients() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 1.0, 0.00457884608813, 0.0, 0.836406580139;
+  Eigen::Matrix<double, 2, 1> B;
+  B << 5.90742803242e-05, 0.0229468687616;
+  Eigen::Matrix<double, 1, 2> C;
+  C << 1, 0;
+  Eigen::Matrix<double, 1, 1> D;
+  D << 0;
+  Eigen::Matrix<double, 1, 1> U_max;
+  U_max << 12.0;
+  Eigen::Matrix<double, 1, 1> U_min;
+  U_min << -12.0;
+  return StateFeedbackPlantCoefficients<2, 1, 1>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<2, 1, 1> MakeElevatorController() {
+  Eigen::Matrix<double, 2, 1> L;
+  L << 0.937593947018, 16.1192495093;
+  Eigen::Matrix<double, 1, 2> K;
+  K << 597.919635715, 17.5389953523;
+  Eigen::Matrix<double, 2, 2> A_inv;
+  A_inv << 1.0, -0.0054744261904, 0.0, 1.19559078533;
+  return StateFeedbackController<2, 1, 1>(L, K, A_inv, MakeElevatorPlantCoefficients());
+}
+
+StateFeedbackPlant<2, 1, 1> MakeElevatorPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 1, 1>>> plants(1);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 1, 1>>(new StateFeedbackPlantCoefficients<2, 1, 1>(MakeElevatorPlantCoefficients()));
+  return StateFeedbackPlant<2, 1, 1>(&plants);
+}
+
+StateFeedbackLoop<2, 1, 1> MakeElevatorLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<2, 1, 1>>> controllers(1);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<2, 1, 1>>(new StateFeedbackController<2, 1, 1>(MakeElevatorController()));
+  return StateFeedbackLoop<2, 1, 1>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/elevator/elevator_motor_plant.h b/y2015_bot3/control_loops/elevator/elevator_motor_plant.h
new file mode 100644
index 0000000..7be05e6
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/elevator_motor_plant.h
@@ -0,0 +1,20 @@
+#ifndef Y2015_BOT3_CONTROL_LOOPS_ELEVATOR_ELEVATOR_MOTOR_PLANT_H_
+#define Y2015_BOT3_CONTROL_LOOPS_ELEVATOR_ELEVATOR_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 1, 1> MakeElevatorPlantCoefficients();
+
+StateFeedbackController<2, 1, 1> MakeElevatorController();
+
+StateFeedbackPlant<2, 1, 1> MakeElevatorPlant();
+
+StateFeedbackLoop<2, 1, 1> MakeElevatorLoop();
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_CONTROL_LOOPS_ELEVATOR_ELEVATOR_MOTOR_PLANT_H_
diff --git a/y2015_bot3/control_loops/elevator/integral_elevator_motor_plant.cc b/y2015_bot3/control_loops/elevator/integral_elevator_motor_plant.cc
new file mode 100644
index 0000000..8573618
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/integral_elevator_motor_plant.cc
@@ -0,0 +1,49 @@
+#include "y2015_bot3/control_loops/elevator/integral_elevator_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<3, 1, 1> MakeIntegralElevatorPlantCoefficients() {
+  Eigen::Matrix<double, 3, 3> A;
+  A << 1.0, 0.00457884608813, 5.90742803242e-05, 0.0, 0.836406580139, 0.0229468687616, 0.0, 0.0, 1.0;
+  Eigen::Matrix<double, 3, 1> B;
+  B << 5.90742803242e-05, 0.0229468687616, 0.0;
+  Eigen::Matrix<double, 1, 3> C;
+  C << 1.0, 0.0, 0.0;
+  Eigen::Matrix<double, 1, 1> D;
+  D << 0;
+  Eigen::Matrix<double, 1, 1> U_max;
+  U_max << 12.0;
+  Eigen::Matrix<double, 1, 1> U_min;
+  U_min << -12.0;
+  return StateFeedbackPlantCoefficients<3, 1, 1>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<3, 1, 1> MakeIntegralElevatorController() {
+  Eigen::Matrix<double, 3, 1> L;
+  L << 0.897632535808, 18.4574278406, 53.6443529697;
+  Eigen::Matrix<double, 1, 3> K;
+  K << 597.919635715, 17.5389953523, 1.0;
+  Eigen::Matrix<double, 3, 3> A_inv;
+  A_inv << 1.0, -0.0054744261904, 6.65466590119e-05, 0.0, 1.19559078533, -0.0274350648434, 0.0, 0.0, 1.0;
+  return StateFeedbackController<3, 1, 1>(L, K, A_inv, MakeIntegralElevatorPlantCoefficients());
+}
+
+StateFeedbackPlant<3, 1, 1> MakeIntegralElevatorPlant() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<3, 1, 1>>> plants(1);
+  plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<3, 1, 1>>(new StateFeedbackPlantCoefficients<3, 1, 1>(MakeIntegralElevatorPlantCoefficients()));
+  return StateFeedbackPlant<3, 1, 1>(&plants);
+}
+
+StateFeedbackLoop<3, 1, 1> MakeIntegralElevatorLoop() {
+  ::std::vector< ::std::unique_ptr<StateFeedbackController<3, 1, 1>>> controllers(1);
+  controllers[0] = ::std::unique_ptr<StateFeedbackController<3, 1, 1>>(new StateFeedbackController<3, 1, 1>(MakeIntegralElevatorController()));
+  return StateFeedbackLoop<3, 1, 1>(&controllers);
+}
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/elevator/integral_elevator_motor_plant.h b/y2015_bot3/control_loops/elevator/integral_elevator_motor_plant.h
new file mode 100644
index 0000000..553c0c3
--- /dev/null
+++ b/y2015_bot3/control_loops/elevator/integral_elevator_motor_plant.h
@@ -0,0 +1,20 @@
+#ifndef Y2015_BOT3_CONTROL_LOOPS_ELEVATOR_INTEGRAL_ELEVATOR_MOTOR_PLANT_H_
+#define Y2015_BOT3_CONTROL_LOOPS_ELEVATOR_INTEGRAL_ELEVATOR_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<3, 1, 1> MakeIntegralElevatorPlantCoefficients();
+
+StateFeedbackController<3, 1, 1> MakeIntegralElevatorController();
+
+StateFeedbackPlant<3, 1, 1> MakeIntegralElevatorPlant();
+
+StateFeedbackLoop<3, 1, 1> MakeIntegralElevatorLoop();
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_CONTROL_LOOPS_ELEVATOR_INTEGRAL_ELEVATOR_MOTOR_PLANT_H_
diff --git a/y2015_bot3/control_loops/intake/BUILD b/y2015_bot3/control_loops/intake/BUILD
new file mode 100644
index 0000000..fe21b7f
--- /dev/null
+++ b/y2015_bot3/control_loops/intake/BUILD
@@ -0,0 +1,53 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+queue_library(
+  name = 'intake_queue',
+  srcs = [
+    'intake.q',
+  ],
+  deps = [
+    '//aos/common/controls:control_loop_queues',
+  ],
+)
+
+cc_library(
+  name = 'intake_lib',
+  srcs = [
+    'intake.cc',
+  ],
+  hdrs = [
+    'intake.h',
+  ],
+  deps = [
+    ':intake_queue',
+    '//aos/common/controls:control_loop',
+  ],
+)
+
+cc_test(
+  name = 'intake_lib_test',
+  srcs = [
+    'intake_lib_test.cc',
+  ],
+  deps = [
+    '//third_party/googletest',
+    ':intake_lib',
+    '//frc971/control_loops:state_feedback_loop',
+    '//aos/common/controls:control_loop_test',
+    '//aos/common:time',
+    '//frc971/control_loops:team_number_test_environment',
+  ],
+)
+
+cc_binary(
+  name = 'intake',
+  srcs = [
+    'intake_main.cc',
+  ],
+  deps = [
+    '//aos/linux_code:init',
+    ':intake_lib',
+  ],
+)
diff --git a/y2015_bot3/control_loops/intake/intake.cc b/y2015_bot3/control_loops/intake/intake.cc
new file mode 100644
index 0000000..51bab21
--- /dev/null
+++ b/y2015_bot3/control_loops/intake/intake.cc
@@ -0,0 +1,30 @@
+#include "y2015_bot3/control_loops/intake/intake.h"
+
+#include "y2015_bot3/control_loops/intake/intake.q.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+Intake::Intake(control_loops::IntakeQueue *intake)
+    : aos::controls::ControlLoop<control_loops::IntakeQueue>(intake) {}
+
+void Intake::RunIteration(
+    const control_loops::IntakeQueue::Goal *goal,
+    const control_loops::IntakeQueue::Position * /*position*/,
+    control_loops::IntakeQueue::Output *output,
+    control_loops::IntakeQueue::Status * /*status*/) {
+  if (output != nullptr) {
+    output->Zero();
+
+    if (goal != nullptr) {
+      output->intake = goal->movement;
+      output->claw_closed = goal->claw_closed;
+    } else {
+      output->intake = 0.0;
+      output->claw_closed = false;
+    }
+  }
+}
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/intake/intake.gyp b/y2015_bot3/control_loops/intake/intake.gyp
new file mode 100644
index 0000000..41f1b7f
--- /dev/null
+++ b/y2015_bot3/control_loops/intake/intake.gyp
@@ -0,0 +1,60 @@
+{
+  'targets': [
+    {
+      'target_name': 'intake_queue',
+      'type': 'static_library',
+      'sources': ['intake.q'],
+      'variables': {
+        'header_path': 'bot3/control_loops/intake',
+      },
+      'dependencies': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+      ],
+      'includes': ['../../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'intake_lib',
+      'type': 'static_library',
+      'sources': [
+        'intake.cc',
+      ],
+      'dependencies': [
+        'intake_queue',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+      ],
+      'export_dependent_settings': [
+        'intake_queue',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+      ],
+    },
+    {
+      'target_name': 'intake_lib_test',
+      'type': 'executable',
+      'sources': [
+        'intake_lib_test.cc',
+      ],
+      'dependencies': [
+        '<(EXTERNALS):gtest',
+        'intake_lib',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(AOS)/common/controls/controls.gyp:control_loop_test',
+        '<(AOS)/common/common.gyp:time',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:team_number_test_environment',
+      ],
+    },
+    {
+      'target_name': 'intake',
+      'type': 'executable',
+      'sources': [
+        'intake_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        'intake_lib',
+      ],
+    },
+  ],
+}
diff --git a/y2015_bot3/control_loops/intake/intake.h b/y2015_bot3/control_loops/intake/intake.h
new file mode 100644
index 0000000..120b0a3
--- /dev/null
+++ b/y2015_bot3/control_loops/intake/intake.h
@@ -0,0 +1,28 @@
+#ifndef Y2015_BOT3_CONTROL_LOOPS_INTAKE_H_
+#define Y2015_BOT3_CONTROL_LOOPS_INTAKE_H_
+
+#include "aos/common/controls/control_loop.h"
+
+#include "y2015_bot3/control_loops/intake/intake.q.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+constexpr double kIntakeVoltageFullPower = 12.0;
+
+class Intake : public aos::controls::ControlLoop<control_loops::IntakeQueue> {
+ public:
+  explicit Intake(
+      control_loops::IntakeQueue *intake_queue = &control_loops::intake_queue);
+
+ protected:
+  void RunIteration(const control_loops::IntakeQueue::Goal *goal,
+                    const control_loops::IntakeQueue::Position *position,
+                    control_loops::IntakeQueue::Output *output,
+                    control_loops::IntakeQueue::Status *status) override;
+};
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_CONTROL_LOOPS_INTAKE_H_
diff --git a/y2015_bot3/control_loops/intake/intake.q b/y2015_bot3/control_loops/intake/intake.q
new file mode 100644
index 0000000..f778231
--- /dev/null
+++ b/y2015_bot3/control_loops/intake/intake.q
@@ -0,0 +1,32 @@
+package y2015_bot3.control_loops;
+
+import "aos/common/controls/control_loops.q";
+
+queue_group IntakeQueue {
+  implements aos.control_loops.ControlLoop;
+
+  message Goal {
+    // Units: volts
+    double movement;
+
+    bool claw_closed;
+  };
+
+  message Position {};
+
+  message Output {
+    // Positive or negative, depending on whether we're sucking or spitting.
+    double intake;
+
+    bool claw_closed;
+  };
+
+  message Status {};
+
+  queue Goal goal;
+  queue Position position;
+  queue Output output;
+  queue Status status;
+};
+
+queue_group IntakeQueue intake_queue;
diff --git a/y2015_bot3/control_loops/intake/intake_lib_test.cc b/y2015_bot3/control_loops/intake/intake_lib_test.cc
new file mode 100644
index 0000000..6d598fe
--- /dev/null
+++ b/y2015_bot3/control_loops/intake/intake_lib_test.cc
@@ -0,0 +1,121 @@
+#include "y2015_bot3/control_loops/intake/intake.h"
+
+#include <math.h>
+#include <unistd.h>
+
+#include "gtest/gtest.h"
+#include "aos/common/queue.h"
+#include "aos/common/controls/control_loop_test.h"
+#include "y2015_bot3/control_loops/intake/intake.q.h"
+
+using ::aos::time::Time;
+
+namespace y2015_bot3 {
+namespace control_loops {
+namespace testing {
+
+// Class which simulates the elevator and sends out queue messages with the
+// position.
+class IntakeSimulation {
+ public:
+  // Constructs a simulation.
+  IntakeSimulation()
+      : queue_(".y2015_bot3.control_loops.intake_queue", 0x627ceeeb,
+               ".y2015_bot3.control_loops.intake_queue.goal",
+               ".y2015_bot3.control_loops.intake_queue.position",
+               ".y2015_bot3.control_loops.intake_queue.output",
+               ".y2015_bot3.control_loops.intake_queue.status") {}
+
+  // Simulates for a single timestep.
+  void Simulate() {
+    EXPECT_TRUE(queue_.output.FetchLatest());
+  }
+
+ private:
+  IntakeQueue queue_;
+};
+
+class IntakeTest : public ::aos::testing::ControlLoopTest {
+ protected:
+  IntakeTest()
+      : queue_(".y2015_bot3.control_loops.intake_queue", 0x627ceeeb,
+               ".y2015_bot3.control_loops.intake_queue.goal",
+               ".y2015_bot3.control_loops.intake_queue.position",
+               ".y2015_bot3.control_loops.intake_queue.output",
+               ".y2015_bot3.control_loops.intake_queue.status"),
+        intake_(&queue_),
+        plant_() {
+    set_team_id(971);
+  }
+
+  // Runs one iteration of the whole simulation.
+  void RunIteration(bool enabled = true) {
+    SendMessages(enabled);
+
+    queue_.position.MakeMessage().Send();
+
+    intake_.Iterate();
+
+    TickTime();
+  }
+
+  // Runs iterations until the specified amount of simulated time has elapsed.
+  void RunForTime(const Time &run_for, bool enabled = true) {
+    const auto start_time = Time::Now();
+    while (Time::Now() < start_time + run_for) {
+      RunIteration(enabled);
+    }
+  }
+
+  // Create a new instance of the test queue so that it invalidates the queue
+  // that it points to. Otherwise, we will have a pointed to shared memory that
+  // is no longer valid.
+  IntakeQueue queue_;
+
+  // Create a control loop.
+  Intake intake_;
+  IntakeSimulation plant_;
+};
+
+// Tests that the loop does nothing when the goal is zero.
+TEST_F(IntakeTest, DoesNothing) {
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder()
+                  .movement(0)
+                  .Send());
+
+  // Run for a bit.
+  RunForTime(1.0);
+
+  ASSERT_TRUE(queue_.output.FetchLatest());
+  EXPECT_EQ(queue_.output->intake, 0.0);
+}
+
+// Tests that the intake sucks with a positive goal.
+TEST_F(IntakeTest, SuckingGoal) {
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder()
+                  .movement(1)
+                  .Send());
+
+  // Run for a bit.
+  RunForTime(1.0);
+
+  ASSERT_TRUE(queue_.output.FetchLatest());
+  EXPECT_GT(queue_.output->intake, 0.0);
+}
+
+// Tests that the intake spits with a negative goal.
+TEST_F(IntakeTest, SpittingGoal) {
+  ASSERT_TRUE(queue_.goal.MakeWithBuilder()
+                  .movement(-1)
+                  .Send());
+
+  // Run for a bit.
+  RunForTime(1.0);
+
+  ASSERT_TRUE(queue_.output.FetchLatest());
+  EXPECT_LT(queue_.output->intake, 0.0);
+}
+
+}  // namespace testing
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/intake/intake_main.cc b/y2015_bot3/control_loops/intake/intake_main.cc
new file mode 100644
index 0000000..095460d
--- /dev/null
+++ b/y2015_bot3/control_loops/intake/intake_main.cc
@@ -0,0 +1,11 @@
+#include "y2015_bot3/control_loops/intake/intake.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+  ::aos::Init();
+  ::y2015_bot3::control_loops::Intake intake;
+  intake.Run();
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/y2015_bot3/control_loops/position_sensor_sim.cc b/y2015_bot3/control_loops/position_sensor_sim.cc
new file mode 100644
index 0000000..9562a3f
--- /dev/null
+++ b/y2015_bot3/control_loops/position_sensor_sim.cc
@@ -0,0 +1,28 @@
+#include "y2015_bot3/control_loops/position_sensor_sim.h"
+
+#include <cmath>
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+void PositionSensorSimulator::Initialize(double start_position,
+                                         double hall_effect_position) {
+  hall_effect_position_ = hall_effect_position;
+  start_position_ = start_position;
+  cur_pos_ = start_position;
+}
+
+void PositionSensorSimulator::MoveTo(double new_pos) { cur_pos_ = new_pos; }
+
+void PositionSensorSimulator::GetSensorValues(
+    control_loops::ElevatorQueue::Position* position) {
+  position->encoder = cur_pos_ - start_position_;
+  if (cur_pos_ <= hall_effect_position_) {
+    position->bottom_hall_effect = true;
+  } else {
+    position->bottom_hall_effect = false;
+  }
+}
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
diff --git a/y2015_bot3/control_loops/position_sensor_sim.h b/y2015_bot3/control_loops/position_sensor_sim.h
new file mode 100644
index 0000000..f4bf56c
--- /dev/null
+++ b/y2015_bot3/control_loops/position_sensor_sim.h
@@ -0,0 +1,47 @@
+#ifndef Y2015_BOT3_CONTROL_LOOPS_POSITION_SENSOR_SIM_H_
+#define Y2015_BOT3_CONTROL_LOOPS_POSITION_SENSOR_SIM_H_
+
+#include "y2015_bot3/control_loops/elevator/elevator.q.h"
+
+namespace y2015_bot3 {
+namespace control_loops {
+
+// NOTE: All encoder values in this class are assumed to be in
+// translated SI units.
+
+class PositionSensorSimulator {
+ public:
+
+  // Set new parameters for the sensors. This is useful for unit tests to change
+  // the simulated sensors' behavior on the fly.
+  // start_position: The position relative to absolute zero where the simulated
+  //                 structure starts. For example, to simulate the elevator
+  //                 starting at 40cm above absolute zero, set this to 0.4.
+  void Initialize(double start_position, double hall_effect_position);
+
+  // Simulate the structure moving to a new position. The new value is measured
+  // relative to absolute zero. This will update the simulated sensors with new
+  // readings.
+  // new_position: The new position relative to absolute zero.
+  void MoveTo(double new_position);
+
+  // Get the current values of the simulated sensors.
+  // values: The target structure will be populated with simulated sensor
+  //         readings. The readings will be in SI units. For example the units
+  //         can be given in radians, meters, etc.
+  void GetSensorValues(control_loops::ElevatorQueue::Position* position);
+
+ private:
+  // the position of the bottom hall effect sensor.
+  double hall_effect_position_;
+  // Current position of the mechanism relative to absolute zero.
+  double cur_pos_;
+  // Starting position of the mechanism relative to absolute zero. See the
+  // `starting_position` parameter in the constructor for more info.
+  double start_position_;
+};
+
+}  // namespace control_loops
+}  // namespace y2015_bot3
+
+#endif  // Y2015_BOT3_CONTROL_LOOPS_POSITION_SENSOR_SIM_H_
diff --git a/y2015_bot3/control_loops/python/controls.py b/y2015_bot3/control_loops/python/controls.py
new file mode 100755
index 0000000..b66bd56
--- /dev/null
+++ b/y2015_bot3/control_loops/python/controls.py
@@ -0,0 +1,153 @@
+#!/usr/bin/python
+
+"""
+Control loop pole placement library.
+
+This library will grow to support many different pole placement methods.
+Currently it only supports direct pole placement.
+"""
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+import numpy
+import slycot
+import scipy.signal.cont2discrete
+
+class Error (Exception):
+  """Base class for all control loop exceptions."""
+
+
+class PolePlacementError(Error):
+  """Exception raised when pole placement fails."""
+
+
+# TODO(aschuh): dplace should take a control system object.
+# There should also exist a function to manipulate laplace expressions, and
+# something to plot bode plots and all that.
+def dplace(A, B, poles, alpha=1e-6):
+  """Set the poles of (A - BF) to poles.
+
+  Args:
+    A: numpy.matrix(n x n), The A matrix.
+    B: numpy.matrix(n x m), The B matrix.
+    poles: array(imaginary numbers), The poles to use.  Complex conjugates poles
+      must be in pairs.
+
+  Raises:
+    ValueError: Arguments were the wrong shape or there were too many poles.
+    PolePlacementError: Pole placement failed.
+
+  Returns:
+    numpy.matrix(m x n), K
+  """
+  # See http://www.icm.tu-bs.de/NICONET/doc/SB01BD.html for a description of the
+  # fortran code that this is cleaning up the interface to.
+  n = A.shape[0]
+  if A.shape[1] != n:
+    raise ValueError("A must be square")
+  if B.shape[0] != n:
+    raise ValueError("B must have the same number of states as A.")
+  m = B.shape[1]
+
+  num_poles = len(poles)
+  if num_poles > n:
+    raise ValueError("Trying to place more poles than states.")
+
+  out = slycot.sb01bd(n=n,
+                      m=m,
+                      np=num_poles,
+                      alpha=alpha,
+                      A=A,
+                      B=B,
+                      w=numpy.array(poles),
+                      dico='D')
+
+  A_z = numpy.matrix(out[0])
+  num_too_small_eigenvalues = out[2]
+  num_assigned_eigenvalues = out[3]
+  num_uncontrollable_eigenvalues = out[4]
+  K = numpy.matrix(-out[5])
+  Z = numpy.matrix(out[6])
+
+  if num_too_small_eigenvalues != 0:
+    raise PolePlacementError("Number of eigenvalues that are too small "
+                             "and are therefore unmodified is %d." %
+                             num_too_small_eigenvalues)
+  if num_assigned_eigenvalues != num_poles:
+    raise PolePlacementError("Did not place all the eigenvalues that were "
+                             "requested. Only placed %d eigenvalues." %
+                             num_assigned_eigenvalues)
+  if num_uncontrollable_eigenvalues != 0:
+    raise PolePlacementError("Found %d uncontrollable eigenvlaues." %
+                             num_uncontrollable_eigenvalues)
+
+  return K
+
+
+def c2d(A, B, dt):
+  """Converts from continuous time state space representation to discrete time.
+     Returns (A, B).  C and D are unchanged."""
+
+  ans_a, ans_b, _, _, _ = scipy.signal.cont2discrete((A, B, None, None), dt)
+  return numpy.matrix(ans_a), numpy.matrix(ans_b)
+
+def ctrb(A, B):
+  """Returns the controlability matrix.
+
+    This matrix must have full rank for all the states to be controlable.
+  """
+  n = A.shape[0]
+  output = B
+  intermediate = B
+  for i in xrange(0, n):
+    intermediate = A * intermediate
+    output = numpy.concatenate((output, intermediate), axis=1)
+
+  return output
+
+def dlqr(A, B, Q, R):
+  """Solves for the optimal lqr controller.
+
+    x(n+1) = A * x(n) + B * u(n)
+    J = sum(0, inf, x.T * Q * x + u.T * R * u)
+  """
+
+  # P = (A.T * P * A) - (A.T * P * B * numpy.linalg.inv(R + B.T * P *B) * (A.T * P.T * B).T + Q
+
+  P, rcond, w, S, T = slycot.sb02od(
+      n=A.shape[0], m=B.shape[1], A=A, B=B, Q=Q, R=R, dico='D')
+
+  F = numpy.linalg.inv(R + B.T * P *B) * B.T * P * A
+  return F
+
+def kalman(A, B, C, Q, R):
+  """Solves for the steady state kalman gain and covariance matricies.
+
+    Args:
+      A, B, C: SS matricies.
+      Q: The model uncertantity
+      R: The measurement uncertainty
+
+    Returns:
+      KalmanGain, Covariance.
+  """
+  P = Q
+
+  I = numpy.matrix(numpy.eye(P.shape[0]))
+  At = A.T
+  Ct = C.T
+  i = 0
+
+  while True:
+    last_P = P
+    P_prior = A * P * At + Q
+    S = C * P_prior * Ct + R
+    K = P_prior * Ct * numpy.linalg.inv(S)
+    P = (I - K * C) * P_prior
+
+    diff = P - last_P
+    i += 1
+    if numpy.linalg.norm(diff) / numpy.linalg.norm(P) < 1e-9:
+      break
+
+  return K, P
diff --git a/y2015_bot3/control_loops/python/drivetrain.py b/y2015_bot3/control_loops/python/drivetrain.py
new file mode 100755
index 0000000..9742167
--- /dev/null
+++ b/y2015_bot3/control_loops/python/drivetrain.py
@@ -0,0 +1,243 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import numpy
+import sys
+from matplotlib import pylab
+
+
+class CIM(control_loop.ControlLoop):
+  def __init__(self):
+    super(CIM, self).__init__("CIM")
+    # Stall Torque in N m
+    self.stall_torque = 2.42
+    # Stall Current in Amps
+    self.stall_current = 133
+    # Free Speed in RPM
+    self.free_speed = 4650.0
+    # Free Current in Amps
+    self.free_current = 2.7
+    # Moment of inertia of the CIM in kg m^2
+    self.J = 0.0001
+    # Resistance of the motor, divided by 2 to account for the 2 motors
+    self.R = 12.0 / self.stall_current
+    # Motor velocity constant
+    self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
+              (12.0 - self.R * self.free_current))
+    # Torque constant
+    self.Kt = self.stall_torque / self.stall_current
+    # Control loop time step
+    self.dt = 0.005
+
+    # State feedback matrices
+    self.A_continuous = numpy.matrix(
+        [[-self.Kt / self.Kv / (self.J * self.R)]])
+    self.B_continuous = numpy.matrix(
+        [[self.Kt / (self.J * self.R)]])
+    self.C = numpy.matrix([[1]])
+    self.D = numpy.matrix([[0]])
+
+    self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+                                               self.B_continuous, self.dt)
+
+    self.PlaceControllerPoles([0.01])
+    self.PlaceObserverPoles([0.01])
+
+    self.U_max = numpy.matrix([[12.0]])
+    self.U_min = numpy.matrix([[-12.0]])
+
+    self.InitializeState()
+
+
+class Drivetrain(control_loop.ControlLoop):
+  def __init__(self, name="Drivetrain", left_low=True, right_low=True):
+    super(Drivetrain, self).__init__(name)
+    # Stall Torque in N m
+    self.stall_torque = 2.42
+    # Stall Current in Amps
+    self.stall_current = 133.0
+    # Free Speed in RPM. Used number from last year.
+    self.free_speed = 4650.0
+    # Free Current in Amps
+    self.free_current = 2.7
+    # Moment of inertia of the drivetrain in kg m^2
+    # Just borrowed from last year.
+    self.J = 10
+    # Mass of the robot, in kg.
+    self.m = 68
+    # Radius of the robot, in meters (from last year).
+    self.rb = 0.9603 / 2.0
+    # Radius of the wheels, in meters.
+    self.r = 0.0508
+    # Resistance of the motor, divided by the number of motors.
+    self.R = 12.0 / self.stall_current / 2
+    # Motor velocity constant
+    self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
+               (12.0 - self.R * self.free_current))
+    # Torque constant
+    self.Kt = self.stall_torque / self.stall_current
+    # Gear ratios
+    self.G_const = 18.0 / 44.0 * 18.0 / 60.0
+
+    self.G_low = self.G_const
+    self.G_high = self.G_const
+
+    if left_low:
+      self.Gl = self.G_low
+    else:
+      self.Gl = self.G_high
+    if right_low:
+      self.Gr = self.G_low
+    else:
+      self.Gr = self.G_high
+
+    # Control loop time step
+    self.dt = 0.005
+
+    # These describe the way that a given side of a robot will be influenced
+    # by the other side. Units of 1 / kg.
+    self.msp = 1.0 / self.m + self.rb * self.rb / self.J
+    self.msn = 1.0 / self.m - self.rb * self.rb / self.J
+    # The calculations which we will need for A and B.
+    self.tcl = -self.Kt / self.Kv / (self.Gl * self.Gl * self.R * self.r * self.r)
+    self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.R * self.r * self.r)
+    self.mpl = self.Kt / (self.Gl * self.R * self.r)
+    self.mpr = self.Kt / (self.Gr * self.R * self.r)
+
+    # State feedback matrices
+    # X will be of the format
+    # [[positionl], [velocityl], [positionr], velocityr]]
+    self.A_continuous = numpy.matrix(
+        [[0, 1, 0, 0],
+         [0, self.msp * self.tcl, 0, self.msn * self.tcr],
+         [0, 0, 0, 1],
+         [0, self.msn * self.tcl, 0, self.msp * self.tcr]])
+    self.B_continuous = numpy.matrix(
+        [[0, 0],
+         [self.msp * self.mpl, self.msn * self.mpr],
+         [0, 0],
+         [self.msn * self.mpl, self.msp * self.mpr]])
+    self.C = numpy.matrix([[1, 0, 0, 0],
+                           [0, 0, 1, 0]])
+    self.D = numpy.matrix([[0, 0],
+                           [0, 0]])
+
+    #print "THE NUMBER I WANT" + str(numpy.linalg.inv(self.A_continuous) * -self.B_continuous * numpy.matrix([[12.0], [12.0]]))
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    # Poles from last year.
+    self.hp = 0.65
+    self.lp = 0.83
+    self.PlaceControllerPoles([self.hp, self.lp, self.hp, self.lp])
+    print self.K
+    q_pos = 0.07
+    q_vel = 1.0
+    self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
+                           [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
+                           [0.0, 0.0, (1.0 / (q_pos ** 2.0)), 0.0],
+                           [0.0, 0.0, 0.0, (1.0 / (q_vel ** 2.0))]])
+
+    self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
+                           [0.0, (1.0 / (12.0 ** 2.0))]])
+    self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+    print self.A
+    print self.B
+    print self.K
+    print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+    self.hlp = 0.3
+    self.llp = 0.4
+    self.PlaceObserverPoles([self.hlp, self.hlp, self.llp, self.llp])
+
+    self.U_max = numpy.matrix([[12.0], [12.0]])
+    self.U_min = numpy.matrix([[-12.0], [-12.0]])
+    self.InitializeState()
+
+def main(argv):
+  # Simulate the response of the system to a step input.
+  drivetrain = Drivetrain()
+  simulated_left = []
+  simulated_right = []
+  for _ in xrange(100):
+    drivetrain.Update(numpy.matrix([[12.0], [12.0]]))
+    simulated_left.append(drivetrain.X[0, 0])
+    simulated_right.append(drivetrain.X[2, 0])
+
+  #pylab.plot(range(100), simulated_left)
+  #pylab.plot(range(100), simulated_right)
+  #pylab.show()
+
+  # Simulate forwards motion.
+  drivetrain = Drivetrain()
+  close_loop_left = []
+  close_loop_right = []
+  R = numpy.matrix([[1.0], [0.0], [1.0], [0.0]])
+  for _ in xrange(100):
+    U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
+                   drivetrain.U_min, drivetrain.U_max)
+    drivetrain.UpdateObserver(U)
+    drivetrain.Update(U)
+    close_loop_left.append(drivetrain.X[0, 0])
+    close_loop_right.append(drivetrain.X[2, 0])
+
+  #pylab.plot(range(100), close_loop_left)
+  #pylab.plot(range(100), close_loop_right)
+  #pylab.show()
+
+  # Try turning in place
+  drivetrain = Drivetrain()
+  close_loop_left = []
+  close_loop_right = []
+  R = numpy.matrix([[-1.0], [0.0], [1.0], [0.0]])
+  for _ in xrange(100):
+    U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
+                   drivetrain.U_min, drivetrain.U_max)
+    drivetrain.UpdateObserver(U)
+    drivetrain.Update(U)
+    close_loop_left.append(drivetrain.X[0, 0])
+    close_loop_right.append(drivetrain.X[2, 0])
+
+  #pylab.plot(range(100), close_loop_left)
+  #pylab.plot(range(100), close_loop_right)
+  #pylab.show()
+
+  # Try turning just one side.
+  drivetrain = Drivetrain()
+  close_loop_left = []
+  close_loop_right = []
+  R = numpy.matrix([[0.0], [0.0], [1.0], [0.0]])
+  for _ in xrange(100):
+    U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
+                   drivetrain.U_min, drivetrain.U_max)
+    drivetrain.UpdateObserver(U)
+    drivetrain.Update(U)
+    close_loop_left.append(drivetrain.X[0, 0])
+    close_loop_right.append(drivetrain.X[2, 0])
+
+  #pylab.plot(range(100), close_loop_left)
+  #pylab.plot(range(100), close_loop_right)
+  #pylab.show()
+
+  # Write the generated constants out to a file.
+  print "Output one"
+  drivetrain_low_low = Drivetrain(name="DrivetrainLowLow", left_low=True, right_low=True)
+  drivetrain_low_high = Drivetrain(name="DrivetrainLowHigh", left_low=True, right_low=False)
+  drivetrain_high_low = Drivetrain(name="DrivetrainHighLow", left_low=False, right_low=True)
+  drivetrain_high_high = Drivetrain(name="DrivetrainHighHigh", left_low=False, right_low=False)
+
+  if len(argv) != 5:
+    print "Expected .h file name and .cc file name"
+  else:
+    dog_loop_writer = control_loop.ControlLoopWriter(
+        "Drivetrain", [drivetrain_low_low, drivetrain_low_high,
+                       drivetrain_high_low, drivetrain_high_high],
+        namespaces=['y2015_bot3', 'control_loops'])
+    if argv[1][-3:] == '.cc':
+      dog_loop_writer.Write(argv[2], argv[1])
+    else:
+      dog_loop_writer.Write(argv[1], argv[2])
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/y2015_bot3/control_loops/python/elevator3.py b/y2015_bot3/control_loops/python/elevator3.py
new file mode 100755
index 0000000..853b6b3
--- /dev/null
+++ b/y2015_bot3/control_loops/python/elevator3.py
@@ -0,0 +1,283 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import numpy
+import sys
+import matplotlib
+from matplotlib import pylab
+
+class Elevator(control_loop.ControlLoop):
+  def __init__(self, name="Elevator", mass=None):
+    super(Elevator, self).__init__(name)
+    # Stall Torque in N m
+    self.stall_torque = 2.402
+    # Stall Current in Amps
+    self.stall_current = 126.145
+    # Free Speed in RPM
+    self.free_speed = 5015.562
+    # Free Current in Amps
+    self.free_current = 1.170
+    # Mass of the Elevator
+    if mass is None:
+      self.mass = 5.0
+    else:
+      self.mass = mass
+
+    # Number of motors
+    self.num_motors = 2.0
+    # Resistance of the motor
+    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.num_motors * self.stall_torque) / self.stall_current
+    # Gear ratio
+    self.G = 8
+    # Radius of pulley
+    self.r = 0.0254
+
+    # Control loop time step
+    self.dt = 0.005
+
+    # State is [position, velocity]
+    # Input is [Voltage]
+
+    C1 = self.Kt * self.G * self.G / (self.Kv * self.resistance * self.r * self.r * self.mass)
+    C2 = self.G * self.Kt / (self.resistance * self.r * self.mass)
+
+    self.A_continuous = numpy.matrix(
+        [[0, 1],
+         [0, -C1]])
+
+    # Start with the unmodified input
+    self.B_continuous = numpy.matrix(
+        [[0],
+         [C2]])
+
+    self.C = numpy.matrix([[1, 0]])
+    self.D = numpy.matrix([[0]])
+    
+    self.A, self.B = self.ContinuousToDiscrete(
+        self.A_continuous, self.B_continuous, self.dt)
+
+    controlability = controls.ctrb(self.A, self.B)
+
+    q_pos = 0.015
+    q_vel = 0.5
+    self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0],
+                           [0.0, (1.0 / (q_vel ** 2.0))]])
+
+    self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0))]])
+    self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+
+    print 'K', self.K
+    print 'Poles are', numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+    self.rpl = 0.30
+    self.ipl = 0.10
+    self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+                             self.rpl - 1j * self.ipl])
+
+    #    print 'L is', self.L
+
+    q_pos = 0.05
+    q_vel = 2.65
+    self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0],
+                           [0.0, (q_vel ** 2.0)]])
+
+    r_volts = 0.025
+    self.R = numpy.matrix([[(r_volts ** 2.0)]])
+
+    self.KalmanGain, self.Q_steady = controls.kalman(
+        A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+    #    print 'Kal', self.KalmanGain
+    self.L = self.A * self.KalmanGain
+    print 'KalL is', self.L
+
+    # The box formed by U_min and U_max must encompass all possible values,
+    # or else Austin's code gets angry.
+    self.U_max = numpy.matrix([[12.0]])
+    self.U_min = numpy.matrix([[-12.0]])
+
+    self.InitializeState()
+
+class IntegralElevator(Elevator):
+  def __init__(self, name="IntegralElevator", mass=None):
+    super(IntegralElevator, self).__init__(name=name, mass=mass)
+
+    self.A_continuous_unaugmented = self.A_continuous
+    self.B_continuous_unaugmented = self.B_continuous
+
+    self.A_continuous = numpy.matrix(numpy.zeros((3, 3)))
+    self.A_continuous[0:2, 0:2] = self.A_continuous_unaugmented
+    self.A_continuous[0:2, 2] = self.B_continuous_unaugmented
+
+    self.B_continuous = numpy.matrix(numpy.zeros((3, 1)))
+    self.B_continuous[0:2, 0] = self.B_continuous_unaugmented
+
+    self.C_unaugmented = self.C
+    self.C = numpy.matrix(numpy.zeros((1, 3)))
+    self.C[0:1, 0:2] = self.C_unaugmented
+
+    self.A, self.B = self.ContinuousToDiscrete(self.A_continuous, self.B_continuous, self.dt)
+
+    q_pos = 0.08
+    q_vel = 4.00
+    q_voltage = 6.0
+    self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0],
+                           [0.0, (q_vel ** 2.0), 0.0],
+                           [0.0, 0.0, (q_voltage ** 2.0)]])
+
+    r_pos = 0.05
+    self.R = numpy.matrix([[(r_pos ** 2.0)]])
+
+    self.KalmanGain, self.Q_steady = controls.kalman(
+        A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+    self.L = self.A * self.KalmanGain
+
+    self.K_unaugmented = self.K
+    self.K = numpy.matrix(numpy.zeros((1, 3)))
+    self.K[0, 0:2] = self.K_unaugmented
+    self.K[0, 2] = 1
+
+    self.InitializeState()
+
+
+class ScenarioPlotter(object):
+  def __init__(self):
+    # Various lists for graphing things.
+    self.t = []
+    self.x = []
+    self.v = []
+    self.a = []
+    self.x_hat = []
+    self.u = []
+
+  def run_test(self, elevator, goal,
+               iterations=200, controller_elevator=None,
+               observer_elevator=None):
+    """Runs the Elevator plant with an initial condition and goal.
+
+      Args:
+        Elevator: elevator object to use.
+        initial_X: starting state.
+        goal: goal state.
+        iterations: Number of timesteps to run the model for.
+        controller_Elevator: elevator object to get K from, or None if we should
+            use Elevator.
+        observer_Elevator: elevator object to use for the observer, or None if we should
+            use the actual state.
+    """
+
+    if controller_elevator is None:
+      controller_elevator = elevator
+
+    vbat = 10.0
+    if self.t:
+      initial_t = self.t[-1] + elevator.dt
+    else:
+      initial_t = 0
+    for i in xrange(iterations):
+      X_hat = elevator.X
+      if observer_elevator is not None:
+        X_hat = observer_elevator.X_hat
+        self.x_hat.append(observer_elevator.X_hat[0, 0])
+      gravity_compensation =  9.8 * elevator.mass * elevator.r / elevator.G / elevator.Kt * elevator.resistance
+
+      U = controller_elevator.K * (goal - X_hat)
+      U[0, 0] = numpy.clip(U[0, 0], -vbat , vbat )
+      self.x.append(elevator.X[0, 0])
+      if self.v:
+        last_v = self.v[-1]
+      else:
+        last_v = 0
+      self.v.append(elevator.X[1, 0])
+      self.a.append((self.v[-1] - last_v) / elevator.dt)
+
+      if observer_elevator is not None:
+        observer_elevator.Y = elevator.Y
+        observer_elevator.CorrectObserver(U)
+
+      elevator.Update(U - gravity_compensation)
+
+      if observer_elevator is not None:
+        observer_elevator.PredictObserver(U)
+
+      self.t.append(initial_t + i * elevator.dt)
+      self.u.append(U[0, 0])
+#      if numpy.abs((goal - X_hat)[0:2, 0]).sum() < .025:
+#        print "Time: ", self.t[-1]
+#        break
+
+    print "Time: ", self.t[-1]
+
+
+  def Plot(self):
+    pylab.subplot(3, 1, 1)
+    pylab.plot(self.t, self.x, label='x')
+    pylab.plot(self.t, self.x_hat, label='x_hat')
+    pylab.legend()
+
+    pylab.subplot(3, 1, 2)
+    pylab.plot(self.t, self.u, label='u')
+
+    pylab.subplot(3, 1, 3)
+    pylab.plot(self.t, self.a, label='a')
+
+    pylab.legend()
+    pylab.show()
+
+
+def main(argv):
+  loaded_mass = 7+4.0
+  #loaded_mass = 0
+  #observer_elevator = None
+
+  # Test moving the Elevator
+  initial_X = numpy.matrix([[0.0], [0.0]])
+  up_R = numpy.matrix([[0.4572], [0.0], [0.0]])
+  down_R = numpy.matrix([[0.0], [0.0], [0.0]])
+  totemass = 3.54
+  scenario_plotter = ScenarioPlotter()
+
+  elevator_controller = IntegralElevator(mass=4*totemass + loaded_mass)
+  observer_elevator = IntegralElevator(mass=4*totemass + loaded_mass)
+
+  for i in xrange(0, 7):
+    elevator = Elevator(mass=i*totemass + loaded_mass)
+    print 'Actual poles are', numpy.linalg.eig(elevator.A - elevator.B * elevator_controller.K[0, 0:2])[0]
+
+    elevator.X = initial_X
+    scenario_plotter.run_test(elevator, goal=up_R, controller_elevator=elevator_controller,
+                              observer_elevator=observer_elevator, iterations=200)
+    scenario_plotter.run_test(elevator, goal=down_R, controller_elevator=elevator_controller,
+                              observer_elevator=observer_elevator, iterations=200)
+
+  scenario_plotter.Plot()
+
+  # Write the generated constants out to a file.
+  if len(argv) != 5:
+    print "Expected .h file name and .cc file name for the Elevator and integral elevator."
+  else:
+    design_mass = 4*totemass + loaded_mass
+    elevator = Elevator("Elevator", mass=design_mass)
+    loop_writer = control_loop.ControlLoopWriter("Elevator", [elevator],
+                                                 namespaces=['y2015_bot3', 'control_loops'])
+    if argv[1][-3:] == '.cc':
+      loop_writer.Write(argv[2], argv[1])
+    else:
+      loop_writer.Write(argv[1], argv[2])
+
+    integral_elevator = IntegralElevator("IntegralElevator", mass=design_mass)
+    integral_loop_writer = control_loop.ControlLoopWriter("IntegralElevator", [integral_elevator],
+                                                          namespaces=['y2015_bot3', 'control_loops'])
+    if argv[3][-3:] == '.cc':
+      integral_loop_writer.Write(argv[4], argv[3])
+    else:
+      integral_loop_writer.Write(argv[3], argv[4])
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/y2015_bot3/control_loops/python/polydrivetrain.py b/y2015_bot3/control_loops/python/polydrivetrain.py
new file mode 100755
index 0000000..9aa4821
--- /dev/null
+++ b/y2015_bot3/control_loops/python/polydrivetrain.py
@@ -0,0 +1,506 @@
+#!/usr/bin/python
+
+import numpy
+import sys
+import polytope
+import drivetrain
+import control_loop
+import controls
+from matplotlib import pylab
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+
+def CoerceGoal(region, K, w, R):
+  """Intersects a line with a region, and finds the closest point to R.
+
+  Finds a point that is closest to R inside the region, and on the line
+  defined by K X = w.  If it is not possible to find a point on the line,
+  finds a point that is inside the region and closest to the line.  This
+  function assumes that
+
+  Args:
+    region: HPolytope, the valid goal region.
+    K: numpy.matrix (2 x 1), the matrix for the equation [K1, K2] [x1; x2] = w
+    w: float, the offset in the equation above.
+    R: numpy.matrix (2 x 1), the point to be closest to.
+
+  Returns:
+    numpy.matrix (2 x 1), the point.
+  """
+  return DoCoerceGoal(region, K, w, R)[0]
+
+def DoCoerceGoal(region, K, w, R):
+  if region.IsInside(R):
+    return (R, True)
+
+  perpendicular_vector = K.T / numpy.linalg.norm(K)
+  parallel_vector = numpy.matrix([[perpendicular_vector[1, 0]],
+                                  [-perpendicular_vector[0, 0]]])
+  
+  # We want to impose the constraint K * X = w on the polytope H * X <= k.
+  # We do this by breaking X up into parallel and perpendicular components to
+  # the half plane.  This gives us the following equation.
+  #
+  #  parallel * (parallel.T \dot X) + perpendicular * (perpendicular \dot X)) = X
+  #
+  # Then, substitute this into the polytope.
+  #
+  #  H * (parallel * (parallel.T \dot X) + perpendicular * (perpendicular \dot X)) <= k
+  #
+  # Substitute K * X = w
+  #
+  # H * parallel * (parallel.T \dot X) + H * perpendicular * w <= k
+  #
+  # Move all the knowns to the right side.
+  #
+  # H * parallel * ([parallel1 parallel2] * X) <= k - H * perpendicular * w
+  #
+  # Let t = parallel.T \dot X, the component parallel to the surface.
+  #
+  # H * parallel * t <= k - H * perpendicular * w
+  #
+  # This is a polytope which we can solve, and use to figure out the range of X
+  # that we care about!
+
+  t_poly = polytope.HPolytope(
+      region.H * parallel_vector,
+      region.k - region.H * perpendicular_vector * w)
+
+  vertices = t_poly.Vertices()
+
+  if vertices.shape[0]:
+    # The region exists!
+    # Find the closest vertex
+    min_distance = numpy.infty
+    closest_point = None
+    for vertex in vertices:
+      point = parallel_vector * vertex + perpendicular_vector * w
+      length = numpy.linalg.norm(R - point)
+      if length < min_distance:
+        min_distance = length
+        closest_point = point
+
+    return (closest_point, True)
+  else:
+    # Find the vertex of the space that is closest to the line.
+    region_vertices = region.Vertices()
+    min_distance = numpy.infty
+    closest_point = None
+    for vertex in region_vertices:
+      point = vertex.T
+      length = numpy.abs((perpendicular_vector.T * point)[0, 0])
+      if length < min_distance:
+        min_distance = length
+        closest_point = point
+
+    return (closest_point, False)
+
+
+class VelocityDrivetrainModel(control_loop.ControlLoop):
+  def __init__(self, left_low=True, right_low=True, name="VelocityDrivetrainModel"):
+    super(VelocityDrivetrainModel, self).__init__(name)
+    self._drivetrain = drivetrain.Drivetrain(left_low=left_low,
+                                             right_low=right_low)
+    self.dt = 0.01
+    self.A_continuous = numpy.matrix(
+        [[self._drivetrain.A_continuous[1, 1], self._drivetrain.A_continuous[1, 3]],
+         [self._drivetrain.A_continuous[3, 1], self._drivetrain.A_continuous[3, 3]]])
+
+    self.B_continuous = numpy.matrix(
+        [[self._drivetrain.B_continuous[1, 0], self._drivetrain.B_continuous[1, 1]],
+         [self._drivetrain.B_continuous[3, 0], self._drivetrain.B_continuous[3, 1]]])
+    self.C = numpy.matrix(numpy.eye(2))
+    self.D = numpy.matrix(numpy.zeros((2, 2)))
+
+    self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+                                               self.B_continuous, self.dt)
+
+    # FF * X = U (steady state)
+    self.FF = self.B.I * (numpy.eye(2) - self.A)
+
+    self.PlaceControllerPoles([0.6, 0.6])
+    self.PlaceObserverPoles([0.02, 0.02])
+
+    self.G_high = self._drivetrain.G_high
+    self.G_low = self._drivetrain.G_low
+    self.R = self._drivetrain.R
+    self.r = self._drivetrain.r
+    self.Kv = self._drivetrain.Kv
+    self.Kt = self._drivetrain.Kt
+
+    self.U_max = self._drivetrain.U_max
+    self.U_min = self._drivetrain.U_min
+
+
+class VelocityDrivetrain(object):
+  HIGH = 'high'
+  LOW = 'low'
+  SHIFTING_UP = 'up'
+  SHIFTING_DOWN = 'down'
+
+  def __init__(self):
+    self.drivetrain_low_low = VelocityDrivetrainModel(
+        left_low=True, right_low=True, name='VelocityDrivetrainLowLow')
+    self.drivetrain_low_high = VelocityDrivetrainModel(left_low=True, right_low=False, name='VelocityDrivetrainLowHigh')
+    self.drivetrain_high_low = VelocityDrivetrainModel(left_low=False, right_low=True, name = 'VelocityDrivetrainHighLow')
+    self.drivetrain_high_high = VelocityDrivetrainModel(left_low=False, right_low=False, name = 'VelocityDrivetrainHighHigh')
+
+    # X is [lvel, rvel]
+    self.X = numpy.matrix(
+        [[0.0],
+         [0.0]])
+
+    self.U_poly = polytope.HPolytope(
+        numpy.matrix([[1, 0],
+                      [-1, 0],
+                      [0, 1],
+                      [0, -1]]),
+        numpy.matrix([[12],
+                      [12],
+                      [12],
+                      [12]]))
+
+    self.U_max = numpy.matrix(
+        [[12.0],
+         [12.0]])
+    self.U_min = numpy.matrix(
+        [[-12.0000000000],
+         [-12.0000000000]])
+
+    self.dt = 0.01
+
+    self.R = numpy.matrix(
+        [[0.0],
+         [0.0]])
+
+    # ttrust is the comprimise between having full throttle negative inertia,
+    # and having no throttle negative inertia.  A value of 0 is full throttle
+    # inertia.  A value of 1 is no throttle negative inertia.
+    self.ttrust = 1.1
+
+    self.left_gear = VelocityDrivetrain.LOW
+    self.right_gear = VelocityDrivetrain.LOW
+    self.left_shifter_position = 0.0
+    self.right_shifter_position = 0.0
+    self.left_cim = drivetrain.CIM()
+    self.right_cim = drivetrain.CIM()
+
+  def IsInGear(self, gear):
+    return gear is VelocityDrivetrain.HIGH or gear is VelocityDrivetrain.LOW
+
+  def MotorRPM(self, shifter_position, velocity):
+    if shifter_position > 0.5:
+      return (velocity / self.CurrentDrivetrain().G_high /
+              self.CurrentDrivetrain().r)
+    else:
+      return (velocity / self.CurrentDrivetrain().G_low /
+              self.CurrentDrivetrain().r)
+
+  def CurrentDrivetrain(self):
+    if self.left_shifter_position > 0.5:
+      if self.right_shifter_position > 0.5:
+        return self.drivetrain_high_high
+      else:
+        return self.drivetrain_high_low
+    else:
+      if self.right_shifter_position > 0.5:
+        return self.drivetrain_low_high
+      else:
+        return self.drivetrain_low_low
+
+  def SimShifter(self, gear, shifter_position):
+    if gear is VelocityDrivetrain.HIGH or gear is VelocityDrivetrain.SHIFTING_UP:
+      shifter_position = min(shifter_position + 0.5, 1.0)
+    else:
+      shifter_position = max(shifter_position - 0.5, 0.0)
+
+    if shifter_position == 1.0:
+      gear = VelocityDrivetrain.HIGH
+    elif shifter_position == 0.0:
+      gear = VelocityDrivetrain.LOW
+
+    return gear, shifter_position
+
+  def ComputeGear(self, wheel_velocity, should_print=False, current_gear=False, gear_name=None):
+    high_omega = (wheel_velocity / self.CurrentDrivetrain().G_high /
+                  self.CurrentDrivetrain().r)
+    low_omega = (wheel_velocity / self.CurrentDrivetrain().G_low /
+                 self.CurrentDrivetrain().r)
+    #print gear_name, "Motor Energy Difference.", 0.5 * 0.000140032647 * (low_omega * low_omega - high_omega * high_omega), "joules"
+    high_torque = ((12.0 - high_omega / self.CurrentDrivetrain().Kv) *
+                   self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
+    low_torque = ((12.0 - low_omega / self.CurrentDrivetrain().Kv) *
+                  self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
+    high_power = high_torque * high_omega
+    low_power = low_torque * low_omega
+    #if should_print:
+    #  print gear_name, "High omega", high_omega, "Low omega", low_omega
+    #  print gear_name, "High torque", high_torque, "Low torque", low_torque
+    #  print gear_name, "High power", high_power, "Low power", low_power
+
+    # Shift algorithm improvements.
+    # TODO(aschuh):
+    # It takes time to shift.  Shifting down for 1 cycle doesn't make sense
+    # because you will end up slower than without shifting.  Figure out how
+    # to include that info.
+    # If the driver is still in high gear, but isn't asking for the extra power
+    # from low gear, don't shift until he asks for it.
+    goal_gear_is_high = high_power > low_power
+    #goal_gear_is_high = True
+
+    if not self.IsInGear(current_gear):
+      print gear_name, 'Not in gear.'
+      return current_gear
+    else:
+      is_high = current_gear is VelocityDrivetrain.HIGH
+      if is_high != goal_gear_is_high:
+        if goal_gear_is_high:
+          print gear_name, 'Shifting up.'
+          return VelocityDrivetrain.SHIFTING_UP
+        else:
+          print gear_name, 'Shifting down.'
+          return VelocityDrivetrain.SHIFTING_DOWN
+      else:
+        return current_gear
+
+  def FilterVelocity(self, throttle):
+    # Invert the plant to figure out how the velocity filter would have to work
+    # out in order to filter out the forwards negative inertia.
+    # This math assumes that the left and right power and velocity are equal.
+
+    # The throttle filter should filter such that the motor in the highest gear
+    # should be controlling the time constant.
+    # Do this by finding the index of FF that has the lowest value, and computing
+    # the sums using that index.
+    FF_sum = self.CurrentDrivetrain().FF.sum(axis=1)
+    min_FF_sum_index = numpy.argmin(FF_sum)
+    min_FF_sum = FF_sum[min_FF_sum_index, 0]
+    min_K_sum = self.CurrentDrivetrain().K[min_FF_sum_index, :].sum()
+    # Compute the FF sum for high gear.
+    high_min_FF_sum = self.drivetrain_high_high.FF[0, :].sum()
+
+    # U = self.K[0, :].sum() * (R - x_avg) + self.FF[0, :].sum() * R
+    # throttle * 12.0 = (self.K[0, :].sum() + self.FF[0, :].sum()) * R
+    #                   - self.K[0, :].sum() * x_avg
+
+    # R = (throttle * 12.0 + self.K[0, :].sum() * x_avg) /
+    #     (self.K[0, :].sum() + self.FF[0, :].sum())
+
+    # U = (K + FF) * R - K * X
+    # (K + FF) ^-1 * (U + K * X) = R
+
+    # Scale throttle by min_FF_sum / high_min_FF_sum.  This will make low gear
+    # have the same velocity goal as high gear, and so that the robot will hold
+    # the same speed for the same throttle for all gears.
+    adjusted_ff_voltage = numpy.clip(throttle * 12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0)
+    return ((adjusted_ff_voltage + self.ttrust * min_K_sum * (self.X[0, 0] + self.X[1, 0]) / 2.0)
+            / (self.ttrust * min_K_sum + min_FF_sum))
+
+  def Update(self, throttle, steering):
+    # Shift into the gear which sends the most power to the floor.
+    # This is the same as sending the most torque down to the floor at the
+    # wheel.
+
+    self.left_gear = self.right_gear = True
+    if False:
+      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])
+
+    steering *= 2.3
+    if True or self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
+      # Filter the throttle to provide a nicer response.
+      fvel = self.FilterVelocity(throttle)
+
+      # Constant radius means that angualar_velocity / linear_velocity = constant.
+      # Compute the left and right velocities.
+      steering_velocity = numpy.abs(fvel) * steering
+      left_velocity = fvel - steering_velocity
+      right_velocity = fvel + steering_velocity
+
+      # Write this constraint in the form of K * R = w
+      # angular velocity / linear velocity = constant
+      # (left - right) / (left + right) = constant
+      # left - right = constant * left + constant * right
+
+      # (fvel - steering * numpy.abs(fvel) - fvel - steering * numpy.abs(fvel)) /
+      #  (fvel - steering * numpy.abs(fvel) + fvel + steering * numpy.abs(fvel)) =
+      #       constant
+      # (- 2 * steering * numpy.abs(fvel)) / (2 * fvel) = constant
+      # (-steering * sign(fvel)) = constant
+      # (-steering * sign(fvel)) * (left + right) = left - right
+      # (steering * sign(fvel) + 1) * left + (steering * sign(fvel) - 1) * right = 0
+
+      equality_k = numpy.matrix(
+          [[1 + steering * numpy.sign(fvel), -(1 - steering * numpy.sign(fvel))]])
+      equality_w = 0.0
+
+      self.R[0, 0] = left_velocity
+      self.R[1, 0] = right_velocity
+
+      # Construct a constraint on R by manipulating the constraint on U
+      # Start out with H * U <= k
+      # U = FF * R + K * (R - X)
+      # H * (FF * R + K * R - K * X) <= k
+      # H * (FF + K) * R <= k + H * K * X
+      R_poly = polytope.HPolytope(
+          self.U_poly.H * (self.CurrentDrivetrain().K + self.CurrentDrivetrain().FF),
+          self.U_poly.k + self.U_poly.H * self.CurrentDrivetrain().K * self.X)
+
+      # Limit R back inside the box.
+      self.boxed_R = CoerceGoal(R_poly, equality_k, equality_w, self.R)
+
+      FF_volts = self.CurrentDrivetrain().FF * self.boxed_R
+      self.U_ideal = self.CurrentDrivetrain().K * (self.boxed_R - self.X) + FF_volts
+    else:
+      print 'Not all in gear'
+      if not self.IsInGear(self.left_gear) and not self.IsInGear(self.right_gear):
+        # TODO(austin): Use battery volts here.
+        R_left = self.MotorRPM(self.left_shifter_position, self.X[0, 0])
+        self.U_ideal[0, 0] = numpy.clip(
+            self.left_cim.K * (R_left - self.left_cim.X) + R_left / self.left_cim.Kv,
+            self.left_cim.U_min, self.left_cim.U_max)
+        self.left_cim.Update(self.U_ideal[0, 0])
+
+        R_right = self.MotorRPM(self.right_shifter_position, self.X[1, 0])
+        self.U_ideal[1, 0] = numpy.clip(
+            self.right_cim.K * (R_right - self.right_cim.X) + R_right / self.right_cim.Kv,
+            self.right_cim.U_min, self.right_cim.U_max)
+        self.right_cim.Update(self.U_ideal[1, 0])
+      else:
+        assert False
+
+    self.U = numpy.clip(self.U_ideal, self.U_min, self.U_max)
+
+    # TODO(austin): Model the robot as not accelerating when you shift...
+    # This hack only works when you shift at the same time.
+    if True or self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
+      self.X = self.CurrentDrivetrain().A * self.X + self.CurrentDrivetrain().B * self.U
+
+    self.left_gear, self.left_shifter_position = self.SimShifter(
+        self.left_gear, self.left_shifter_position)
+    self.right_gear, self.right_shifter_position = self.SimShifter(
+        self.right_gear, self.right_shifter_position)
+
+    print "U is", self.U[0, 0], self.U[1, 0]
+    print "Left shifter", self.left_gear, self.left_shifter_position, "Right shifter", self.right_gear, self.right_shifter_position
+
+
+def main(argv):
+  vdrivetrain = VelocityDrivetrain()
+
+  if len(argv) != 7:
+    print "Expected .h file name and .cc file name"
+  else:
+    dog_loop_writer = control_loop.ControlLoopWriter(
+        "VelocityDrivetrain", [vdrivetrain.drivetrain_low_low,
+                       vdrivetrain.drivetrain_low_high,
+                       vdrivetrain.drivetrain_high_low,
+                       vdrivetrain.drivetrain_high_high],
+        namespaces=['y2015_bot3', 'control_loops'])
+
+    if argv[1][-3:] == '.cc':
+      dog_loop_writer.Write(argv[2], argv[1])
+    else:
+      dog_loop_writer.Write(argv[1], argv[2])
+
+    cim_writer = control_loop.ControlLoopWriter(
+        "CIM", [drivetrain.CIM()],
+        namespaces=['y2015_bot3', 'control_loops'])
+
+    if argv[5][-3:] == '.cc':
+      cim_writer.Write(argv[6], argv[5])
+    else:
+      cim_writer.Write(argv[5], argv[6])
+    return
+
+  vl_plot = []
+  vr_plot = []
+  ul_plot = []
+  ur_plot = []
+  radius_plot = []
+  t_plot = []
+  left_gear_plot = []
+  right_gear_plot = []
+  vdrivetrain.left_shifter_position = 0.0
+  vdrivetrain.right_shifter_position = 0.0
+  vdrivetrain.left_gear = VelocityDrivetrain.LOW
+  vdrivetrain.right_gear = VelocityDrivetrain.LOW
+
+  print "K is", vdrivetrain.CurrentDrivetrain().K
+
+  if vdrivetrain.left_gear is VelocityDrivetrain.HIGH:
+    print "Left is high"
+  else:
+    print "Left is low"
+  if vdrivetrain.right_gear is VelocityDrivetrain.HIGH:
+    print "Right is high"
+  else:
+    print "Right is low"
+
+  for t in numpy.arange(0, 1.7, vdrivetrain.dt):
+    if t < 0.5:
+      vdrivetrain.Update(throttle=0.00, steering=1.0)
+    elif t < 1.2:
+      vdrivetrain.Update(throttle=0.5, steering=1.0)
+    else:
+      vdrivetrain.Update(throttle=0.00, steering=1.0)
+    t_plot.append(t)
+    vl_plot.append(vdrivetrain.X[0, 0])
+    vr_plot.append(vdrivetrain.X[1, 0])
+    ul_plot.append(vdrivetrain.U[0, 0])
+    ur_plot.append(vdrivetrain.U[1, 0])
+    left_gear_plot.append((vdrivetrain.left_gear is VelocityDrivetrain.HIGH) * 2.0 - 10.0)
+    right_gear_plot.append((vdrivetrain.right_gear is VelocityDrivetrain.HIGH) * 2.0 - 10.0)
+
+    fwd_velocity = (vdrivetrain.X[1, 0] + vdrivetrain.X[0, 0]) / 2
+    turn_velocity = (vdrivetrain.X[1, 0] - vdrivetrain.X[0, 0])
+    if abs(fwd_velocity) < 0.0000001:
+      radius_plot.append(turn_velocity)
+    else:
+      radius_plot.append(turn_velocity / fwd_velocity)
+
+  cim_velocity_plot = []
+  cim_voltage_plot = []
+  cim_time = []
+  cim = drivetrain.CIM()
+  R = numpy.matrix([[300]])
+  for t in numpy.arange(0, 0.5, cim.dt):
+    U = numpy.clip(cim.K * (R - cim.X) + R / cim.Kv, cim.U_min, cim.U_max)
+    cim.Update(U)
+    cim_velocity_plot.append(cim.X[0, 0])
+    cim_voltage_plot.append(U[0, 0] * 10)
+    cim_time.append(t)
+  pylab.plot(cim_time, cim_velocity_plot, label='cim spinup')
+  pylab.plot(cim_time, cim_voltage_plot, label='cim voltage')
+  pylab.legend()
+  pylab.show()
+
+  # TODO(austin):
+  # Shifting compensation.
+
+  # Tighten the turn.
+  # Closed loop drive.
+
+  pylab.plot(t_plot, vl_plot, label='left velocity')
+  pylab.plot(t_plot, vr_plot, label='right velocity')
+  pylab.plot(t_plot, ul_plot, label='left voltage')
+  pylab.plot(t_plot, ur_plot, label='right voltage')
+  pylab.plot(t_plot, radius_plot, label='radius')
+  pylab.plot(t_plot, left_gear_plot, label='left gear high')
+  pylab.plot(t_plot, right_gear_plot, label='right gear high')
+  pylab.legend()
+  pylab.show()
+  return 0
+
+if __name__ == '__main__':
+  sys.exit(main(sys.argv))
diff --git a/y2015_bot3/control_loops/python/polydrivetrain_test.py b/y2015_bot3/control_loops/python/polydrivetrain_test.py
new file mode 100755
index 0000000..434cdca
--- /dev/null
+++ b/y2015_bot3/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/y2015_bot3/control_loops/update_drivetrain.sh b/y2015_bot3/control_loops/update_drivetrain.sh
new file mode 100755
index 0000000..b5757d3
--- /dev/null
+++ b/y2015_bot3/control_loops/update_drivetrain.sh
@@ -0,0 +1,12 @@
+#!/bin/bash
+#
+# Updates the drivetrain controllers.
+
+cd $(dirname $0)
+
+export PYTHONPATH=../../frc971/control_loops/python
+
+./python/drivetrain.py drivetrain/drivetrain_dog_motor_plant.h \
+    drivetrain/drivetrain_dog_motor_plant.cc \
+    drivetrain/drivetrain_clutch_motor_plant.h \
+    drivetrain/drivetrain_clutch_motor_plant.cc
diff --git a/y2015_bot3/control_loops/update_elevator.sh b/y2015_bot3/control_loops/update_elevator.sh
new file mode 100755
index 0000000..4f0e359
--- /dev/null
+++ b/y2015_bot3/control_loops/update_elevator.sh
@@ -0,0 +1,10 @@
+#!/bin/bash
+#
+# Updates the elevator controllers.
+
+cd $(dirname $0)
+
+export PYTHONPATH=../../frc971/control_loops/python
+
+./python/elevator3.py elevator/elevator_motor_plant.h \
+    elevator/elevator_motor_plant.cc elevator/integral_elevator_motor_plant.cc elevator/integral_elevator_motor_plant.h
diff --git a/y2015_bot3/control_loops/update_polydrivetrain.sh b/y2015_bot3/control_loops/update_polydrivetrain.sh
new file mode 100755
index 0000000..b1bb2b4
--- /dev/null
+++ b/y2015_bot3/control_loops/update_polydrivetrain.sh
@@ -0,0 +1,14 @@
+#!/bin/bash
+#
+# Updates the polydrivetrain controllers and CIM models.
+
+cd $(dirname $0)
+
+export PYTHONPATH=../../frc971/control_loops/python
+
+./python/polydrivetrain.py drivetrain/polydrivetrain_dog_motor_plant.h \
+    drivetrain/polydrivetrain_dog_motor_plant.cc \
+    drivetrain/polydrivetrain_clutch_motor_plant.h \
+    drivetrain/polydrivetrain_clutch_motor_plant.cc \
+    drivetrain/polydrivetrain_cim_plant.h \
+    drivetrain/polydrivetrain_cim_plant.cc
diff --git a/y2015_bot3/joystick_reader.cc b/y2015_bot3/joystick_reader.cc
new file mode 100644
index 0000000..0d00e5c
--- /dev/null
+++ b/y2015_bot3/joystick_reader.cc
@@ -0,0 +1,386 @@
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+#include <math.h>
+
+#include "aos/linux_code/init.h"
+#include "aos/prime/input/joystick_input.h"
+#include "aos/common/input/driver_station_data.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/util/log_interval.h"
+#include "aos/common/time.h"
+#include "aos/common/actions/actions.h"
+
+#include "frc971/queues/gyro.q.h"
+#include "y2015_bot3/autonomous/auto.q.h"
+#include "y2015_bot3/control_loops/elevator/elevator.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.q.h"
+#include "y2015_bot3/control_loops/elevator/elevator.q.h"
+#include "y2015_bot3/control_loops/intake/intake.q.h"
+
+using ::y2015_bot3::control_loops::drivetrain_queue;
+using ::y2015_bot3::control_loops::elevator_queue;
+using ::y2015_bot3::control_loops::intake_queue;
+using ::frc971::sensors::gyro_reading;
+
+using ::aos::input::driver_station::ButtonLocation;
+using ::aos::input::driver_station::POVLocation;
+using ::aos::input::driver_station::JoystickAxis;
+using ::aos::input::driver_station::ControlBit;
+
+namespace y2015_bot3 {
+namespace input {
+namespace joysticks {
+
+struct ProfileParams {
+  double velocity;
+  double acceleration;
+};
+
+// Preset motion limits.
+constexpr ProfileParams kElevatorMove{0.3, 1.0};
+constexpr ProfileParams kFastElevatorMove{1.0, 5.0};
+
+// Preset goals for autostacking
+constexpr double kOneToteHeight{0.46};
+constexpr double kCarryHeight{0.180};
+constexpr double kGroundHeight{0.030};
+
+// Joystick & button addresses.
+const JoystickAxis kSteeringWheel(1, 1), kDriveThrottle(2, 2);
+const ButtonLocation kShiftHigh(2, 1), kShiftLow(2, 3);
+const ButtonLocation kQuickTurn(1, 5);
+
+// essential
+const ButtonLocation kMoveToteHeight(4, 9);
+const ButtonLocation kOpenIntake(3, 8);
+const ButtonLocation kCloseIntake(3, 6);
+const ButtonLocation kOpenCanRestraint(4, 5);
+const ButtonLocation kCloseCanRestraint(4, 1);
+const POVLocation kOpenPassiveSupport(4, 0);
+const POVLocation kClosePassiveSupport(4, 180);
+
+const ButtonLocation kIntakeOut(3, 7);
+const ButtonLocation kIntakeIn(4, 12);
+
+const ButtonLocation kAutoStack(4, 7);
+const ButtonLocation kManualStack(4, 6);
+
+const ButtonLocation kCarry(4, 10);
+const ButtonLocation kSetDown(3, 9);
+const ButtonLocation kSkyscraper(4, 11);
+
+const ButtonLocation kScoreBegin(4, 8);
+
+const ButtonLocation kCanGrabberLift(3, 2);
+const ButtonLocation kFastCanGrabberLift(2, 3);
+const ButtonLocation kCanGrabberLower(3, 5);
+
+class Reader : public ::aos::input::JoystickInput {
+ public:
+  Reader() : was_running_(false) {}
+
+  virtual void RunIteration(const ::aos::input::driver_station::Data &data) {
+    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();
+      }
+      intake_closed_ = true;
+      can_restraint_open_ = false;
+      passive_support_open_ = true;
+    }
+
+    if (!data.GetControlBit(ControlBit::kAutonomous)) {
+      HandleDrivetrain(data);
+      HandleTeleop(data);
+    }
+  }
+
+  void HandleDrivetrain(const ::aos::input::driver_station::Data &data) {
+    const double wheel = -data.GetAxis(kSteeringWheel);
+    const double throttle = -data.GetAxis(kDriveThrottle);
+
+    if (!drivetrain_queue.goal.MakeWithBuilder()
+             .steering(wheel)
+             .throttle(throttle)
+             .quickturn(data.IsPressed(kQuickTurn))
+             .control_loop_driving(false)
+             .Send()) {
+      LOG(WARNING, "sending stick values failed\n");
+    }
+  }
+
+  void HandleTeleop(const ::aos::input::driver_station::Data &data) {
+    double intake_goal = 0;
+
+    if (!data.GetControlBit(ControlBit::kEnabled)) {
+      action_queue_.CancelAllActions();
+      LOG(DEBUG, "Canceling\n");
+    }
+
+    elevator_queue.status.FetchLatest();
+    if (!elevator_queue.status.get()) {
+      LOG(ERROR, "Got no elevator status packet.\n");
+    }
+
+    if (elevator_queue.status.get() && elevator_queue.status->zeroed) {
+      if (waiting_for_zero_) {
+        LOG(INFO, "Zeroed! Starting teleop mode.\n");
+        waiting_for_zero_ = false;
+
+        // Set the initial goals to the bottom, since otherwise the driver seems
+        // to get confused and think that the end of the zeroing sequence is the
+        // same location and then wonders why it doesn't work...
+        elevator_goal_ = kGroundHeight;
+      }
+    } else {
+      waiting_for_zero_ = true;
+    }
+
+    if (data.PosEdge(kAutoStack)) {
+      action_queue_.CancelAllActions();
+      if (tote_count_ == 6) {
+        stacking_state_machine_ = FULL;
+      } else {
+        stacking_state_machine_ = WAITING;
+      }
+    }
+    if (data.IsPressed(kAutoStack)) {
+      switch (stacking_state_machine_) {
+        case WAITING:
+          elevator_params_ = kFastElevatorMove;
+          elevator_goal_ = kOneToteHeight;
+          if (elevator_queue.status->has_tote) {
+            stacking_state_machine_ = GOING_DOWN;
+          }
+          break;
+        case GOING_DOWN:
+          elevator_params_ = kFastElevatorMove;
+          elevator_goal_ = kGroundHeight;
+          if (elevator_queue.status->height < 0.05) {
+            ++tote_count_;
+            if (tote_count_ == 6) {
+              stacking_state_machine_ = FULL;
+            } else {
+              stacking_state_machine_ = GOING_UP;
+            }
+          }
+          break;
+        case GOING_UP:
+          elevator_params_ = kFastElevatorMove;
+          elevator_goal_ = kOneToteHeight;
+          if (elevator_queue.status->height > kOneToteHeight - 0.05) {
+            stacking_state_machine_ = WAITING;
+          }
+          break;
+        case FULL:
+          elevator_goal_ = kCarryHeight;
+          elevator_params_ = kFastElevatorMove;
+          break;
+        case OFF:
+          stacking_state_machine_ = WAITING;
+          break;
+      }
+    } else {
+      stacking_state_machine_ = OFF;
+    }
+
+    // Buttons for intaking.
+    if (data.IsPressed(kIntakeIn)) {
+      intake_goal = 10.0;
+      if (stacking_state_machine_ != OFF &&
+          elevator_queue.status->height < 0.43) {
+        intake_goal = 0.0;
+      }
+    } else if (data.IsPressed(kIntakeOut)) {
+      intake_goal = -10.0;
+
+      action_queue_.CancelAllActions();
+    }
+    // TODO(Adam): Implement essential actors/goals.
+    if (data.PosEdge(kMoveToteHeight)) {
+      elevator_goal_ = 0.45;
+      elevator_params_ = {1.0, 5.0};
+      action_queue_.CancelAllActions();
+    }
+
+    if (data.IsPressed(kOpenIntake)) {
+      intake_closed_ = false;
+    }
+
+    if (data.IsPressed(kCloseIntake)) {
+      intake_closed_ = true;
+    }
+
+    if (data.IsPressed(kOpenCanRestraint)) {
+      can_restraint_open_ = true;
+    }
+
+    if (data.IsPressed(kCloseCanRestraint)) {
+      can_restraint_open_ = false;
+    }
+
+    if (data.IsPressed(kOpenPassiveSupport)) {
+      passive_support_open_ = true;
+    }
+
+    if (data.IsPressed(kClosePassiveSupport)) {
+      passive_support_open_ = false;
+    }
+
+    // Buttons for elevator.
+    if (data.IsPressed(kCarry)) {
+      // TODO(comran): Get actual height/velocity/acceleration values.
+      elevator_goal_ = 0.180;
+      elevator_params_ = {1.0, 2.0};
+      action_queue_.CancelAllActions();
+    }
+
+    if (data.IsPressed(kSetDown)) {
+      // TODO(comran): Get actual height/velocity/acceleration values.
+      elevator_goal_ = 0.005;
+      elevator_params_ = {1.0, 5.0};
+      action_queue_.CancelAllActions();
+    }
+
+    if (data.IsPressed(kSkyscraper)) {
+      // TODO(comran): Get actual height/velocity/acceleration values.
+      elevator_goal_ = 1.0;
+      elevator_params_ = {1.0, 5.0};
+    }
+
+    if (data.IsPressed(kScoreBegin)) {
+      // TODO(comran): Get actual height/velocity/acceleration values.
+      elevator_goal_ = 0.005;
+      elevator_params_ = {1.0, 5.0};
+      intake_closed_ = false;
+      can_restraint_open_ = true;
+      passive_support_open_ = true;
+      tote_count_ = 0;
+    }
+
+    // Buttons for can grabber.
+    if (data.IsPressed(kCanGrabberLift)) {
+      ::y2015_bot3::autonomous::can_grabber_control.MakeWithBuilder()
+          .can_grabber_voltage(-3)
+          .can_grabbers(false)
+          .Send();
+    } else if (data.IsPressed(kFastCanGrabberLift)) {
+      ::y2015_bot3::autonomous::can_grabber_control.MakeWithBuilder()
+          .can_grabber_voltage(-12).can_grabbers(false).Send();
+    } else if (data.IsPressed(kCanGrabberLower)) {
+      if (grab_delay_ > 5) {
+        ::y2015_bot3::autonomous::can_grabber_control.MakeWithBuilder()
+            .can_grabber_voltage(2).can_grabbers(true).Send();
+      } else {
+        ::y2015_bot3::autonomous::can_grabber_control.MakeWithBuilder()
+            .can_grabber_voltage(0).can_grabbers(true).Send();
+      }
+      ++grab_delay_;
+    } else {
+      grab_delay_ = 0;
+    }
+
+    // Send our goals if everything looks OK.
+    if (!waiting_for_zero_) {
+      if (!action_queue_.Running()) {
+        // Send our elevator goals, with limits set in the profile params.
+        auto new_elevator_goal = elevator_queue.goal.MakeMessage();
+        new_elevator_goal->max_velocity = elevator_params_.velocity;
+        new_elevator_goal->max_acceleration = elevator_params_.acceleration;
+        new_elevator_goal->height = elevator_goal_;
+        new_elevator_goal->velocity = 0.0;
+        new_elevator_goal->passive_support = passive_support_open_;
+        new_elevator_goal->can_support = can_restraint_open_;
+
+        if (new_elevator_goal.Send()) {
+          LOG(DEBUG, "sending goals: elevator: %f\n", elevator_goal_);
+        } else {
+          LOG(ERROR, "Sending elevator goal failed.\n");
+        }
+      }
+    }
+
+    // Send our intake goals.
+    if (!intake_queue.goal.MakeWithBuilder().movement(intake_goal)
+            .claw_closed(intake_closed_).Send()) {
+      LOG(ERROR, "Sending intake goal failed.\n");
+    }
+
+    // If an action is running, use the action's goals for the profiled
+    // superstructure subsystems & bypass others.
+    if (action_queue_.Running()) {
+      control_loops::elevator_queue.status.FetchLatest();
+      if (control_loops::elevator_queue.status.get()) {
+        elevator_goal_ = control_loops::elevator_queue.status->goal_height;
+      } else {
+        LOG(ERROR, "No elevator status!\n");
+      }
+    }
+    action_queue_.Tick();
+    was_running_ = action_queue_.Running();
+  }
+
+ private:
+  void StartAuto() {
+    LOG(INFO, "Starting auto mode\n");
+    ::y2015_bot3::autonomous::autonomous.MakeWithBuilder().run_auto(true).Send();
+  }
+
+  void StopAuto() {
+    LOG(INFO, "Stopping auto mode\n");
+    ::y2015_bot3::autonomous::autonomous.MakeWithBuilder().run_auto(false).Send();
+  }
+
+  bool was_running_;
+
+  double elevator_goal_ = 0.2;
+
+  ProfileParams elevator_params_ = kElevatorMove;
+
+  // If we're waiting for the subsystems to zero.
+  bool waiting_for_zero_ = true;
+
+  bool auto_running_ = false;
+
+  bool intake_closed_ = false;
+
+  bool can_restraint_open_ = true;
+
+  bool passive_support_open_ = true;
+
+  int tote_count_ = 0;
+
+  ::aos::common::actions::ActionQueue action_queue_;
+
+  enum StackingStateMachine {
+    WAITING,
+    GOING_DOWN,
+    GOING_UP,
+    FULL,
+    OFF
+  };
+
+  StackingStateMachine stacking_state_machine_;
+
+  ::aos::util::SimpleLogInterval no_drivetrain_status_ =
+      ::aos::util::SimpleLogInterval(::aos::time::Time::InSeconds(0.2), WARNING,
+                                     "no drivetrain status");
+  int grab_delay_ = 0;
+};
+
+}  // namespace joysticks
+}  // namespace input
+}  // namespace y2015_bot3
+
+int main() {
+  ::aos::Init();
+  ::y2015_bot3::input::joysticks::Reader reader;
+  reader.Run();
+  ::aos::Cleanup();
+}
diff --git a/y2015_bot3/prime/BUILD b/y2015_bot3/prime/BUILD
new file mode 100644
index 0000000..7f30673
--- /dev/null
+++ b/y2015_bot3/prime/BUILD
@@ -0,0 +1,20 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/prime/downloader/downloader', 'aos_downloader')
+
+aos_downloader(
+  name = 'download',
+  start_srcs = [
+    '//aos:prime_start_binaries',
+    '//y2015_bot3/control_loops/drivetrain:drivetrain',
+    '//y2015_bot3/control_loops/intake:intake',
+    '//y2015_bot3:joystick_reader',
+    '//y2015_bot3/control_loops/elevator:elevator',
+    '//y2015_bot3/autonomous:auto',
+    '//y2015_bot3/actors:binaries',
+    '//y2015_bot3/wpilib:wpilib_interface',
+  ],
+  srcs = [
+    '//aos:prime_binaries',
+  ],
+)
diff --git a/y2015_bot3/prime/build.sh b/y2015_bot3/prime/build.sh
new file mode 100755
index 0000000..9586590
--- /dev/null
+++ b/y2015_bot3/prime/build.sh
@@ -0,0 +1,5 @@
+#!/bin/bash
+
+cd $(dirname $0)
+
+exec ../../aos/build/build.py $0 prime bot3 prime.gyp "$@"
diff --git a/y2015_bot3/prime/prime.gyp b/y2015_bot3/prime/prime.gyp
new file mode 100644
index 0000000..bbc59ad
--- /dev/null
+++ b/y2015_bot3/prime/prime.gyp
@@ -0,0 +1,40 @@
+{
+  'targets': [
+    {
+      'target_name': 'All',
+      'type': 'none',
+      'dependencies': [
+        '../../frc971/frc971.gyp:All',
+
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop_test',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:position_sensor_sim_test',
+        '../control_loops/drivetrain/drivetrain.gyp:drivetrain_bot3',
+        '../control_loops/drivetrain/drivetrain.gyp:drivetrain_lib_test_bot3',
+        '../control_loops/drivetrain/drivetrain.gyp:replay_drivetrain_bot3',
+        '../control_loops/intake/intake.gyp:intake',
+        '../control_loops/intake/intake.gyp:intake_lib_test',
+        '../bot3.gyp:joystick_reader_bot3',
+        '../control_loops/elevator/elevator.gyp:elevator',
+        '../control_loops/elevator/elevator.gyp:elevator_lib_test',
+        #'../control_loops/elevator/elevator.gyp:replay_elevator',
+        '../autonomous/autonomous.gyp:auto_bot3',
+        '../actors/actors.gyp:binaries',
+      ],
+      'copies': [
+        {
+          'destination': '<(rsync_dir)',
+          'files': [
+            'start_list.txt',
+          ],
+        },
+      ],
+      'conditions': [
+        ['ARCHITECTURE=="arm_frc"', {
+          'dependencies': [
+            '../wpilib/wpilib.gyp:wpilib_interface_bot3',
+          ],
+        }],
+      ],
+    },
+  ],
+}
diff --git a/y2015_bot3/wpilib/BUILD b/y2015_bot3/wpilib/BUILD
new file mode 100644
index 0000000..3e7453b
--- /dev/null
+++ b/y2015_bot3/wpilib/BUILD
@@ -0,0 +1,32 @@
+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',
+    '//y2015_bot3/control_loops/drivetrain:drivetrain_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/control_loops:queues',
+    '//frc971/wpilib:logging_queue',
+    '//y2015_bot3/autonomous:auto_queue',
+    '//y2015_bot3/control_loops/drivetrain:drivetrain_lib',
+    '//y2015_bot3/control_loops/elevator:elevator_lib',
+    '//y2015_bot3/control_loops/intake:intake_lib',
+  ],
+)
diff --git a/y2015_bot3/wpilib/wpilib.gyp b/y2015_bot3/wpilib/wpilib.gyp
new file mode 100644
index 0000000..81f2e9a
--- /dev/null
+++ b/y2015_bot3/wpilib/wpilib.gyp
@@ -0,0 +1,36 @@
+{
+  'targets': [
+    {
+      'target_name': 'wpilib_interface_bot3',
+      'type': 'executable',
+      'sources': [
+        'wpilib_interface.cc'
+      ],
+      'dependencies': [
+        '<(AOS)/linux_code/linux_code.gyp:init',
+        '<(AOS)/common/common.gyp:stl_mutex',
+        '<(AOS)/build/aos.gyp:logging',
+        '<(EXTERNALS):WPILib',
+        '<(DEPTH)/bot3/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
+        '<(AOS)/common/controls/controls.gyp:control_loop',
+        '<(AOS)/common/util/util.gyp:log_interval',
+        '<(AOS)/common/common.gyp:time',
+        '<(AOS)/common/logging/logging.gyp:queue_logging',
+        '<(AOS)/common/messages/messages.gyp:robot_state',
+        '<(AOS)/common/util/util.gyp:phased_loop',
+        '<(AOS)/common/messages/messages.gyp:robot_state',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:hall_effect',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:joystick_sender',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:loop_output_handler',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:buffered_pcm',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:gyro_sender',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+        '<(DEPTH)/frc971/wpilib/wpilib.gyp:logging_queue',
+        '<(DEPTH)/bot3/autonomous/autonomous.gyp:auto_queue',
+        '<(DEPTH)/bot3/control_loops/drivetrain/drivetrain.gyp:drivetrain_lib',
+        '<(DEPTH)/bot3/control_loops/elevator/elevator.gyp:elevator_lib',
+        '<(DEPTH)/bot3/control_loops/intake/intake.gyp:intake_lib',
+      ],
+    },
+  ],
+}
diff --git a/y2015_bot3/wpilib/wpilib_interface.cc b/y2015_bot3/wpilib/wpilib_interface.cc
new file mode 100644
index 0000000..f43fe8e
--- /dev/null
+++ b/y2015_bot3/wpilib/wpilib_interface.cc
@@ -0,0 +1,556 @@
+#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 "RobotBase.h"
+#include "dma.h"
+#include "ControllerPower.h"
+#ifndef WPILIB2015
+#include "DigitalGlitchFilter.h"
+#endif
+#include "DigitalInput.h"
+#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/control_loops/control_loops.q.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.q.h"
+#include "y2015_bot3/control_loops/elevator/elevator.q.h"
+#include "y2015_bot3/control_loops/intake/intake.q.h"
+#include "y2015_bot3/autonomous/auto.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/logging.q.h"
+#include "y2015_bot3/control_loops/drivetrain/drivetrain.h"
+#include "y2015_bot3/control_loops/elevator/elevator.h"
+#include "y2015_bot3/control_loops/intake/intake.h"
+
+
+#ifndef M_PI
+#define M_PI 3.14159265358979323846
+#endif
+
+using ::aos::util::SimpleLogInterval;
+using ::y2015_bot3::control_loops::drivetrain_queue;
+using ::y2015_bot3::control_loops::elevator_queue;
+using ::y2015_bot3::control_loops::intake_queue;
+using ::frc971::wpilib::BufferedPcm;
+using ::frc971::wpilib::BufferedSolenoid;
+using ::frc971::wpilib::LoopOutputHandler;
+using ::frc971::wpilib::JoystickSender;
+using ::frc971::wpilib::GyroSender;
+
+namespace y2015_bot3 {
+namespace wpilib {
+
+double drivetrain_translate(int32_t in) {
+  return static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*4x*/) *
+         ::y2015_bot3::control_loops::kDrivetrainEncoderRatio *
+         (4 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
+}
+
+double elevator_translate(int32_t in) {
+  return static_cast<double>(in) / (512.0 /*cpr*/ * 4.0 /*4x*/) *
+         ::y2015_bot3::control_loops::kElevEncoderRatio * (2 * M_PI /*radians*/) *
+         ::y2015_bot3::control_loops::kElevChainReduction *
+         ::y2015_bot3::control_loops::kElevGearboxOutputRadianDistance;
+}
+
+static const double kMaximumEncoderPulsesPerSecond =
+    4650.0 /* free speed RPM */ * 18.0 / 48.0 /* belt reduction */ /
+    60.0 /* seconds / minute */ * 512.0 /* CPR */ *
+    4.0 /* index pulse = 1/4 cycle */;
+
+// Reads in our inputs. (sensors, voltages, etc.)
+class SensorReader {
+ public:
+  SensorReader() {
+    // Set it to filter out anything shorter than 1/4 of the minimum pulse width
+    // we should ever see.
+    filter_.SetPeriodNanoSeconds(
+        static_cast<int>(1 / 4.0 / kMaximumEncoderPulsesPerSecond * 1e9 + 0.5));
+  }
+
+  // Drivetrain setters.
+  void set_left_encoder(::std::unique_ptr<Encoder> left_encoder) {
+    left_encoder_ = ::std::move(left_encoder);
+  }
+
+  void set_right_encoder(::std::unique_ptr<Encoder> right_encoder) {
+    right_encoder_ = ::std::move(right_encoder);
+  }
+
+  // Elevator setters.
+  void set_elevator_encoder(::std::unique_ptr<Encoder> encoder) {
+    filter_.Add(encoder.get());
+    elevator_encoder_ = ::std::move(encoder);
+  }
+
+  void set_elevator_zeroing_hall_effect(::std::unique_ptr<DigitalInput> hall) {
+    zeroing_hall_effect_ = ::std::move(hall);
+  }
+
+  void set_elevator_tote_sensor(::std::unique_ptr<AnalogInput> tote_sensor) {
+    tote_sensor_ = ::std::move(tote_sensor);
+  }
+
+  void operator()() {
+    LOG(INFO, "In sensor reader thread\n");
+    ::aos::SetCurrentThreadName("SensorReader");
+
+    my_pid_ = getpid();
+    ds_ =
+#ifdef WPILIB2015
+        DriverStation::GetInstance();
+#else
+        &DriverStation::GetInstance();
+#endif
+
+    LOG(INFO, "Things are now started\n");
+
+    ::aos::SetCurrentThreadRealtimePriority(kPriority);
+    while (run_) {
+      ::aos::time::PhasedLoopXMS(5, 4000);
+      RunIteration();
+    }
+  }
+
+  void RunIteration() {
+    // General
+    {
+      auto new_state = ::aos::robot_state.MakeMessage();
+
+      new_state->reader_pid = my_pid_;
+      new_state->outputs_enabled = ds_->IsSysActive();
+      new_state->browned_out = ds_->IsSysBrownedOut();
+
+      new_state->is_3v3_active = ControllerPower::GetEnabled3V3();
+      new_state->is_5v_active = ControllerPower::GetEnabled5V();
+      new_state->voltage_3v3 = ControllerPower::GetVoltage3V3();
+      new_state->voltage_5v = ControllerPower::GetVoltage5V();
+
+      new_state->voltage_roborio_in = ControllerPower::GetInputVoltage();
+      new_state->voltage_battery = ds_->GetBatteryVoltage();
+
+      LOG_STRUCT(DEBUG, "robot_state", *new_state);
+
+      new_state.Send();
+    }
+
+    // Drivetrain
+    {
+      auto drivetrain_message = drivetrain_queue.position.MakeMessage();
+      drivetrain_message->right_encoder =
+          -drivetrain_translate(right_encoder_->GetRaw());
+      drivetrain_message->left_encoder =
+          drivetrain_translate(left_encoder_->GetRaw());
+
+      drivetrain_message.Send();
+    }
+
+    // Elevator
+    {
+      // Update control loop positions.
+      auto elevator_message = elevator_queue.position.MakeMessage();
+      elevator_message->encoder =
+          elevator_translate(elevator_encoder_->GetRaw());
+      elevator_message->bottom_hall_effect = !zeroing_hall_effect_->Get();
+      elevator_message->has_tote = tote_sensor_->GetVoltage() > 2.5;
+
+      elevator_message.Send();
+    }
+
+    // Intake
+    {
+      auto intake_message = intake_queue.position.MakeMessage();
+      intake_message.Send();
+    }
+  }
+
+  void Quit() { run_ = false; }
+
+ private:
+  static const int kPriority = 30;
+  static const int kInterruptPriority = 55;
+
+  int32_t my_pid_;
+  DriverStation *ds_;
+
+  ::std::unique_ptr<Encoder> left_encoder_, right_encoder_, elevator_encoder_;
+  ::std::unique_ptr<DigitalInput> zeroing_hall_effect_;
+  ::std::unique_ptr<AnalogInput> tote_sensor_;
+
+  ::std::atomic<bool> run_{true};
+  DigitalGlitchFilter filter_;
+};
+
+// Writes out our pneumatic outputs.
+class SolenoidWriter {
+ public:
+  SolenoidWriter(const ::std::unique_ptr< ::frc971::wpilib::BufferedPcm> &pcm)
+      : pcm_(pcm),
+        elevator_(".y2015_bot3.control_loops.elevator_queue.output"),
+        intake_(".y2015_bot3.control_loops.intake_queue.output"),
+        can_grabber_control_(".y2015_bot3.autonomous.can_grabber_control") {}
+
+  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_elevator_passive_support(
+      ::std::unique_ptr<BufferedSolenoid> elevator_passive_support) {
+    elevator_passive_support_ = ::std::move(elevator_passive_support);
+  }
+
+  void set_can_grabber(::std::unique_ptr<BufferedSolenoid> can_grabber) {
+    can_grabber_ = ::std::move(can_grabber);
+  }
+
+  void set_elevator_can_support(
+      ::std::unique_ptr<BufferedSolenoid> elevator_can_support) {
+    elevator_can_support_ = ::std::move(elevator_can_support);
+  }
+
+  void set_intake_claw(::std::unique_ptr<BufferedSolenoid> intake_claw) {
+    intake_claw_ = ::std::move(intake_claw);
+  }
+
+  void operator()() {
+    ::aos::SetCurrentThreadName("Solenoids");
+    ::aos::SetCurrentThreadRealtimePriority(30);
+
+    while (run_) {
+      ::aos::time::PhasedLoopXMS(20, 1000);
+
+      // Can Grabber
+      {
+        can_grabber_control_.FetchLatest();
+        if (can_grabber_control_.get()) {
+          LOG_STRUCT(DEBUG, "solenoids", *can_grabber_control_);
+          can_grabber_->Set(can_grabber_control_->can_grabbers);
+        }
+      }
+
+      // Elevator
+      {
+        elevator_.FetchLatest();
+        if (elevator_.get()) {
+          LOG_STRUCT(DEBUG, "solenoids", *elevator_);
+          elevator_passive_support_->Set(!elevator_->passive_support);
+          elevator_can_support_->Set(!elevator_->can_support);
+        }
+      }
+
+      // Intake
+      {
+        intake_.FetchLatest();
+        if (intake_.get()) {
+          LOG_STRUCT(DEBUG, "solenoids", *intake_);
+          intake_claw_->Set(intake_->claw_closed);
+        }
+      }
+
+      // Compressor
+      ::aos::joystick_state.FetchLatest();
+      {
+        ::frc971::wpilib::PneumaticsToLog to_log;
+        {
+          // Refill if pneumatic pressure goes too low.
+          const bool compressor_on = !pressure_switch_->Get();
+          to_log.compressor_on = compressor_on;
+          if (compressor_on) {
+            compressor_relay_->Set(Relay::kForward);
+          } else {
+            compressor_relay_->Set(Relay::kOff);
+          }
+        }
+
+        pcm_->Flush();
+        to_log.read_solenoids = pcm_->GetAll();
+        LOG_STRUCT(DEBUG, "pneumatics info", to_log);
+      }
+    }
+  }
+
+  void Quit() { run_ = false; }
+
+ private:
+  const ::std::unique_ptr<BufferedPcm> &pcm_;
+
+  ::std::unique_ptr<BufferedSolenoid> elevator_passive_support_;
+  ::std::unique_ptr<BufferedSolenoid> elevator_can_support_;
+  ::std::unique_ptr<BufferedSolenoid> intake_claw_;
+  ::std::unique_ptr<BufferedSolenoid> can_grabber_;
+
+  ::std::unique_ptr<DigitalInput> pressure_switch_;
+  ::std::unique_ptr<Relay> compressor_relay_;
+
+  ::aos::Queue<::y2015_bot3::control_loops::ElevatorQueue::Output> elevator_;
+  ::aos::Queue<::y2015_bot3::control_loops::IntakeQueue::Output> intake_;
+  ::aos::Queue<::y2015_bot3::autonomous::CanGrabberControl> can_grabber_control_;
+
+  ::std::atomic<bool> run_{true};
+};
+
+// Writes out drivetrain voltages.
+class DrivetrainWriter : public LoopOutputHandler {
+ public:
+  void set_left_drivetrain_talon(::std::unique_ptr<Talon> t) {
+    left_drivetrain_talon_ = ::std::move(t);
+  }
+
+  void set_right_drivetrain_talon(::std::unique_ptr<Talon> t) {
+    right_drivetrain_talon_ = ::std::move(t);
+  }
+
+ private:
+  virtual void Read() override {
+    ::y2015_bot3::control_loops::drivetrain_queue.output.FetchAnother();
+  }
+
+  virtual void Write() override {
+    auto &queue = ::y2015_bot3::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_;
+};
+
+// Writes out elevator voltages.
+class ElevatorWriter : public LoopOutputHandler {
+ public:
+  void set_elevator_talon1(::std::unique_ptr<Talon> t) {
+    elevator_talon1_ = ::std::move(t);
+  }
+  void set_elevator_talon2(::std::unique_ptr<Talon> t) {
+    elevator_talon2_ = ::std::move(t);
+  }
+
+ private:
+  virtual void Read() override {
+    ::y2015_bot3::control_loops::elevator_queue.output.FetchAnother();
+  }
+
+  virtual void Write() override {
+    auto &queue = ::y2015_bot3::control_loops::elevator_queue.output;
+    LOG_STRUCT(DEBUG, "will output", *queue);
+    elevator_talon1_->Set(queue->elevator / 12.0);
+    elevator_talon2_->Set(-queue->elevator / 12.0);
+  }
+
+  virtual void Stop() override {
+    LOG(WARNING, "Elevator output too old.\n");
+    elevator_talon1_->Disable();
+    elevator_talon2_->Disable();
+  }
+
+  ::std::unique_ptr<Talon> elevator_talon1_;
+  ::std::unique_ptr<Talon> elevator_talon2_;
+};
+
+// Writes out intake voltages.
+class IntakeWriter : public LoopOutputHandler {
+ public:
+  void set_intake_talon1(::std::unique_ptr<Talon> t) {
+    intake_talon1_ = ::std::move(t);
+  }
+  void set_intake_talon2(::std::unique_ptr<Talon> t) {
+    intake_talon2_ = ::std::move(t);
+  }
+
+ private:
+  virtual void Read() override {
+    ::y2015_bot3::control_loops::intake_queue.output.FetchAnother();
+  }
+
+  virtual void Write() override {
+    auto &queue = ::y2015_bot3::control_loops::intake_queue.output;
+    LOG_STRUCT(DEBUG, "will output", *queue);
+    intake_talon1_->Set(queue->intake / 12.0);
+    intake_talon2_->Set(-queue->intake / 12.0);
+  }
+
+  virtual void Stop() override {
+    LOG(WARNING, "Intake output too old.\n");
+    intake_talon1_->Disable();
+    intake_talon2_->Disable();
+  }
+
+  ::std::unique_ptr<Talon> intake_talon1_;
+  ::std::unique_ptr<Talon> intake_talon2_;
+};
+
+// Writes out can grabber voltages.
+class CanGrabberWriter : public LoopOutputHandler {
+ public:
+  CanGrabberWriter() : LoopOutputHandler(::aos::time::Time::InSeconds(0.05)) {}
+
+  void set_can_grabber_talon1(::std::unique_ptr<Talon> t) {
+    can_grabber_talon1_ = ::std::move(t);
+  }
+
+  void set_can_grabber_talon2(::std::unique_ptr<Talon> t) {
+    can_grabber_talon2_ = ::std::move(t);
+  }
+
+ private:
+  virtual void Read() override {
+    ::y2015_bot3::autonomous::can_grabber_control.FetchAnother();
+  }
+
+  virtual void Write() override {
+    auto &queue = ::y2015_bot3::autonomous::can_grabber_control;
+    LOG_STRUCT(DEBUG, "will output", *queue);
+    can_grabber_talon1_->Set(queue->can_grabber_voltage / 12.0);
+    can_grabber_talon2_->Set(-queue->can_grabber_voltage / 12.0);
+  }
+
+  virtual void Stop() override {
+    LOG(WARNING, "Can grabber output too old\n");
+    can_grabber_talon1_->Disable();
+    can_grabber_talon2_->Disable();
+  }
+
+  ::std::unique_ptr<Talon> can_grabber_talon1_, can_grabber_talon2_;
+};
+
+// TODO(brian): Replace this with ::std::make_unique once all our toolchains
+// have support.
+template <class T, class... U>
+std::unique_ptr<T> make_unique(U &&... u) {
+  return std::unique_ptr<T>(new T(std::forward<U>(u)...));
+}
+
+class WPILibRobot : public RobotBase {
+ public:
+  ::std::unique_ptr<Encoder> encoder(int index) {
+    return make_unique<Encoder>(10 + index * 2, 11 + index * 2, false,
+                                Encoder::k4X);
+  }
+  virtual void StartCompetition() {
+    ::aos::InitNRT();
+    ::aos::SetCurrentThreadName("StartCompetition");
+
+    JoystickSender joystick_sender;
+    ::std::thread joystick_thread(::std::ref(joystick_sender));
+
+    SensorReader reader;
+    LOG(INFO, "Creating the reader\n");
+
+    reader.set_elevator_encoder(encoder(6));
+    reader.set_elevator_zeroing_hall_effect(make_unique<DigitalInput>(6));
+
+    reader.set_left_encoder(encoder(0));
+    reader.set_right_encoder(encoder(1));
+    reader.set_elevator_tote_sensor(make_unique<AnalogInput>(0));
+
+    ::std::thread reader_thread(::std::ref(reader));
+    GyroSender gyro_sender;
+    ::std::thread gyro_thread(::std::ref(gyro_sender));
+
+    DrivetrainWriter drivetrain_writer;
+    drivetrain_writer.set_left_drivetrain_talon(
+        ::std::unique_ptr<Talon>(new Talon(0)));
+    drivetrain_writer.set_right_drivetrain_talon(
+        ::std::unique_ptr<Talon>(new Talon(7)));
+    ::std::thread drivetrain_writer_thread(::std::ref(drivetrain_writer));
+
+    ElevatorWriter elevator_writer;
+    elevator_writer.set_elevator_talon1(::std::unique_ptr<Talon>(new Talon(1)));
+    elevator_writer.set_elevator_talon2(::std::unique_ptr<Talon>(new Talon(6)));
+    ::std::thread elevator_writer_thread(::std::ref(elevator_writer));
+
+    IntakeWriter intake_writer;
+    intake_writer.set_intake_talon1(::std::unique_ptr<Talon>(new Talon(2)));
+    intake_writer.set_intake_talon2(::std::unique_ptr<Talon>(new Talon(5)));
+    ::std::thread intake_writer_thread(::std::ref(intake_writer));
+
+    CanGrabberWriter can_grabber_writer;
+    can_grabber_writer.set_can_grabber_talon1(
+        ::std::unique_ptr<Talon>(new Talon(3)));
+    can_grabber_writer.set_can_grabber_talon2(
+        ::std::unique_ptr<Talon>(new Talon(4)));
+    ::std::thread can_grabber_writer_thread(::std::ref(can_grabber_writer));
+
+    ::std::unique_ptr<::frc971::wpilib::BufferedPcm> pcm(
+        new ::frc971::wpilib::BufferedPcm());
+    SolenoidWriter solenoid_writer(pcm);
+    solenoid_writer.set_pressure_switch(make_unique<DigitalInput>(9));
+    solenoid_writer.set_compressor_relay(make_unique<Relay>(0));
+    solenoid_writer.set_elevator_passive_support(pcm->MakeSolenoid(0));
+    solenoid_writer.set_elevator_can_support(pcm->MakeSolenoid(1));
+    solenoid_writer.set_intake_claw(pcm->MakeSolenoid(2));
+    solenoid_writer.set_can_grabber(pcm->MakeSolenoid(3));
+    ::std::thread solenoid_thread(::std::ref(solenoid_writer));
+
+    // Wait forever. Not much else to do...
+    PCHECK(select(0, nullptr, nullptr, nullptr, nullptr));
+
+    LOG(ERROR, "Exiting WPILibRobot\n");
+
+    joystick_sender.Quit();
+    joystick_thread.join();
+    reader.Quit();
+    reader_thread.join();
+    gyro_sender.Quit();
+    gyro_thread.join();
+
+    drivetrain_writer.Quit();
+    drivetrain_writer_thread.join();
+
+    elevator_writer.Quit();
+    elevator_writer_thread.join();
+
+    intake_writer.Quit();
+    intake_writer_thread.join();
+
+    can_grabber_writer.Quit();
+    can_grabber_writer_thread.join();
+
+    solenoid_writer.Quit();
+    solenoid_thread.join();
+
+    ::aos::Cleanup();
+  }
+};
+
+}  // namespace wpilib
+}  // namespace y2015_bot3
+
+START_ROBOT_CLASS(::y2015_bot3::wpilib::WPILibRobot);