Moved shooter to a subfolder.
diff --git a/frc971/control_loops/shooter/shooter.cc b/frc971/control_loops/shooter/shooter.cc
new file mode 100644
index 0000000..cecf10f
--- /dev/null
+++ b/frc971/control_loops/shooter/shooter.cc
@@ -0,0 +1,109 @@
+#include "frc971/control_loops/shooter/shooter.h"
+
+#include "aos/aos_core.h"
+
+#include "aos/common/control_loop/control_loops.q.h"
+#include "aos/common/logging/logging.h"
+
+#include "frc971/control_loops/shooter/shooter_motor_plant.h"
+
+namespace frc971 {
+namespace control_loops {
+
+ShooterMotor::ShooterMotor(control_loops::ShooterLoop *my_shooter)
+    : aos::control_loops::ControlLoop<control_loops::ShooterLoop>(my_shooter),
+    loop_(new StateFeedbackLoop<2, 1, 1>(MakeShooterLoop())),
+    history_position_(0),
+    position_goal_(0.0),
+    last_position_(0.0) {
+  memset(history_, 0, sizeof(history_));
+}
+
+/*static*/ const double ShooterMotor::dt = 0.01;
+/*static*/ const double ShooterMotor::kMaxSpeed =
+    10000.0 * (2.0 * M_PI) / 60.0 * 15.0 / 34.0;
+
+void ShooterMotor::RunIteration(
+    const control_loops::ShooterLoop::Goal *goal,
+    const control_loops::ShooterLoop::Position *position,
+    ::aos::control_loops::Output *output,
+    control_loops::ShooterLoop::Status *status) {
+  const double velocity_goal = std::min(goal->velocity, kMaxSpeed);
+  const double current_position = 
+      (position == NULL ? loop_->X_hat[0] : position->position);
+  double output_voltage = 0.0;
+
+  // Track the current position if the velocity goal is small.
+  if (velocity_goal <= 1.0) {
+    position_goal_ = current_position;
+  }
+
+  loop_->Y << current_position;
+
+  // Add the position to the history.
+  history_[history_position_] = current_position;
+  history_position_ = (history_position_ + 1) % kHistoryLength;
+
+  // Prevents integral windup by limiting the position error such that the
+  // error can't produce much more than full power.
+  const double kVelocityWeightScalar = 0.35;
+  const double max_reference =
+      (loop_->plant.U_max[0] - kVelocityWeightScalar * 
+       (velocity_goal - loop_->X_hat[1]) * loop_->K[1])
+      / loop_->K[0] + loop_->X_hat[0];
+  const double min_reference =
+      (loop_->plant.U_min[0] - kVelocityWeightScalar * 
+       (velocity_goal - loop_->X_hat[1]) * loop_->K[1]) 
+      / loop_->K[0] + loop_->X_hat[0];
+
+  position_goal_ = ::std::max(::std::min(position_goal_, max_reference),
+                              min_reference);
+  loop_->R << position_goal_, velocity_goal;
+  position_goal_ += velocity_goal * dt;
+  
+  loop_->Update(position, output == NULL);
+
+  // Kill power at low velocity goals.
+  if (velocity_goal < 1.0) {
+    loop_->U[0] = 0.0;
+  } else {
+    output_voltage = loop_->U[0];
+  }
+
+  LOG(DEBUG,
+      "PWM: %f, raw_pos: %f rotations: %f "
+      "junk velocity: %f, xhat[0]: %f xhat[1]: %f, R[0]: %f R[1]: %f\n",
+      output_voltage, current_position,
+      current_position / (2 * M_PI),
+      (current_position - last_position_) / dt,
+      loop_->X_hat[0], loop_->X_hat[1], loop_->R[0], loop_->R[1]);
+
+  // Calculates the velocity over the last kHistoryLength * .01 seconds
+  // by taking the difference between the current and next history positions.
+  int old_history_position = ((history_position_ == 0) ?
+        kHistoryLength : history_position_) - 1;
+  average_velocity_ = (history_[old_history_position] -
+      history_[history_position_]) * 100.0 / (double)(kHistoryLength - 1);
+
+  status->average_velocity = average_velocity_;
+
+  // Determine if the velocity is close enough to the goal to be ready.
+  if (std::abs(velocity_goal - average_velocity_) < 10.0 &&
+      velocity_goal != 0.0) {
+    LOG(DEBUG, "Steady: ");
+    status->ready = true;
+  } else {
+    LOG(DEBUG, "Not ready: ");
+    status->ready = false;
+  }
+  LOG(DEBUG, "avg = %f goal = %f\n", average_velocity_, velocity_goal);
+  
+  last_position_ = current_position;
+
+  if (output) {
+    output->voltage = output_voltage;
+  }
+}
+
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/frc971/control_loops/shooter/shooter.gyp b/frc971/control_loops/shooter/shooter.gyp
new file mode 100644
index 0000000..710bcb9
--- /dev/null
+++ b/frc971/control_loops/shooter/shooter.gyp
@@ -0,0 +1,70 @@
+{
+  'targets': [
+    {
+      'target_name': 'shooter_loop',
+      'type': 'static_library',
+      'sources': ['shooter_motor.q'],
+      'variables': {
+        'header_path': 'frc971/control_loops/shooter',
+      },
+      'dependencies': [
+        '<(AOS)/build/aos.gyp:libaos',
+        '<(AOS)/common/common.gyp:control_loop_queues',
+        '<(AOS)/common/common.gyp:queues',
+      ],
+      'export_dependent_settings': [
+        '<(AOS)/build/aos.gyp:libaos',
+        '<(AOS)/common/common.gyp:control_loop_queues',
+        '<(AOS)/common/common.gyp:queues',
+      ],
+      'includes': ['../../../aos/build/queues.gypi'],
+    },
+    {
+      'target_name': 'shooter_lib',
+      'type': 'static_library',
+      'sources': [
+        'shooter.cc',
+        'shooter_motor_plant.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/build/aos.gyp:libaos',
+        'shooter_loop',
+        '<(AOS)/common/common.gyp:controls',
+        '<(DEPTH)/frc971/frc971.gyp:common',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+      'export_dependent_settings': [
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+        '<(AOS)/common/common.gyp:controls',
+        'shooter_loop',
+      ],
+    },
+    {
+      'target_name': 'shooter_lib_test',
+      'type': 'executable',
+      'sources': [
+        'shooter_lib_test.cc',
+      ],
+      'dependencies': [
+        '<(EXTERNALS):gtest',
+        '<(AOS)/build/aos.gyp:libaos',
+        'shooter_loop',
+        'shooter_lib',
+        '<(AOS)/common/common.gyp:queue_testutils',
+        '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+      ],
+    },
+    {
+      'target_name': 'shooter',
+      'type': 'executable',
+      'sources': [
+        'shooter_main.cc',
+      ],
+      'dependencies': [
+        '<(AOS)/build/aos.gyp:libaos',
+        'shooter_lib',
+        'shooter_loop',
+      ],
+    },
+  ],
+}
diff --git a/frc971/control_loops/shooter/shooter.h b/frc971/control_loops/shooter/shooter.h
new file mode 100644
index 0000000..77c605b
--- /dev/null
+++ b/frc971/control_loops/shooter/shooter.h
@@ -0,0 +1,54 @@
+#ifndef FRC971_CONTROL_LOOPS_SHOOTER_H_
+#define FRC971_CONTROL_LOOPS_SHOOTER_H_
+
+#include <memory>
+
+#include "aos/common/control_loop/ControlLoop.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/shooter/shooter_motor.q.h"
+#include "frc971/control_loops/shooter/shooter_motor_plant.h"
+
+namespace frc971 {
+namespace control_loops {
+
+class ShooterMotor
+    : public aos::control_loops::ControlLoop<control_loops::ShooterLoop> {
+ public:
+  explicit ShooterMotor(
+      control_loops::ShooterLoop *my_shooter = &control_loops::shooter);
+
+  // Control loop time step.
+  static const double dt;
+
+  // Maximum speed of the shooter wheel which the encoder is rated for in
+  // rad/sec.
+  static const double kMaxSpeed;
+
+ protected:
+  virtual void RunIteration(
+      const control_loops::ShooterLoop::Goal *goal,
+      const control_loops::ShooterLoop::Position *position,
+      ::aos::control_loops::Output *output,
+      control_loops::ShooterLoop::Status *status);
+
+ private:
+  // The state feedback control loop to talk to.
+  ::std::unique_ptr<StateFeedbackLoop<2, 1, 1>> loop_;
+
+  // History array and stuff for determining average velocity and whether
+  // we are ready to shoot.
+  static const int kHistoryLength = 5;
+  double history_[kHistoryLength];
+  ptrdiff_t history_position_;
+  double average_velocity_;
+
+  double position_goal_;
+  double last_position_;
+
+  DISALLOW_COPY_AND_ASSIGN(ShooterMotor);
+};
+
+}  // namespace control_loops
+}  // namespace frc971
+
+#endif // FRC971_CONTROL_LOOPS_SHOOTER_H_
diff --git a/frc971/control_loops/shooter/shooter_lib_test.cc b/frc971/control_loops/shooter/shooter_lib_test.cc
new file mode 100644
index 0000000..beb62f1
--- /dev/null
+++ b/frc971/control_loops/shooter/shooter_lib_test.cc
@@ -0,0 +1,193 @@
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/queue.h"
+#include "aos/common/queue_testutils.h"
+#include "frc971/control_loops/shooter/shooter_motor.q.h"
+#include "frc971/control_loops/shooter/shooter.h"
+#include "frc971/constants.h"
+
+using ::aos::time::Time;
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+
+// Class which simulates the shooter and sends out queue messages with the
+// position.
+class ShooterMotorSimulation {
+ public:
+  // Constructs a shooter simulation. I'm not sure how the construction of
+  // the queue (my_shooter_loop_) actually works (same format as wrist).
+  ShooterMotorSimulation()
+      : shooter_plant_(new StateFeedbackPlant<2, 1, 1>(MakeShooterPlant())),
+        my_shooter_loop_(".frc971.control_loops.shooter",
+          0x78d8e372, ".frc971.control_loops.shooter.goal",
+          ".frc971.control_loops.shooter.position",
+          ".frc971.control_loops.shooter.output",
+          ".frc971.control_loops.shooter.status") {
+  }
+
+  // Sends a queue message with the position of the shooter.
+  void SendPositionMessage() {
+    ::aos::ScopedMessagePtr<control_loops::ShooterLoop::Position> position =
+      my_shooter_loop_.position.MakeMessage();
+    position->position = shooter_plant_->Y(0, 0);
+    position.Send();
+  }
+
+  // Simulates shooter for a single timestep.
+  void Simulate() {
+    EXPECT_TRUE(my_shooter_loop_.output.FetchLatest());
+    shooter_plant_->U << my_shooter_loop_.output->voltage;
+    shooter_plant_->Update();
+  }
+
+  ::std::unique_ptr<StateFeedbackPlant<2, 1, 1>> shooter_plant_;
+
+ private:
+  ShooterLoop my_shooter_loop_;
+};
+
+class ShooterTest : public ::testing::Test {
+ protected:
+  ShooterTest() : my_shooter_loop_(".frc971.control_loops.shooter",
+                                   0x78d8e372,
+                                   ".frc971.control_loops.shooter.goal",
+                                   ".frc971.control_loops.shooter.position",
+                                   ".frc971.control_loops.shooter.output",
+                                   ".frc971.control_loops.shooter.status"),
+                  shooter_motor_(&my_shooter_loop_),
+                  shooter_motor_plant_() {
+    // Flush the robot state queue so we can use clean shared memory for this
+    // test.
+    ::aos::robot_state.Clear();
+    SendDSPacket(true);
+  }
+
+  virtual ~ShooterTest() {
+    ::aos::robot_state.Clear();
+  }
+
+  // Update the robot state. Without this, the Iteration of the control loop
+  // will stop all the motors and the shooter won't go anywhere.
+  void SendDSPacket(bool enabled) {
+    ::aos::robot_state.MakeWithBuilder().enabled(enabled)
+                                        .autonomous(false)
+                                        .team_id(971).Send();
+    ::aos::robot_state.FetchLatest();
+  }
+
+  void VerifyNearGoal() {
+    my_shooter_loop_.goal.FetchLatest();
+    my_shooter_loop_.status.FetchLatest();
+    EXPECT_NEAR(my_shooter_loop_.goal->velocity,
+                my_shooter_loop_.status->average_velocity,
+                10.0);
+  }
+
+  // Bring up and down Core.
+  ::aos::common::testing::GlobalCoreInstance my_core;
+
+  // 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.
+  ShooterLoop my_shooter_loop_;
+
+  // Create a control loop and simulation.
+  ShooterMotor shooter_motor_;
+  ShooterMotorSimulation shooter_motor_plant_;
+};
+
+// Tests that the shooter does nothing when the goal is zero.
+TEST_F(ShooterTest, DoesNothing) {
+  my_shooter_loop_.goal.MakeWithBuilder().velocity(0.0).Send();
+  SendDSPacket(true);
+  shooter_motor_plant_.SendPositionMessage();
+  shooter_motor_.Iterate();
+  shooter_motor_plant_.Simulate();
+  VerifyNearGoal();
+  my_shooter_loop_.output.FetchLatest();
+  EXPECT_EQ(my_shooter_loop_.output->voltage, 0.0);
+}
+
+// Tests that the shooter spins up to speed and that it then spins down
+// without applying any power.
+TEST_F(ShooterTest, SpinUpAndDown) {
+  my_shooter_loop_.goal.MakeWithBuilder().velocity(450.0).Send();
+  bool is_done = false;
+  while (!is_done) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SendDSPacket(true);
+    EXPECT_TRUE(my_shooter_loop_.status.FetchLatest());
+    is_done = my_shooter_loop_.status->ready;
+  }
+  VerifyNearGoal();
+
+  my_shooter_loop_.goal.MakeWithBuilder().velocity(0.0).Send();
+  for (int i = 0; i < 100; ++i) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SendDSPacket(true);
+    EXPECT_TRUE(my_shooter_loop_.output.FetchLatest());
+    EXPECT_EQ(0.0, my_shooter_loop_.output->voltage);
+  }
+}
+
+// Test to make sure that it does not exceed the encoder's rated speed.
+TEST_F(ShooterTest, RateLimitTest) {
+  my_shooter_loop_.goal.MakeWithBuilder().velocity(1000.0).Send();
+  bool is_done = false;
+  while (!is_done) {
+    shooter_motor_plant_.SendPositionMessage();
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SendDSPacket(true);
+    EXPECT_TRUE(my_shooter_loop_.status.FetchLatest());
+    is_done = my_shooter_loop_.status->ready;
+  }
+
+  my_shooter_loop_.goal.FetchLatest();
+  my_shooter_loop_.status.FetchLatest();
+  EXPECT_GT(shooter_motor_.kMaxSpeed,
+            shooter_motor_plant_.shooter_plant_->X(1, 0));
+}
+
+// Tests that the shooter can spin up nicely while missing position packets.
+TEST_F(ShooterTest, MissingPositionMessages) {
+  my_shooter_loop_.goal.MakeWithBuilder().velocity(200.0).Send();
+  for (int i = 0; i < 100; ++i) {
+    if (i % 7) {
+      shooter_motor_plant_.SendPositionMessage();
+    }
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SendDSPacket(true);
+  }
+
+  VerifyNearGoal();
+}
+
+// Tests that the shooter can spin up nicely while disabled for a while.
+TEST_F(ShooterTest, Disabled) {
+  my_shooter_loop_.goal.MakeWithBuilder().velocity(200.0).Send();
+  for (int i = 0; i < 100; ++i) {
+    if (i % 7) {
+      shooter_motor_plant_.SendPositionMessage();
+    }
+    shooter_motor_.Iterate();
+    shooter_motor_plant_.Simulate();
+    SendDSPacket(i > 50);
+  }
+
+  VerifyNearGoal();
+}
+
+}  // namespace testing
+}  // namespace control_loops
+}  // namespace frc971
diff --git a/frc971/control_loops/shooter/shooter_main.cc b/frc971/control_loops/shooter/shooter_main.cc
new file mode 100644
index 0000000..72b820e
--- /dev/null
+++ b/frc971/control_loops/shooter/shooter_main.cc
@@ -0,0 +1,11 @@
+#include "frc971/control_loops/shooter/shooter.h"
+
+#include "aos/aos_core.h"
+
+int main() {
+  ::aos::Init();
+  frc971::control_loops::ShooterMotor shooter;
+  shooter.Run();
+  ::aos::Cleanup();
+  return 0;
+}
diff --git a/frc971/control_loops/shooter/shooter_motor.q b/frc971/control_loops/shooter/shooter_motor.q
new file mode 100644
index 0000000..f2abf25
--- /dev/null
+++ b/frc971/control_loops/shooter/shooter_motor.q
@@ -0,0 +1,31 @@
+package frc971.control_loops;
+
+import "aos/common/control_loop/control_loops.q";
+
+queue_group ShooterLoop {
+  implements aos.control_loops.ControlLoop;
+
+  message Goal {
+    // Goal velocity in rad/sec
+    double velocity;
+  };
+
+  message Status {
+    // True if the shooter is up to speed.
+    bool ready;
+    // The average velocity over the last 0.1 seconds.
+    double average_velocity;
+  };
+
+  message Position {
+    // The angle of the shooter wheel measured in rad/sec.
+    double position;
+  };
+
+  queue Goal goal;
+  queue Position position;
+  queue aos.control_loops.Output output;
+  queue Status status;
+};
+
+queue_group ShooterLoop shooter;
diff --git a/frc971/control_loops/shooter/shooter_motor_plant.cc b/frc971/control_loops/shooter/shooter_motor_plant.cc
new file mode 100644
index 0000000..c13ce2d
--- /dev/null
+++ b/frc971/control_loops/shooter/shooter_motor_plant.cc
@@ -0,0 +1,34 @@
+#include "frc971/control_loops/shooter/shooter_motor_plant.h"
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+
+StateFeedbackPlant<2, 1, 1> MakeShooterPlant() {
+  Eigen::Matrix<double, 2, 2> A;
+  A << 1.0, 0.0098571228289, 0.0, 0.971561310859;
+  Eigen::Matrix<double, 2, 1> B;
+  B << 0.00785005397639, 1.56249765488;
+  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 StateFeedbackPlant<2, 1, 1>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackLoop<2, 1, 1> MakeShooterLoop() {
+  Eigen::Matrix<double, 2, 1> L;
+  L << 1.07156131086, 28.0940195016;
+  Eigen::Matrix<double, 1, 2> K;
+  K << 0.486400730028, 0.247515916371;
+  return StateFeedbackLoop<2, 1, 1>(L, K, MakeShooterPlant());
+}
+
+}  // namespace frc971
+}  // namespace control_loops
diff --git a/frc971/control_loops/shooter/shooter_motor_plant.h b/frc971/control_loops/shooter/shooter_motor_plant.h
new file mode 100644
index 0000000..ac42b0b
--- /dev/null
+++ b/frc971/control_loops/shooter/shooter_motor_plant.h
@@ -0,0 +1,16 @@
+#ifndef FRC971_CONTROL_LOOPS_SHOOTER_SHOOTER_MOTOR_PLANT_H_
+#define FRC971_CONTROL_LOOPS_SHOOTER_SHOOTER_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlant<2, 1, 1> MakeShooterPlant();
+
+StateFeedbackLoop<2, 1, 1> MakeShooterLoop();
+
+}  // namespace frc971
+}  // namespace control_loops
+
+#endif  // FRC971_CONTROL_LOOPS_SHOOTER_SHOOTER_MOTOR_PLANT_H_