Added a start at a fridge.

Change-Id: I5bab9686f966368161ede528ff7abf038d7bcb9a
diff --git a/frc971/control_loops/fridge/fridge.cc b/frc971/control_loops/fridge/fridge.cc
index a226915..d2e7bbf 100644
--- a/frc971/control_loops/fridge/fridge.cc
+++ b/frc971/control_loops/fridge/fridge.cc
@@ -1,26 +1,479 @@
 #include "frc971/control_loops/fridge/fridge.h"
 
+#include <cmath>
+
 #include "aos/common/controls/control_loops.q.h"
 #include "aos/common/logging/logging.h"
 
 #include "frc971/control_loops/fridge/elevator_motor_plant.h"
 #include "frc971/control_loops/fridge/arm_motor_plant.h"
+#include "frc971/zeroing/zeroing.h"
+
+#include "frc971/constants.h"
 
 namespace frc971 {
 namespace control_loops {
 
+constexpr double Fridge::dt;
+
+namespace {
+constexpr double kZeroingVoltage = 1.0;
+constexpr double kElevatorZeroingVelocity = 0.1;
+constexpr double kArmZeroingVelocity = 0.1;
+}  // namespace
+
+
+void CappedStateFeedbackLoop::CapU() {
+  // TODO(austin): Use Campbell's code.
+  if (mutable_U(0, 0) > max_voltage_) {
+    mutable_U(0, 0) = max_voltage_;
+  }
+  if (mutable_U(1, 0) > max_voltage_) {
+    mutable_U(1, 0) = max_voltage_;
+  }
+  if (mutable_U(0, 0) < -max_voltage_) {
+    mutable_U(0, 0) = -max_voltage_;
+  }
+  if (mutable_U(1, 0) < -max_voltage_) {
+    mutable_U(1, 0) = -max_voltage_;
+  }
+}
+
+Eigen::Matrix<double, 2, 1>
+CappedStateFeedbackLoop::UnsaturateOutputGoalChange() {
+  // Compute the K matrix used to compensate for position errors.
+  Eigen::Matrix<double, 2, 2> Kp;
+  Kp.setZero();
+  Kp.col(0) = K().col(0);
+  Kp.col(1) = K().col(2);
+
+  Eigen::Matrix<double, 2, 2> Kp_inv = Kp.inverse();
+
+  // Compute how much we need to change R in order to achieve the change in U
+  // that was observed.
+  Eigen::Matrix<double, 2, 1> deltaR = -Kp_inv * (U_uncapped() - U());
+  return deltaR;
+}
+
 Fridge::Fridge(control_loops::FridgeQueue *fridge)
     : aos::controls::ControlLoop<control_loops::FridgeQueue>(fridge),
-      arm_loop_(new StateFeedbackLoop<4, 2, 2>(MakeArmLoop())),
-      elev_loop_(new StateFeedbackLoop<4, 2, 2>(MakeElevatorLoop())) {}
+      arm_loop_(new CappedStateFeedbackLoop(
+          StateFeedbackLoop<4, 2, 2>(MakeArmLoop()))),
+      elevator_loop_(new CappedStateFeedbackLoop(
+          StateFeedbackLoop<4, 2, 2>(MakeElevatorLoop()))),
+      left_arm_estimator_(constants::GetValues().left_arm_zeroing_constants),
+      right_arm_estimator_(constants::GetValues().right_arm_zeroing_constants),
+      left_elevator_estimator_(
+          constants::GetValues().left_elevator_zeroing_constants),
+      right_elevator_estimator_(
+          constants::GetValues().right_elevator_zeroing_constants) {}
 
-void Fridge::RunIteration(
-    const control_loops::FridgeQueue::Goal * /*goal*/,
-    const control_loops::FridgeQueue::Position * /*position*/,
-    control_loops::FridgeQueue::Output * /*output*/,
-    control_loops::FridgeQueue::Status * /*status*/) {
+void Fridge::UpdateZeroingState() {
+  if (left_elevator_estimator_.offset_ratio_ready() < 0.5 ||
+      right_elevator_estimator_.offset_ratio_ready() < 0.5 ||
+      left_arm_estimator_.offset_ratio_ready() < 0.5 ||
+      right_arm_estimator_.offset_ratio_ready() < 0.5) {
+    state_ = INITIALIZING;
+  } else if (!left_elevator_estimator_.zeroed() ||
+      !right_elevator_estimator_.zeroed()) {
+    state_ = ZEROING_ELEVATOR;
+  } else if (!left_arm_estimator_.zeroed() ||
+      !right_arm_estimator_.zeroed()) {
+    state_ = ZEROING_ARM;
+  } else {
+    state_ = RUNNING;
+  }
+}
 
-  LOG(DEBUG, "Hi Brian!\n");
+void Fridge::Correct() {
+  {
+    Eigen::Matrix<double, 2, 1> Y;
+    Y << left_elevator(), right_elevator();
+    elevator_loop_->Correct(Y);
+  }
+
+  {
+    Eigen::Matrix<double, 2, 1> Y;
+    Y << left_arm(), right_arm();
+    arm_loop_->Correct(Y);
+  }
+}
+
+void Fridge::SetElevatorOffset(double left_offset, double right_offset) {
+  double left_doffset = left_offset - left_elevator_offset_;
+  double right_doffset = right_offset - right_elevator_offset_;
+
+  // Adjust the average height and height difference between the two sides.
+  // The derivatives of both should not need to be updated since the speeds
+  // haven't changed.
+  // The height difference is calculated as left - right, not right - left.
+  elevator_loop_->mutable_X_hat(0, 0) += (left_doffset + right_doffset) / 2;
+  elevator_loop_->mutable_X_hat(2, 0) += (left_doffset - right_doffset) / 2;
+
+  // Modify the zeroing goal.
+  elevator_goal_ += (left_doffset + right_doffset) / 2;
+
+  // Update the cached offset values to the actual values.
+  left_elevator_offset_ = left_offset;
+  right_elevator_offset_ = right_offset;
+}
+
+void Fridge::SetArmOffset(double left_offset, double right_offset) {
+  double left_doffset = left_offset - left_arm_offset_;
+  double right_doffset = right_offset - right_arm_offset_;
+
+  // Adjust the average angle and angle difference between the two sides.
+  // The derivatives of both should not need to be updated since the speeds
+  // haven't changed.
+  arm_loop_->mutable_X_hat(0, 0) += (left_doffset + right_doffset) / 2;
+  arm_loop_->mutable_X_hat(2, 0) += (left_doffset - right_doffset) / 2;
+
+  // Modify the zeroing goal.
+  arm_goal_ += (left_doffset + right_doffset) / 2;
+
+  // Update the cached offset values to the actual values.
+  left_arm_offset_ = left_offset;
+  right_arm_offset_ = right_offset;
+}
+
+double Fridge::estimated_left_elevator() {
+  return current_position_.elevator.left.encoder +
+         left_elevator_estimator_.offset();
+}
+double Fridge::estimated_right_elevator() {
+  return current_position_.elevator.right.encoder +
+         right_elevator_estimator_.offset();
+}
+
+double Fridge::estimated_elevator() {
+  return (estimated_left_elevator() + estimated_right_elevator()) / 2.0;
+}
+
+double Fridge::estimated_left_arm() {
+  return current_position_.elevator.left.encoder + left_arm_estimator_.offset();
+}
+double Fridge::estimated_right_arm() {
+  return current_position_.elevator.right.encoder +
+         right_arm_estimator_.offset();
+}
+double Fridge::estimated_arm() {
+  return (estimated_left_arm() + estimated_right_arm()) / 2.0;
+}
+
+double Fridge::left_elevator() {
+  return current_position_.elevator.left.encoder + left_elevator_offset_;
+}
+double Fridge::right_elevator() {
+  return current_position_.elevator.right.encoder + right_elevator_offset_;
+}
+
+double Fridge::elevator() { return (left_elevator() + right_elevator()) / 2.0; }
+
+double Fridge::left_arm() {
+  return current_position_.arm.left.encoder + left_arm_offset_;
+}
+double Fridge::right_arm() {
+  return current_position_.arm.right.encoder + right_arm_offset_;
+}
+double Fridge::arm() { return (left_arm() + right_arm()) / 2.0; }
+
+double Fridge::elevator_zeroing_velocity() {
+  double average_elevator =
+      (constants::GetValues().fridge.elevator.lower_limit +
+       constants::GetValues().fridge.elevator.upper_limit) /
+      2.0;
+
+  const double pulse_width = ::std::max(
+      constants::GetValues().left_elevator_zeroing_constants.index_difference,
+      constants::GetValues().right_elevator_zeroing_constants.index_difference);
+
+  if (elevator_zeroing_velocity_ == 0) {
+    if (estimated_elevator() > average_elevator) {
+      elevator_zeroing_velocity_ = -kElevatorZeroingVelocity;
+    } else {
+      elevator_zeroing_velocity_ = kElevatorZeroingVelocity;
+    }
+  } else if (elevator_zeroing_velocity_ > 0 &&
+             estimated_elevator() > average_elevator + 2 * pulse_width) {
+    elevator_zeroing_velocity_ = -kElevatorZeroingVelocity;
+  } else if (elevator_zeroing_velocity_ < 0 &&
+             estimated_elevator() < average_elevator - 2 * pulse_width) {
+    elevator_zeroing_velocity_ = kElevatorZeroingVelocity;
+  }
+  return elevator_zeroing_velocity_;
+}
+
+double Fridge::arm_zeroing_velocity() {
+  const double average_arm = (constants::GetValues().fridge.arm.lower_limit +
+                              constants::GetValues().fridge.arm.upper_limit) /
+                             2.0;
+  const double pulse_width = ::std::max(
+      constants::GetValues().right_arm_zeroing_constants.index_difference,
+      constants::GetValues().left_arm_zeroing_constants.index_difference);
+
+  if (arm_zeroing_velocity_ == 0) {
+    if (estimated_arm() > average_arm) {
+      arm_zeroing_velocity_ = -kArmZeroingVelocity;
+    } else {
+      arm_zeroing_velocity_ = kArmZeroingVelocity;
+    }
+  } else if (arm_zeroing_velocity_ > 0.0 &&
+             estimated_arm() > average_arm + 2.0 * pulse_width) {
+    arm_zeroing_velocity_ = -kArmZeroingVelocity;
+  } else if (arm_zeroing_velocity_ < 0.0 &&
+             estimated_arm() < average_arm - 2.0 * pulse_width) {
+    arm_zeroing_velocity_ = kArmZeroingVelocity;
+  }
+  return arm_zeroing_velocity_;
+}
+
+void Fridge::RunIteration(const control_loops::FridgeQueue::Goal *goal,
+                          const control_loops::FridgeQueue::Position *position,
+                          control_loops::FridgeQueue::Output *output,
+                          control_loops::FridgeQueue::Status *status) {
+  // Get a reference to the constants struct since we use it so often in this
+  // code.
+  auto &values = constants::GetValues();
+
+  // Bool to track if we should turn the motors on or not.
+  bool disable = output == nullptr;
+  double elevator_goal_velocity = 0.0;
+  double arm_goal_velocity = 0.0;
+
+  // Save the current position so it can be used easily in the class.
+  current_position_ = *position;
+
+  left_elevator_estimator_.UpdateEstimate(position->elevator.left);
+  right_elevator_estimator_.UpdateEstimate(position->elevator.right);
+  left_arm_estimator_.UpdateEstimate(position->arm.left);
+  right_arm_estimator_.UpdateEstimate(position->arm.right);
+
+  if (state_ != UNINITIALIZED) {
+    Correct();
+  }
+
+  // Zeroing will work as follows:
+  // At startup, record the offset of the two halves of the two subsystems.
+  // Then, start moving the elevator towards the center until both halves are
+  // zeroed.
+  // Then, start moving the claw towards the center until both halves are
+  // zeroed.
+  // Then, done!
+
+  // We'll then need code to do sanity checking on values.
+
+  // Now, we need to figure out which way to go.
+
+  switch (state_) {
+    case UNINITIALIZED:
+      LOG(DEBUG, "Uninitialized\n");
+      // Startup.  Assume that we are at the origin everywhere.
+      // This records the encoder offset between the two sides of the elevator.
+      left_elevator_offset_ = -position->elevator.left.encoder;
+      right_elevator_offset_ = -position->elevator.right.encoder;
+      left_arm_offset_ = -position->arm.left.encoder;
+      right_arm_offset_ = -position->arm.right.encoder;
+      Correct();
+      state_ = INITIALIZING;
+      disable = true;
+      break;
+
+    case INITIALIZING:
+      LOG(DEBUG, "Waiting for accurate initial position.\n");
+      disable = true;
+      // Update state_ to accurately represent the state of the zeroing
+      // estimators.
+      UpdateZeroingState();
+      if (state_ != INITIALIZING) {
+        // Set the goals to where we are now.
+        elevator_goal_ = elevator();
+        arm_goal_ = arm();
+      }
+      break;
+
+    case ZEROING_ELEVATOR:
+      LOG(DEBUG, "Zeroing elevator\n");
+      elevator_goal_velocity = elevator_zeroing_velocity();
+      elevator_goal_ += elevator_goal_velocity * dt;
+
+      // Update state_ to accurately represent the state of the zeroing
+      // estimators.
+      UpdateZeroingState();
+      if (left_elevator_estimator_.zeroed() &&
+          right_elevator_estimator_.zeroed()) {
+        SetElevatorOffset(left_elevator_estimator_.offset(),
+                          right_elevator_estimator_.offset());
+        LOG(DEBUG, "Zeroed the elevator!\n");
+      }
+      break;
+
+    case ZEROING_ARM:
+      LOG(DEBUG, "Zeroing the arm\n");
+      arm_goal_velocity = arm_zeroing_velocity();
+      arm_goal_ += arm_goal_velocity * dt;
+
+      // Update state_ to accurately represent the state of the zeroing
+      // estimators.
+      UpdateZeroingState();
+      if (left_arm_estimator_.zeroed() && right_arm_estimator_.zeroed()) {
+        SetArmOffset(left_arm_estimator_.offset(),
+                     right_arm_estimator_.offset());
+        LOG(DEBUG, "Zeroed the arm!\n");
+      }
+      break;
+
+    case RUNNING:
+      LOG(DEBUG, "Running!\n");
+      arm_goal_velocity = goal->angular_velocity;
+      elevator_goal_velocity = goal->velocity;
+
+      // Update state_ to accurately represent the state of the zeroing
+      // estimators.
+      UpdateZeroingState();
+      arm_goal_ = goal->angle;
+      elevator_goal_ = goal->height;
+
+      if (state_ != RUNNING && state_ != ESTOP) {
+        state_ = UNINITIALIZED;
+      }
+      break;
+
+    case ESTOP:
+      LOG(ERROR, "Estop\n");
+      disable = true;
+      break;
+  }
+
+  // Commence death if either left/right tracking error gets too big. This
+  // should run immediately after the SetArmOffset and SetElevatorOffset
+  // functions to double-check that the hardware is in a sane state.
+  if (::std::abs(left_arm() - right_arm()) >=
+          values.max_allowed_left_right_arm_difference ||
+      ::std::abs(left_elevator() - right_elevator()) >=
+          values.max_allowed_left_right_elevator_difference) {
+    LOG(ERROR, "The two sides went too far apart\n");
+
+    // Indicate an ESTOP condition and stop the motors.
+    state_ = ESTOP;
+    disable = true;
+  }
+
+  // Limit the goals so we can't exceed the hardware limits if we are RUNNING.
+  if (state_ == RUNNING) {
+    // Limit the arm goal to min/max allowable angles.
+    if (arm_goal_ >= values.fridge.arm.upper_limit) {
+      LOG(WARNING, "Arm goal above limit, %f > %f\n", arm_goal_,
+          values.fridge.arm.upper_limit);
+      arm_goal_ = values.fridge.arm.upper_limit;
+    }
+    if (arm_goal_ <= values.fridge.arm.lower_limit) {
+      LOG(WARNING, "Arm goal below limit, %f < %f\n", arm_goal_,
+          values.fridge.arm.lower_limit);
+      arm_goal_ = values.fridge.arm.lower_limit;
+    }
+
+    // Limit the elevator goal to min/max allowable heights.
+    if (elevator_goal_ >= values.fridge.elevator.upper_limit) {
+      LOG(WARNING, "Elevator goal above limit, %f > %f\n", elevator_goal_,
+          values.fridge.elevator.upper_limit);
+      elevator_goal_ = values.fridge.elevator.upper_limit;
+    }
+    if (elevator_goal_ <= values.fridge.elevator.lower_limit) {
+      LOG(WARNING, "Elevator goal below limit, %f < %f\n", elevator_goal_,
+          values.fridge.elevator.lower_limit);
+      elevator_goal_ = values.fridge.elevator.lower_limit;
+    }
+  }
+
+  // Check the lower level hardware limit as well.
+  if (state_ == RUNNING) {
+    if (left_arm() >= values.fridge.arm.upper_hard_limit ||
+        left_arm() <= values.fridge.arm.lower_hard_limit) {
+      LOG(ERROR, "Left arm at %f out of bounds [%f, %f], ESTOPing\n",
+          left_arm(), values.fridge.arm.lower_hard_limit,
+          values.fridge.arm.upper_hard_limit);
+      state_ = ESTOP;
+    }
+
+    if (right_arm() >= values.fridge.arm.upper_hard_limit ||
+        right_arm() <= values.fridge.arm.lower_hard_limit) {
+      LOG(ERROR, "Right arm at %f out of bounds [%f, %f], ESTOPing\n",
+          right_arm(), values.fridge.arm.lower_hard_limit,
+          values.fridge.arm.upper_hard_limit);
+      state_ = ESTOP;
+    }
+
+    if (left_elevator() >= values.fridge.elevator.upper_hard_limit ||
+        left_elevator() <= values.fridge.elevator.lower_hard_limit) {
+      LOG(ERROR, "Left elevator at %f out of bounds [%f, %f], ESTOPing\n",
+          left_elevator(), values.fridge.elevator.lower_hard_limit,
+          values.fridge.elevator.upper_hard_limit);
+      state_ = ESTOP;
+    }
+
+    if (right_elevator() >= values.fridge.elevator.upper_hard_limit ||
+        right_elevator() <= values.fridge.elevator.lower_hard_limit) {
+      LOG(ERROR, "Right elevator at %f out of bounds [%f, %f], ESTOPing\n",
+          right_elevator(), values.fridge.elevator.lower_hard_limit,
+          values.fridge.elevator.upper_hard_limit);
+      state_ = ESTOP;
+    }
+  }
+
+  // Set the goals.
+  arm_loop_->mutable_R() << arm_goal_, arm_goal_velocity, 0.0, 0.0;
+  elevator_loop_->mutable_R() << elevator_goal_, elevator_goal_velocity, 0.0,
+      0.0;
+
+  const double max_voltage = state_ == RUNNING ? 12.0 : kZeroingVoltage;
+  arm_loop_->set_max_voltage(max_voltage);
+  elevator_loop_->set_max_voltage(max_voltage);
+
+  if (state_ == ESTOP) {
+    disable = true;
+  }
+  arm_loop_->Update(disable);
+  elevator_loop_->Update(disable);
+
+  if (state_ == INITIALIZING || state_ == ZEROING_ELEVATOR ||
+      state_ == ZEROING_ARM) {
+    if (arm_loop_->U() != arm_loop_->U_uncapped()) {
+      Eigen::Matrix<double, 2, 1> deltaR =
+          arm_loop_->UnsaturateOutputGoalChange();
+
+      // Move the average arm goal by the amount observed.
+      LOG(WARNING, "Moving arm goal by %f to handle saturation\n",
+          deltaR(0, 0));
+      arm_goal_ += deltaR(0, 0);
+    }
+
+    if (elevator_loop_->U() != elevator_loop_->U_uncapped()) {
+      Eigen::Matrix<double, 2, 1> deltaR =
+          elevator_loop_->UnsaturateOutputGoalChange();
+
+      // Move the average elevator goal by the amount observed.
+      LOG(WARNING, "Moving elevator goal by %f to handle saturation\n",
+          deltaR(0, 0));
+      elevator_goal_ += deltaR(0, 0);
+    }
+  }
+
+  if (output) {
+    output->left_arm = arm_loop_->U(0, 0);
+    output->right_arm = arm_loop_->U(1, 0);
+    output->left_elevator = elevator_loop_->U(0, 0);
+    output->right_elevator = elevator_loop_->U(1, 0);
+    output->grabbers = goal->grabbers;
+  }
+
+  // TODO(austin): Populate these fully.
+  status->zeroed = false;
+  status->done = false;
+  status->angle = arm_loop_->X_hat(0, 0);
+  status->height = elevator_loop_->X_hat(0, 0);
+  status->grabbers = goal->grabbers;
+  status->estopped = (state_ == ESTOP);
+  last_state_ = state_;
 }
 
 }  // namespace control_loops
diff --git a/frc971/control_loops/fridge/fridge.gyp b/frc971/control_loops/fridge/fridge.gyp
index 4a39901..a0016e8 100644
--- a/frc971/control_loops/fridge/fridge.gyp
+++ b/frc971/control_loops/fridge/fridge.gyp
@@ -10,11 +10,12 @@
       'dependencies': [
         '<(AOS)/common/controls/controls.gyp:control_loop_queues',
         '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+        '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
       ],
       'export_dependent_settings': [
         '<(AOS)/common/controls/controls.gyp:control_loop_queues',
         '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
-
+        '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
       ],
       'includes': ['../../../aos/build/queues.gypi'],
     },
diff --git a/frc971/control_loops/fridge/fridge.h b/frc971/control_loops/fridge/fridge.h
index 3d0fa6c..5ee6ed0 100644
--- a/frc971/control_loops/fridge/fridge.h
+++ b/frc971/control_loops/fridge/fridge.h
@@ -8,10 +8,30 @@
 #include "frc971/control_loops/fridge/fridge.q.h"
 #include "frc971/control_loops/fridge/arm_motor_plant.h"
 #include "frc971/control_loops/fridge/elevator_motor_plant.h"
+#include "frc971/zeroing/zeroing.h"
 
 namespace frc971 {
 namespace control_loops {
 
+class CappedStateFeedbackLoop : public StateFeedbackLoop<4, 2, 2> {
+ public:
+  CappedStateFeedbackLoop(StateFeedbackLoop<4, 2, 2> &&loop)
+      : StateFeedbackLoop<4, 2, 2>(::std::move(loop)), max_voltage_(12.0) {}
+
+  void set_max_voltage(double max_voltage) {
+    max_voltage_ = ::std::max(-12.0, ::std::min(12.0, max_voltage));
+  }
+
+  void CapU() override;
+
+  // Returns the amount to change the position goals (average and difference) in
+  // order to no longer saturate the controller.
+  Eigen::Matrix<double, 2, 1> UnsaturateOutputGoalChange();
+
+ private:
+  double max_voltage_;
+};
+
 class Fridge
     : public aos::controls::ControlLoop<control_loops::FridgeQueue> {
  public:
@@ -28,16 +48,92 @@
   //static constexpr double dt;
 
  protected:
-  virtual void RunIteration(
-      const control_loops::FridgeQueue::Goal *goal,
-      const control_loops::FridgeQueue::Position *position,
-      control_loops::FridgeQueue::Output *output,
-      control_loops::FridgeQueue::Status *status);
+  void RunIteration(const control_loops::FridgeQueue::Goal *goal,
+                    const control_loops::FridgeQueue::Position *position,
+                    control_loops::FridgeQueue::Output *output,
+                    control_loops::FridgeQueue::Status *status) override;
 
  private:
+  // Sets state_ to the correct state given the current state of the zeroing
+  // estimators.
+  void UpdateZeroingState();
+
+  void SetElevatorOffset(double left_offset, double right_offset);
+  void SetArmOffset(double left_offset, double right_offset);
+
+  // Getters for the current elevator positions.
+  double left_elevator();
+  double right_elevator();
+  double elevator();
+
+  // Getters for the current arm positions.
+  double left_arm();
+  double right_arm();
+  double arm();
+
+  // Our best guess at the current position of the elevator.
+  double estimated_left_elevator();
+  double estimated_right_elevator();
+  double estimated_elevator();
+
+  // Our best guess at the current position of the arm.
+  double estimated_left_arm();
+  double estimated_right_arm();
+  double estimated_arm();
+
+  // Returns the current zeroing velocity for either subsystem.
+  // If the subsystem is too far away from the center, these will switch
+  // directions.
+  double elevator_zeroing_velocity();
+  double arm_zeroing_velocity();
+
+  // Corrects the Observer with the current position.
+  void Correct();
+
+  enum State {
+    // Waiting to receive data before doing anything.
+    UNINITIALIZED = 0,
+    // Estimating the starting location.
+    INITIALIZING = 1,
+    // Moving the elevator to find an index pulse.
+    ZEROING_ELEVATOR = 2,
+    // Moving the arm to find an index pulse.
+    ZEROING_ARM = 3,
+    // All good!
+    RUNNING = 4,
+    // Internal error caused the fridge to abort.
+    ESTOP = 5,
+  };
+
   // The state feedback control loop or loops to talk to.
-  ::std::unique_ptr<StateFeedbackLoop<4, 2, 2>> arm_loop_;
-  ::std::unique_ptr<StateFeedbackLoop<4, 2, 2>> elev_loop_;
+  ::std::unique_ptr<CappedStateFeedbackLoop> arm_loop_;
+  ::std::unique_ptr<CappedStateFeedbackLoop> elevator_loop_;
+
+  zeroing::ZeroingEstimator left_arm_estimator_;
+  zeroing::ZeroingEstimator right_arm_estimator_;
+  zeroing::ZeroingEstimator left_elevator_estimator_;
+  zeroing::ZeroingEstimator right_elevator_estimator_;
+
+  // Offsets from the encoder position to the absolute position.  Add these to
+  // the encoder position to get the absolute position.
+  double left_elevator_offset_ = 0.0;
+  double right_elevator_offset_ = 0.0;
+  double left_arm_offset_ = 0.0;
+  double right_arm_offset_ = 0.0;
+
+  // Current velocity to move at while zeroing.
+  double elevator_zeroing_velocity_ = 0.0;
+  double arm_zeroing_velocity_ = 0.0;
+
+  // The goals for the elevator and arm.
+  double elevator_goal_ = 0.0;
+  double arm_goal_ = 0.0;
+
+  State state_ = UNINITIALIZED;
+  State last_state_ = UNINITIALIZED;
+
+  control_loops::FridgeQueue::Position current_position_;
+  static constexpr double dt = 0.005;
 };
 
 }  // namespace control_loops
diff --git a/frc971/control_loops/fridge/fridge.q b/frc971/control_loops/fridge/fridge.q
index c85efa5..07a0646 100644
--- a/frc971/control_loops/fridge/fridge.q
+++ b/frc971/control_loops/fridge/fridge.q
@@ -29,6 +29,13 @@
     // Height of the elevator.
     double height;
 
+    // Angular velocity of the arm.
+    double angular_velocity;
+    // Linear velocity of the elevator.
+    double velocity;
+
+    // TODO(austin): Do I need acceleration here too?
+
     GrabberPistons grabbers;
   };
 
@@ -50,6 +57,9 @@
     double height;
     // state of the grabber pistons
     GrabberPistons grabbers;
+
+    // TODO(austin): Internal state.
+    bool estopped;
   };
 
   message Output {
diff --git a/frc971/control_loops/fridge/fridge_lib_test.cc b/frc971/control_loops/fridge/fridge_lib_test.cc
index 03f1d1b..2bc3d02 100644
--- a/frc971/control_loops/fridge/fridge_lib_test.cc
+++ b/frc971/control_loops/fridge/fridge_lib_test.cc
@@ -22,53 +22,59 @@
 // position.
 class FridgeSimulation {
  public:
+  static constexpr double kNoiseScalar = 3.0;
   // Constructs a simulation.
   FridgeSimulation()
       : arm_plant_(new StateFeedbackPlant<4, 2, 2>(MakeArmPlant())),
         elev_plant_(new StateFeedbackPlant<4, 2, 2>(MakeElevatorPlant())),
         left_arm_pot_encoder_(
-            constants::GetValues().fridge.arm.lower_limit,
-            constants::GetValues().left_arm_zeroing_constants.index_difference,
-            constants::GetValues().left_arm_zeroing_constants.index_difference
-                / 3.0),
+            constants::GetValues().left_arm_zeroing_constants.index_difference),
         right_arm_pot_encoder_(
-            constants::GetValues().fridge.arm.lower_limit,
-            constants::GetValues().right_arm_zeroing_constants.index_difference,
-            constants::GetValues().right_arm_zeroing_constants.index_difference
-                / 3.0),
+            constants::GetValues()
+                .right_arm_zeroing_constants.index_difference),
         left_elev_pot_encoder_(
-            constants::GetValues().fridge.elevator.lower_limit,
             constants::GetValues()
-                .left_elevator_zeroing_constants.index_difference,
-            constants::GetValues()
-                .left_elevator_zeroing_constants.index_difference / 3.0),
+                .left_elevator_zeroing_constants.index_difference),
         right_elev_pot_encoder_(
-            constants::GetValues().fridge.elevator.lower_limit,
             constants::GetValues()
-                .right_elevator_zeroing_constants.index_difference,
-            constants::GetValues()
-                .right_elevator_zeroing_constants.index_difference / 3.0),
+                .right_elevator_zeroing_constants.index_difference),
         fridge_queue_(".frc971.control_loops.fridge_queue", 0xe4e05855,
                       ".frc971.control_loops.fridge_queue.goal",
                       ".frc971.control_loops.fridge_queue.position",
                       ".frc971.control_loops.fridge_queue.output",
-                      ".frc971.control_loops.fridge_queue.status") {}
-
-  // Do specific initialization for all the sensors.
-  void SetLeftElevatorSensors(double start_pos, double pot_noise_stddev) {
-    left_elev_pot_encoder_.OverrideParams(start_pos, pot_noise_stddev);
+                      ".frc971.control_loops.fridge_queue.status") {
+    // Initialize the elevator.
+    SetElevatorSensors(
+        constants::GetValues().fridge.elevator.lower_limit,
+        constants::GetValues().fridge.elevator.lower_limit,
+        kNoiseScalar *
+            constants::GetValues()
+                .right_elevator_zeroing_constants.index_difference);
+    // Initialize the arm.
+    SetArmSensors(0.0, 0.0,
+                  kNoiseScalar *
+                      constants::GetValues()
+                          .right_arm_zeroing_constants.index_difference);
   }
 
-  void SetRightElevatorSensors(double start_pos, double pot_noise_stddev) {
-    right_elev_pot_encoder_.OverrideParams(start_pos, pot_noise_stddev);
+  void SetElevatorSensors(double left_start_pos, double right_start_pos,
+                          double pot_noise_stddev) {
+    // Update the internal state of the elevator plant.
+    elev_plant_->mutable_X(0, 0) = (left_start_pos + right_start_pos) / 2.0;
+    elev_plant_->mutable_X(2, 0) = (left_start_pos - right_start_pos) / 2.0;
+
+    right_elev_pot_encoder_.Initialize(right_start_pos, pot_noise_stddev);
+    left_elev_pot_encoder_.Initialize(left_start_pos, pot_noise_stddev);
   }
 
-  void SetLeftArmSensors(double start_pos, double pot_noise_stddev) {
-    left_arm_pot_encoder_.OverrideParams(start_pos, pot_noise_stddev);
-  }
+  void SetArmSensors(double left_start_pos, double right_start_pos,
+                     double pot_noise_stddev) {
+    // Update the internal state of the arm plant.
+    arm_plant_->mutable_X(0, 0) = (left_start_pos + right_start_pos) / 2.0;
+    arm_plant_->mutable_X(2, 0) = (left_start_pos - right_start_pos) / 2.0;
 
-  void SetRightArmSensors(double start_pos, double pot_noise_stddev) {
-    right_arm_pot_encoder_.OverrideParams(start_pos, pot_noise_stddev);
+    left_arm_pot_encoder_.Initialize(left_start_pos, pot_noise_stddev);
+    right_arm_pot_encoder_.Initialize(right_start_pos, pot_noise_stddev);
   }
 
   // Sends a queue message with the position.
@@ -99,8 +105,6 @@
     arm_plant_->Update();
     elev_plant_->Update();
 
-    // TODO (phil) Make sure that the correct values are retrieved from the
-    // plant.
     const double left_arm_angle = arm_plant_->Y(0, 0);
     const double right_arm_angle = arm_plant_->Y(1, 0);
     const double left_elev_height = elev_plant_->Y(0, 0);
@@ -158,9 +162,9 @@
   void VerifyNearGoal() {
     fridge_queue_.goal.FetchLatest();
     fridge_queue_.status.FetchLatest();
-    // TODO(danielp): I think those tens need to change...
-    EXPECT_NEAR(fridge_queue_.goal->angle, fridge_queue_.status->angle, 10.0);
-    EXPECT_NEAR(fridge_queue_.goal->height, fridge_queue_.status->height, 10.0);
+    EXPECT_NEAR(fridge_queue_.goal->angle, fridge_queue_.status->angle, 0.001);
+    EXPECT_NEAR(fridge_queue_.goal->height, fridge_queue_.status->height,
+                0.001);
   }
 
   // Runs one iteration of the whole simulation and checks that separation
@@ -206,7 +210,7 @@
       .Send());
 
   // Run a few iterations.
-  RunForTime(Time::InMS(50));
+  RunForTime(Time::InMS(5000));
 
   VerifyNearGoal();
 }
@@ -218,7 +222,7 @@
   const double soft_limit = values.fridge.elevator.lower_limit;
   ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
       .angle(M_PI / 4.0)
-      .height(soft_limit + 0.5)
+      .height(soft_limit + 0.2)
       .Send());
 
   // Give it a lot of time to get there.
@@ -234,8 +238,8 @@
   // We're going to send the elevator to zero, which should be significantly too
   // low.
   ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
-      .angle(M_PI / 2.0)
-      .height(0.0)
+      .angle(M_PI)
+      .height(-5.0)
       .Send());
 
   RunForTime(Time::InMS(4000));
@@ -243,14 +247,15 @@
   // Check that we are near our soft limit.
   fridge_queue_.status.FetchLatest();
   const auto values = constants::GetValues();
-  EXPECT_NEAR(values.fridge.elevator.lower_limit,
-              fridge_queue_.status->height,
-              0.05);
+  EXPECT_NEAR(values.fridge.elevator.lower_limit, fridge_queue_.status->height,
+              0.001);
+  EXPECT_NEAR(values.fridge.arm.upper_limit, fridge_queue_.status->angle,
+              0.001);
 
   // Put the arm down to get it out of the way.
   // We're going to give the elevator some ridiculously high goal.
   ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
-      .angle(-M_PI / 2.0)
+      .angle(-M_PI)
       .height(50.0)
       .Send());
 
@@ -258,11 +263,45 @@
 
   // Check that we are near our soft limit.
   fridge_queue_.status.FetchLatest();
-  EXPECT_NEAR(values.fridge.elevator.upper_limit,
-              fridge_queue_.status->height,
-              0.05);
+  EXPECT_NEAR(values.fridge.elevator.upper_limit, fridge_queue_.status->height,
+              0.001);
+  EXPECT_NEAR(values.fridge.arm.lower_limit, fridge_queue_.status->angle,
+              0.001);
 }
 
+// Tests that the loop zeroes when run for a while.
+TEST_F(FridgeTest, ZeroTest) {
+  fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.5).Send();
+  while (::aos::time::Time::Now() < ::aos::time::Time::InMS(4000)) {
+    SendMessages(true);
+    fridge_plant_.SendPositionMessage();
+    fridge_.Iterate();
+    fridge_plant_.Simulate();
+    TickTime();
+  }
+
+  VerifyNearGoal();
+}
+
+// TODO(austin): Update unit test to abort when limits are violated.
+// TODO(austin): Test that voltages are within 12 volt ranges.
+
+// TODO(austin): Test starting with nonzero encoder values.
+// TODO(austin): Test that we ignore DMA counts during the uninitialized period
+// TODO(austin): Test starting with nonzero DMA counts.
+
+// TODO(austin): Test starting at all 4 hard limits.
+
+// TODO(austin): Check that we don't move the zeroing goals if disabled.
+// TODO(austin): Test that windup works correctly for both the arm and elevator.
+// TODO(austin): Check that we e-stop if the joints start too far apart.
+
+// Nice to have below here.
+
+// TODO(austin): Check that we e-stop if encoder index pulse is not n revolutions away from last one. (got extra counts from noise, etc).
+// TODO(austin): Check that we e-stop if pot disagrees too much with encoder after we are zeroed.
+
+
 }  // namespace testing
 }  // namespace control_loops
 }  // namespace frc971