Make dual shooter.

Abstracted some stuff to get two shooters running in
the same process.

Change-Id: Id7617d6cf0d90c28fe2c07aefd3896eb592575dc
diff --git a/y2016/control_loops/shooter/BUILD b/y2016/control_loops/shooter/BUILD
index 6c15f15..cb3c0bc 100644
--- a/y2016/control_loops/shooter/BUILD
+++ b/y2016/control_loops/shooter/BUILD
@@ -51,9 +51,6 @@
     ':shooter_queue',
     ':shooter_plants',
     '//aos/common/controls:control_loop',
-    '//aos/common/util:log_interval',
-    '//aos/common/logging:queue_logging',
-    '//aos/common/logging:matrix_logging',
   ],
 )
 
diff --git a/y2016/control_loops/shooter/shooter.cc b/y2016/control_loops/shooter/shooter.cc
index 41e6f81..9a46906 100644
--- a/y2016/control_loops/shooter/shooter.cc
+++ b/y2016/control_loops/shooter/shooter.cc
@@ -6,131 +6,130 @@
 
 #include "y2016/control_loops/shooter/shooter_plant.h"
 
+
 namespace y2016 {
 namespace control_loops {
 
-Shooter::Shooter(control_loops::ShooterQueue *my_shooter)
-    : aos::controls::ControlLoop<control_loops::ShooterQueue>(my_shooter),
-      loop_(new StateFeedbackLoop<2, 1, 1>(
-          ::y2016::control_loops::shooter::MakeShooterLoop())),
-      history_position_(0),
-      position_goal_(0.0),
-      last_position_(0.0),
-      last_velocity_goal_(0) {
+ShooterSide::ShooterSide()
+    : loop_(new StateFeedbackLoop<2, 1, 1>(
+          ::y2016::control_loops::shooter::MakeShooterLoop())) {
   memset(history_, 0, sizeof(history_));
 }
 
-/*static*/ const double Shooter::dt = 0.005;
-/*static*/ const double Shooter::kMaxSpeed =
-    10000.0 * (2.0 * M_PI) / 60.0 * 15.0 / 34.0;
+void ShooterSide::SetGoal(double angular_velocity_goal_uncapped) {
+  angular_velocity_goal_ = std::min(angular_velocity_goal_uncapped,
+                                    kMaxSpeed);
+}
 
-void Shooter::RunIteration(
-    const control_loops::ShooterQueue::Goal *goal,
-    const control_loops::ShooterQueue::Position *position,
-    ::aos::control_loops::Output *output,
-    control_loops::ShooterQueue::Status *status) {
-  double velocity_goal = std::min(goal->velocity, kMaxSpeed);
-  const double current_position =
-      (position == NULL ? loop_->X_hat(0, 0) : position->position);
-  double output_voltage = 0.0;
+void ShooterSide::EstimatePositionTimestep() {
+  // NULL position, so look at the loop.
+  SetPosition(loop_->X_hat(0, 0));
+}
 
-  // TODO(phil): Set a queue to trigger a shot. For now, disable the fetch from
-  // the queue.
-  if (false) {
-  // if (index_loop.status.FetchLatest() || index_loop.status.get()) {
-    // if (index_loop.status->is_shooting) {
-    if (velocity_goal != last_velocity_goal_ && velocity_goal < 130) {
-      velocity_goal = last_velocity_goal_;
-    }
-  } else {
-    LOG(WARNING, "assuming index isn't shooting\n");
-  }
-  last_velocity_goal_ = velocity_goal;
+void ShooterSide::SetPosition(double current_position) {
+  current_position_ = current_position;
 
   // Track the current position if the velocity goal is small.
-  if (velocity_goal <= 1.0) {
-    position_goal_ = current_position;
-  }
+  if (angular_velocity_goal_ <= 1.0) position_goal_ = current_position_;
 
-  // TODO(phil): Does this change make sense?
-  // loop_->Y << current_position;
+  // Update position in the model.
   Eigen::Matrix<double, 1, 1> Y;
-  Y << current_position;
+  Y << current_position_;
   loop_->Correct(Y);
 
-  // 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_->U_max(0, 0) -
-       kVelocityWeightScalar * (velocity_goal - loop_->X_hat(1, 0)) *
-           loop_->K(0, 1)) /
+       kAngularVelocityWeightScalar *
+           (angular_velocity_goal_ - loop_->X_hat(1, 0)) * loop_->K(0, 1)) /
           loop_->K(0, 0) +
       loop_->X_hat(0, 0);
   const double min_reference =
       (loop_->U_min(0, 0) -
-       kVelocityWeightScalar * (velocity_goal - loop_->X_hat(1, 0)) *
-           loop_->K(0, 1)) /
+       kAngularVelocityWeightScalar *
+           (angular_velocity_goal_ - loop_->X_hat(1, 0)) * loop_->K(0, 1)) /
           loop_->K(0, 0) +
       loop_->X_hat(0, 0);
-
   position_goal_ =
       ::std::max(::std::min(position_goal_, max_reference), min_reference);
-  // TODO(phil): Does this change make sense?
-  // loop_->R << position_goal_, velocity_goal;
-  loop_->mutable_R(0, 0) = position_goal_;
-  loop_->mutable_R(1, 0) = velocity_goal;
-  position_goal_ += velocity_goal * dt;
 
-  // TODO(phil): Does this change make sense?
-  // loop_->Update(position, output == NULL);
-  loop_->Update(output == NULL);
+  loop_->mutable_R() << position_goal_, angular_velocity_goal_;
+  position_goal_ +=
+      angular_velocity_goal_ * ::aos::controls::kLoopFrequency.ToSeconds();
 
-  // Kill power at low velocity goals.
-  if (velocity_goal < 1.0) {
-    loop_->mutable_U(0, 0) = 0.0;
-  } else {
-    output_voltage = loop_->U(0, 0);
-  }
+  // Add the position to the history.
+  history_[history_position_] = current_position_;
+  history_position_ = (history_position_ + 1) % kHistoryLength;
+}
 
-  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,
-      // TODO(phil): Does this change make sense?
-      // loop_->X_hat[0], loop_->X_hat[1], loop_->R[0], loop_->R[1]);
-      loop_->X_hat(0, 0), loop_->X_hat(1, 0), loop_->R(0, 0), loop_->R(1, 0));
-
-  // Calculates the velocity over the last kHistoryLength * .01 seconds
-  // by taking the difference between the current and next history positions.
+const ShooterStatus ShooterSide::GetStatus() {
+  // Calculate average over dt * kHistoryLength.
   int old_history_position =
       ((history_position_ == 0) ? kHistoryLength : history_position_) - 1;
-  average_velocity_ =
-      (history_[old_history_position] - history_[history_position_]) / dt /
-      (double)(kHistoryLength - 1);
+  double avg_angular_velocity =
+      (history_[old_history_position] - history_[history_position_]) /
+      ::aos::controls::kLoopFrequency.ToSeconds() /
+      static_cast<double>(kHistoryLength - 1);
 
-  status->average_velocity = average_velocity_;
+  // Ready if average angular velocity is close to the goal.
+  bool ready = (std::abs(angular_velocity_goal_ - avg_angular_velocity) <
+                    kTolerance &&
+                angular_velocity_goal_ != 0.0);
 
-  // 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;
+  return {avg_angular_velocity, ready};
+}
+
+double ShooterSide::GetOutput() {
+  if (angular_velocity_goal_ < 1.0) {
+    // Kill power at low angular velocities.
+    return 0.0;
   }
-  LOG(DEBUG, "avg = %f goal = %f\n", average_velocity_, velocity_goal);
 
-  last_position_ = current_position;
+  return loop_->U(0, 0);
+}
+
+void ShooterSide::UpdateLoop(bool output_is_null) {
+  loop_->Update(output_is_null);
+}
+
+Shooter::Shooter(control_loops::ShooterQueue *my_shooter)
+    : aos::controls::ControlLoop<control_loops::ShooterQueue>(my_shooter) {}
+
+void Shooter::RunIteration(
+    const control_loops::ShooterQueue::Goal *goal,
+    const control_loops::ShooterQueue::Position *position,
+    control_loops::ShooterQueue::Output *output,
+    control_loops::ShooterQueue::Status *status) {
+  if (goal) {
+    // Update position/goal for our two shooter sides.
+    left_.SetGoal(goal->angular_velocity_left);
+    right_.SetGoal(goal->angular_velocity_right);
+
+    if (position == nullptr) {
+      left_.EstimatePositionTimestep();
+      right_.EstimatePositionTimestep();
+    } else {
+      left_.SetPosition(position->theta_left);
+      right_.SetPosition(position->theta_right);
+    }
+  }
+
+  ShooterStatus status_left = left_.GetStatus();
+  ShooterStatus status_right = right_.GetStatus();
+  status->avg_angular_velocity_left = status_left.avg_angular_velocity;
+  status->avg_angular_velocity_right = status_right.avg_angular_velocity;
+
+  status->ready_left = status_left.ready;
+  status->ready_right = status_right.ready;
+  status->ready_both = (status_left.ready && status_right.ready);
+
+  left_.UpdateLoop(output == nullptr);
+  right_.UpdateLoop(output == nullptr);
 
   if (output) {
-    output->voltage = output_voltage;
+    output->voltage_left = left_.GetOutput();
+    output->voltage_right = right_.GetOutput();
   }
 }
 
diff --git a/y2016/control_loops/shooter/shooter.h b/y2016/control_loops/shooter/shooter.h
index 766845d..6a3fa4d 100644
--- a/y2016/control_loops/shooter/shooter.h
+++ b/y2016/control_loops/shooter/shooter.h
@@ -12,42 +12,58 @@
 namespace y2016 {
 namespace control_loops {
 
-class Shooter
-    : public ::aos::controls::ControlLoop<control_loops::ShooterQueue> {
+namespace {
+// TODO(constants): Update.
+const double kTolerance = 10.0;
+const double kMaxSpeed = 10000.0 * (2.0 * M_PI) / 60.0 * 15.0 / 34.0;
+const double kAngularVelocityWeightScalar = 0.35;
+}  // namespace
+
+struct ShooterStatus {
+  double avg_angular_velocity;
+  bool ready;
+};
+
+class ShooterSide {
  public:
-  explicit Shooter(
-      control_loops::ShooterQueue *my_shooter = &control_loops::shooter_queue);
+  ShooterSide();
 
-  // 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::ShooterQueue::Goal *goal,
-      const control_loops::ShooterQueue::Position *position,
-      ::aos::control_loops::Output *output,
-      control_loops::ShooterQueue::Status *status);
+  void SetGoal(double angular_velocity_goal);
+  void EstimatePositionTimestep();
+  void SetPosition(double current_position);
+  const ShooterStatus GetStatus();
+  double GetOutput();
+  void UpdateLoop(bool output_is_null);
 
  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.
+  double current_position_ = 0.0;
+  double position_goal_ = 0.0;
+  double angular_velocity_goal_ = 0.0;
+
+  // History array for calculating a filtered angular velocity.
   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(ShooterSide);
+};
 
-  // For making sure it keeps spinning if we're shooting.
-  double last_velocity_goal_;
+class Shooter
+    : public ::aos::controls::ControlLoop<control_loops::ShooterQueue> {
+ public:
+  explicit Shooter(control_loops::ShooterQueue *shooter_queue =
+                       &control_loops::shooter_queue);
+
+ protected:
+  void RunIteration(const control_loops::ShooterQueue::Goal *goal,
+                    const control_loops::ShooterQueue::Position *position,
+                    control_loops::ShooterQueue::Output *output,
+                    control_loops::ShooterQueue::Status *status) override;
+
+ private:
+  ShooterSide left_, right_;
 
   DISALLOW_COPY_AND_ASSIGN(Shooter);
 };
diff --git a/y2016/control_loops/shooter/shooter.q b/y2016/control_loops/shooter/shooter.q
index 57d54f9..49575fb 100644
--- a/y2016/control_loops/shooter/shooter.q
+++ b/y2016/control_loops/shooter/shooter.q
@@ -6,26 +6,40 @@
 queue_group ShooterQueue {
   implements aos.control_loops.ControlLoop;
 
-  message Goal {
-    // Goal velocity in rad/sec
-    double velocity;
-  };
+  // All angles are in radians, and angular velocities are in rad/sec. For all
+  // angular velocities, positive is shooting the ball out of the robot.
 
-  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 Goal {
+    // Angular velocity goals in rad/sec.
+    double angular_velocity_left;
+    double angular_velocity_right;
   };
 
   message Position {
-    // The angle of the shooter wheel measured in rad/sec.
-    double position;
+    // Wheel angle in rad/sec.
+    double theta_left;
+    double theta_right;
+  };
+
+  message Status {
+    bool ready_left;
+    bool ready_right;
+    // Is the shooter ready to shoot?
+    bool ready_both;
+
+    // Average angular velocities over dt * kHistoryLength.
+    double avg_angular_velocity_left;
+    double avg_angular_velocity_right;
+  };
+
+  message Output {
+    double voltage_left;
+    double voltage_right;
   };
 
   queue Goal goal;
   queue Position position;
-  queue aos.control_loops.Output output;
+  queue Output output;
   queue Status status;
 };
 
diff --git a/y2016/control_loops/shooter/shooter_lib_test.cc b/y2016/control_loops/shooter/shooter_lib_test.cc
index cf5a810..9ec0334 100644
--- a/y2016/control_loops/shooter/shooter_lib_test.cc
+++ b/y2016/control_loops/shooter/shooter_lib_test.cc
@@ -7,8 +7,9 @@
 #include "gtest/gtest.h"
 #include "aos/common/queue.h"
 #include "aos/common/controls/control_loop_test.h"
-#include "y2016/control_loops/shooter/shooter.q.h"
 #include "frc971/control_loops/team_number_test_environment.h"
+#include "y2016/control_loops/shooter/shooter.q.h"
+#include "y2016/control_loops/shooter/shooter.h"
 
 using ::aos::time::Time;
 using ::frc971::control_loops::testing::kTeamNumber;
@@ -21,10 +22,11 @@
 // position.
 class ShooterSimulation {
  public:
-  // Constructs a shooter simulation. I'm not sure how the construction of
-  // the queue (shooter_queue_) actually works (same format as wrist).
+  // Constructs a shooter simulation.
   ShooterSimulation()
-      : shooter_plant_(new StateFeedbackPlant<2, 1, 1>(
+      : shooter_plant_left_(new StateFeedbackPlant<2, 1, 1>(
+            ::y2016::control_loops::shooter::MakeShooterPlant())),
+        shooter_plant_right_(new StateFeedbackPlant<2, 1, 1>(
             ::y2016::control_loops::shooter::MakeShooterPlant())),
         shooter_queue_(".y2016.control_loops.shooter", 0x78d8e372,
                        ".y2016.control_loops.shooter.goal",
@@ -37,7 +39,8 @@
     ::aos::ScopedMessagePtr<control_loops::ShooterQueue::Position> position =
         shooter_queue_.position.MakeMessage();
 
-    position->position = shooter_plant_->Y(0, 0);
+    position->theta_left = shooter_plant_left_->Y(0, 0);
+    position->theta_right = shooter_plant_right_->Y(0, 0);
     position.Send();
   }
 
@@ -45,11 +48,16 @@
   void Simulate() {
     EXPECT_TRUE(shooter_queue_.output.FetchLatest());
 
-    shooter_plant_->mutable_U(0, 0) = shooter_queue_.output->voltage;
-    shooter_plant_->Update();
+    shooter_plant_left_->mutable_U(0, 0) = shooter_queue_.output->voltage_left;
+    shooter_plant_right_->mutable_U(0, 0) =
+        shooter_queue_.output->voltage_right;
+
+    shooter_plant_left_->Update();
+    shooter_plant_right_->Update();
   }
 
-  ::std::unique_ptr<StateFeedbackPlant<2, 1, 1>> shooter_plant_;
+  ::std::unique_ptr<StateFeedbackPlant<2, 1, 1>> shooter_plant_left_,
+      shooter_plant_right_;
 
  private:
   ShooterQueue shooter_queue_;
@@ -65,8 +73,6 @@
                        ".y2016.control_loops.shooter.status"),
         shooter_(&shooter_queue_),
         shooter_plant_() {
-    // Flush the robot state queue so we can use clean shared memory for this
-    // test.
     set_team_id(kTeamNumber);
   }
 
@@ -77,12 +83,13 @@
     EXPECT_TRUE(shooter_queue_.goal.get() != nullptr);
     EXPECT_TRUE(shooter_queue_.status.get() != nullptr);
 
-    EXPECT_NEAR(shooter_queue_.goal->velocity,
-                shooter_queue_.status->average_velocity, 10.0);
+    EXPECT_NEAR(shooter_queue_.goal->angular_velocity_left,
+                shooter_queue_.status->avg_angular_velocity_left, 10.0);
+    EXPECT_NEAR(shooter_queue_.goal->angular_velocity_right,
+                shooter_queue_.status->avg_angular_velocity_right, 10.0);
   }
 
-  // Runs one iteration of the whole simulation and checks that separation
-  // remains reasonable.
+  // Runs one iteration of the whole simulation.
   void RunIteration(bool enabled = true) {
     SendMessages(enabled);
 
@@ -102,8 +109,8 @@
   }
 
   // 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.
+  // that it points to.  Otherwise, we will have a pointer to shared memory that
+  // is no longer valid.
   ShooterQueue shooter_queue_;
 
   // Create a control loop and simulation.
@@ -113,43 +120,58 @@
 
 // Tests that the shooter does nothing when the goal is zero.
 TEST_F(ShooterTest, DoesNothing) {
-  ASSERT_TRUE(shooter_queue_.goal.MakeWithBuilder().velocity(0.0).Send());
+  ASSERT_TRUE(shooter_queue_.goal.MakeWithBuilder()
+                  .angular_velocity_left(0.0)
+                  .angular_velocity_right(0.0)
+                  .Send());
   RunIteration();
 
   VerifyNearGoal();
 
   EXPECT_TRUE(shooter_queue_.output.FetchLatest());
-  EXPECT_EQ(shooter_queue_.output->voltage, 0.0);
+  EXPECT_EQ(shooter_queue_.output->voltage_left, 0.0);
+  EXPECT_EQ(shooter_queue_.output->voltage_right, 0.0);
 }
 
 // Tests that the shooter spins up to speed and that it then spins down
 // without applying any power.
 TEST_F(ShooterTest, SpinUpAndDown) {
   // Spin up.
-  EXPECT_TRUE(shooter_queue_.goal.MakeWithBuilder().velocity(450.0).Send());
+  EXPECT_TRUE(shooter_queue_.goal.MakeWithBuilder()
+                  .angular_velocity_left(450.0)
+                  .angular_velocity_right(450.0)
+                  .Send());
   RunForTime(Time::InSeconds(10));
   VerifyNearGoal();
-  EXPECT_TRUE(shooter_queue_.status->ready);
-  EXPECT_TRUE(shooter_queue_.goal.MakeWithBuilder().velocity(0.0).Send());
+  EXPECT_TRUE(shooter_queue_.status->ready_both);
+  EXPECT_TRUE(shooter_queue_.goal.MakeWithBuilder()
+                  .angular_velocity_left(0.0)
+                  .angular_velocity_right(0.0)
+                  .Send());
 
   // Make sure we don't apply voltage on spin-down.
   RunIteration();
   EXPECT_TRUE(shooter_queue_.output.FetchLatest());
-  EXPECT_EQ(0.0, shooter_queue_.output->voltage);
+  EXPECT_EQ(0.0, shooter_queue_.output->voltage_left);
+  EXPECT_EQ(0.0, shooter_queue_.output->voltage_right);
 
   // Continue to stop.
   RunForTime(Time::InSeconds(5));
   EXPECT_TRUE(shooter_queue_.output.FetchLatest());
-  EXPECT_EQ(0.0, shooter_queue_.output->voltage);
+  EXPECT_EQ(0.0, shooter_queue_.output->voltage_left);
+  EXPECT_EQ(0.0, shooter_queue_.output->voltage_right);
 }
 
-// Test to make sure that it does not exceed the encoder's rated speed.
-TEST_F(ShooterTest, RateLimitTest) {
-  ASSERT_TRUE(shooter_queue_.goal.MakeWithBuilder().velocity(1000.0).Send());
-
-  RunForTime(Time::InSeconds(10));
-  EXPECT_TRUE(shooter_queue_.status.FetchLatest());
-  EXPECT_TRUE(shooter_queue_.status->ready);
+// Tests that the shooter doesn't say it is ready if one side isn't up to speed.
+// According to our tuning, we may overshoot the goal on one shooter and
+// mistakenly say that we are ready. This test should look at both extremes.
+TEST_F(ShooterTest, SideLagTest) {
+  // Spin up.
+  EXPECT_TRUE(shooter_queue_.goal.MakeWithBuilder()
+                  .angular_velocity_left(20.0)
+                  .angular_velocity_right(450.0)
+                  .Send());
+  RunForTime(Time::InSeconds(0.1));
 
   shooter_queue_.goal.FetchLatest();
   shooter_queue_.status.FetchLatest();
@@ -157,12 +179,55 @@
   EXPECT_TRUE(shooter_queue_.goal.get() != nullptr);
   EXPECT_TRUE(shooter_queue_.status.get() != nullptr);
 
-  EXPECT_GT(shooter_.kMaxSpeed, shooter_queue_.status->average_velocity);
+  // Left should be up to speed, right shouldn't.
+  EXPECT_TRUE(shooter_queue_.status->ready_left);
+  EXPECT_FALSE(shooter_queue_.status->ready_right);
+  EXPECT_FALSE(shooter_queue_.status->ready_both);
+
+  RunForTime(Time::InSeconds(5));
+
+  shooter_queue_.goal.FetchLatest();
+  shooter_queue_.status.FetchLatest();
+
+  EXPECT_TRUE(shooter_queue_.goal.get() != nullptr);
+  EXPECT_TRUE(shooter_queue_.status.get() != nullptr);
+
+  // Both should be up to speed.
+  EXPECT_TRUE(shooter_queue_.status->ready_left);
+  EXPECT_TRUE(shooter_queue_.status->ready_right);
+  EXPECT_TRUE(shooter_queue_.status->ready_both);
+}
+
+// Test to make sure that it does not exceed the encoder's rated speed.
+TEST_F(ShooterTest, RateLimitTest) {
+  ASSERT_TRUE(shooter_queue_.goal.MakeWithBuilder()
+                  .angular_velocity_left(1000.0)
+                  .angular_velocity_right(1000.0)
+                  .Send());
+
+  RunForTime(Time::InSeconds(10));
+  EXPECT_TRUE(shooter_queue_.status.FetchLatest());
+  EXPECT_TRUE(shooter_queue_.status->ready_both);
+
+  shooter_queue_.goal.FetchLatest();
+  shooter_queue_.status.FetchLatest();
+
+  EXPECT_TRUE(shooter_queue_.goal.get() != nullptr);
+  EXPECT_TRUE(shooter_queue_.status.get() != nullptr);
+
+  EXPECT_GT(::y2016::control_loops::kMaxSpeed,
+            shooter_queue_.status->avg_angular_velocity_left);
+
+  EXPECT_GT(::y2016::control_loops::kMaxSpeed,
+            shooter_queue_.status->avg_angular_velocity_right);
 }
 
 // Tests that the shooter can spin up nicely while missing position packets.
 TEST_F(ShooterTest, MissingPositionMessages) {
-  ASSERT_TRUE(shooter_queue_.goal.MakeWithBuilder().velocity(200.0).Send());
+  ASSERT_TRUE(shooter_queue_.goal.MakeWithBuilder()
+                  .angular_velocity_left(200.0)
+                  .angular_velocity_right(200.0)
+                  .Send());
   for (int i = 0; i < 100; ++i) {
     if (i % 7) {
       shooter_plant_.SendPositionMessage();
@@ -175,8 +240,13 @@
 }
 
 // Tests that the shooter can spin up nicely while disabled for a while.
+// TODO(comran): Update this test, since it's the same as
+// MissingPositionMessages.
 TEST_F(ShooterTest, Disabled) {
-  ASSERT_TRUE(shooter_queue_.goal.MakeWithBuilder().velocity(200.0).Send());
+  ASSERT_TRUE(shooter_queue_.goal.MakeWithBuilder()
+                  .angular_velocity_left(200.0)
+                  .angular_velocity_right(200.0)
+                  .Send());
   for (int i = 0; i < 100; ++i) {
     if (i % 7) {
       shooter_plant_.SendPositionMessage();