Moved 2014 drivetrain code into y2014 namespace.

Change-Id: I74a1922f846a288725df2aea01c5c9e1b99e07b3
diff --git a/y2014/control_loops/drivetrain/drivetrain.cc b/y2014/control_loops/drivetrain/drivetrain.cc
index 0fa1de9..00686f0 100644
--- a/y2014/control_loops/drivetrain/drivetrain.cc
+++ b/y2014/control_loops/drivetrain/drivetrain.cc
@@ -24,13 +24,15 @@
 
 using frc971::sensors::gyro_reading;
 
-namespace frc971 {
+namespace y2014 {
 namespace control_loops {
+namespace drivetrain {
 
-void DrivetrainLoop::RunIteration(const DrivetrainQueue::Goal *goal,
-                                  const DrivetrainQueue::Position *position,
-                                  DrivetrainQueue::Output *output,
-                                  DrivetrainQueue::Status *status) {
+void DrivetrainLoop::RunIteration(
+    const ::frc971::control_loops::DrivetrainQueue::Goal *goal,
+    const ::frc971::control_loops::DrivetrainQueue::Position *position,
+    ::frc971::control_loops::DrivetrainQueue::Output *output,
+    ::frc971::control_loops::DrivetrainQueue::Status *status) {
   bool bad_pos = false;
   if (position == nullptr) {
     LOG_INTERVAL(no_position_);
@@ -110,5 +112,6 @@
   }
 }
 
+}  // namespace drivetrain
 }  // namespace control_loops
-}  // namespace frc971
+}  // namespace y2014
diff --git a/y2014/control_loops/drivetrain/drivetrain.h b/y2014/control_loops/drivetrain/drivetrain.h
index c5b731d..a77ab15 100644
--- a/y2014/control_loops/drivetrain/drivetrain.h
+++ b/y2014/control_loops/drivetrain/drivetrain.h
@@ -11,16 +11,18 @@
 #include "y2014/control_loops/drivetrain/ssdrivetrain.h"
 #include "aos/common/util/log_interval.h"
 
-namespace frc971 {
+namespace y2014 {
 namespace control_loops {
+namespace drivetrain {
 
 class DrivetrainLoop
-    : public aos::controls::ControlLoop<control_loops::DrivetrainQueue> {
+    : public aos::controls::ControlLoop<::frc971::control_loops::DrivetrainQueue> {
  public:
   // Constructs a control loop which can take a Drivetrain or defaults to the
   // drivetrain at frc971::control_loops::drivetrain
-  explicit DrivetrainLoop(control_loops::DrivetrainQueue *my_drivetrain =
-                              &control_loops::drivetrain_queue)
+  explicit DrivetrainLoop(
+      ::frc971::control_loops::DrivetrainQueue *my_drivetrain =
+          &::frc971::control_loops::drivetrain_queue)
       : aos::controls::ControlLoop<control_loops::DrivetrainQueue>(
             my_drivetrain) {
     ::aos::controls::HPolytope<0>::Init();
@@ -29,10 +31,10 @@
  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);
+      const ::frc971::control_loops::DrivetrainQueue::Goal *goal,
+      const ::frc971::control_loops::DrivetrainQueue::Position *position,
+      ::frc971::control_loops::DrivetrainQueue::Output *output,
+      ::frc971::control_loops::DrivetrainQueue::Status *status);
 
   typedef ::aos::util::SimpleLogInterval SimpleLogInterval;
   SimpleLogInterval no_position_ = SimpleLogInterval(
@@ -42,7 +44,8 @@
   DrivetrainMotorsSS dt_closedloop_;
 };
 
+}  // namespace drivetrain
 }  // namespace control_loops
-}  // namespace frc971
+}  // namespace y2014
 
 #endif  // Y2014_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/y2014/control_loops/drivetrain/drivetrain_lib_test.cc b/y2014/control_loops/drivetrain/drivetrain_lib_test.cc
index e2db9de..f455b57 100644
--- a/y2014/control_loops/drivetrain/drivetrain_lib_test.cc
+++ b/y2014/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -16,8 +16,9 @@
 #include "frc971/queues/gyro.q.h"
 
 
-namespace frc971 {
+namespace y2014 {
 namespace control_loops {
+namespace drivetrain {
 namespace testing {
 
 using ::y2014::control_loops::drivetrain::MakeDrivetrainPlant;
@@ -78,8 +79,8 @@
     const double left_encoder = GetLeftPosition();
     const double right_encoder = GetRightPosition();
 
-    ::aos::ScopedMessagePtr<control_loops::DrivetrainQueue::Position> position =
-        my_drivetrain_queue_.position.MakeMessage();
+    ::aos::ScopedMessagePtr<::frc971::control_loops::DrivetrainQueue::Position>
+        position = my_drivetrain_queue_.position.MakeMessage();
     position->left_encoder = left_encoder;
     position->right_encoder = right_encoder;
     position.Send();
@@ -97,7 +98,7 @@
 
   ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> drivetrain_plant_;
  private:
-  DrivetrainQueue my_drivetrain_queue_;
+  ::frc971::control_loops::DrivetrainQueue my_drivetrain_queue_;
   double last_left_position_;
   double last_right_position_;
 };
@@ -107,7 +108,7 @@
   // 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_;
+  ::frc971::control_loops::DrivetrainQueue my_drivetrain_queue_;
 
   // Create a loop and simulation plant.
   DrivetrainLoop drivetrain_motor_;
@@ -295,5 +296,6 @@
 }
 
 }  // namespace testing
+}  // namespace drivetrain
 }  // namespace control_loops
-}  // namespace frc971
+}  // namespace y2014
diff --git a/y2014/control_loops/drivetrain/drivetrain_main.cc b/y2014/control_loops/drivetrain/drivetrain_main.cc
index 9a2ebe1..cc71c69 100644
--- a/y2014/control_loops/drivetrain/drivetrain_main.cc
+++ b/y2014/control_loops/drivetrain/drivetrain_main.cc
@@ -4,7 +4,7 @@
 
 int main() {
   ::aos::Init();
-  frc971::control_loops::DrivetrainLoop drivetrain;
+  ::y2014::control_loops::drivetrain::DrivetrainLoop drivetrain;
   drivetrain.Run();
   ::aos::Cleanup();
   return 0;
diff --git a/y2014/control_loops/drivetrain/polydrivetrain.cc b/y2014/control_loops/drivetrain/polydrivetrain.cc
index c97be6f..795ad04 100644
--- a/y2014/control_loops/drivetrain/polydrivetrain.cc
+++ b/y2014/control_loops/drivetrain/polydrivetrain.cc
@@ -15,10 +15,13 @@
 
 #define HAVE_SHIFTERS 1
 
-namespace frc971 {
+namespace y2014 {
 namespace control_loops {
+namespace drivetrain {
 
-using ::y2014::control_loops::drivetrain::kDt;
+using ::frc971::control_loops::GearLogging;
+using ::frc971::control_loops::CIMLogging;
+using ::frc971::control_loops::CoerceGoal;
 
 PolyDrivetrain::PolyDrivetrain()
     : U_Poly_((Eigen::Matrix<double, 4, 2>() << /*[[*/ 1, 0 /*]*/,
@@ -154,7 +157,8 @@
     }
   }
 }
-void PolyDrivetrain::SetPosition(const DrivetrainQueue::Position *position) {
+void PolyDrivetrain::SetPosition(
+    const ::frc971::control_loops::DrivetrainQueue::Position *position) {
   const auto &values = constants::GetValues();
   if (position == NULL) {
     ++stale_count_;
@@ -397,7 +401,8 @@
   }
 }
 
-void PolyDrivetrain::SendMotors(DrivetrainQueue::Output *output) {
+void PolyDrivetrain::SendMotors(
+    ::frc971::control_loops::DrivetrainQueue::Output *output) {
   if (output != NULL) {
     output->left_voltage = loop_->U(0, 0);
     output->right_voltage = loop_->U(1, 0);
@@ -415,5 +420,6 @@
 constexpr double PolyDrivetrain::Kv;
 constexpr double PolyDrivetrain::Kt;
 
+}  // namespace drivetrain
 }  // namespace control_loops
-}  // namespace frc971
+}  // namespace y2014
diff --git a/y2014/control_loops/drivetrain/polydrivetrain.h b/y2014/control_loops/drivetrain/polydrivetrain.h
index 82ebd24..1f9a27b 100644
--- a/y2014/control_loops/drivetrain/polydrivetrain.h
+++ b/y2014/control_loops/drivetrain/polydrivetrain.h
@@ -8,35 +8,34 @@
 #include "frc971/control_loops/state_feedback_loop.h"
 #include "y2014/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
 
-namespace frc971 {
+namespace y2014 {
 namespace control_loops {
+namespace drivetrain {
 
 class PolyDrivetrain {
  public:
   enum Gear { HIGH, LOW, SHIFTING_UP, SHIFTING_DOWN };
   // Stall Torque in N m
-  static constexpr double kStallTorque =
-      ::y2014::control_loops::drivetrain::kStallTorque;
+  static constexpr double kStallTorque = kStallTorque;
   // Stall Current in Amps
-  static constexpr double kStallCurrent = ::y2014::control_loops::drivetrain::kStallCurrent;
+  static constexpr double kStallCurrent = kStallCurrent;
   // Free Speed in RPM. Used number from last year.
-  static constexpr double kFreeSpeed =
-      ::y2014::control_loops::drivetrain::kFreeSpeedRPM;
+  static constexpr double kFreeSpeed = kFreeSpeedRPM;
   // Free Current in Amps
-  static constexpr double kFreeCurrent =
-      ::y2014::control_loops::drivetrain::kFreeCurrent;
-  static constexpr double kWheelRadius =
-      ::y2014::control_loops::drivetrain::kWheelRadius;
-  // Resistance of the motor, divided by the number of motors.
-  static constexpr double kR = ::y2014::control_loops::drivetrain::kR;
+  static constexpr double kFreeCurrent = kFreeCurrent;
+  static constexpr double kWheelRadius = kWheelRadius;
+  // Resistance of the motor, divided by the number of motors per side.
+  static constexpr double kR = kR;
   // Motor velocity constant
-  static constexpr double Kv = ::y2014::control_loops::drivetrain::kV;
+  static constexpr double Kv = kV;
 
   // Torque constant
-  static constexpr double Kt = ::y2014::control_loops::drivetrain::kT;
+  static constexpr double Kt = kT;
 
   PolyDrivetrain();
 
+  int controller_index() const { return loop_->controller_index(); }
+
   static bool IsInGear(Gear gear) { return gear == LOW || gear == HIGH; }
 
   static double MotorSpeed(const constants::ShifterHallEffect &hall_effect,
@@ -47,7 +46,8 @@
 
   void SetGoal(double wheel, double throttle, bool quickturn, bool highgear);
 
-  void SetPosition(const DrivetrainQueue::Position *position);
+  void SetPosition(
+      const ::frc971::control_loops::DrivetrainQueue::Position *position);
 
   double FilterVelocity(double throttle);
 
@@ -55,7 +55,7 @@
 
   void Update();
 
-  void SendMotors(DrivetrainQueue::Output *output);
+  void SendMotors(::frc971::control_loops::DrivetrainQueue::Output *output);
 
  private:
   const ::aos::controls::HPolytope<2> U_Poly_;
@@ -70,12 +70,13 @@
   double position_time_delta_;
   Gear left_gear_;
   Gear right_gear_;
-  DrivetrainQueue::Position last_position_;
-  DrivetrainQueue::Position position_;
+  ::frc971::control_loops::DrivetrainQueue::Position last_position_;
+  ::frc971::control_loops::DrivetrainQueue::Position position_;
   int counter_;
 };
 
+}  // namespace drivetrain
 }  // namespace control_loops
-}  // namespace frc971
+}  // namespace y2014
 
 #endif  // Y2014_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_H_
diff --git a/y2014/control_loops/drivetrain/ssdrivetrain.cc b/y2014/control_loops/drivetrain/ssdrivetrain.cc
index 2551ddb..3c2a962 100644
--- a/y2014/control_loops/drivetrain/ssdrivetrain.cc
+++ b/y2014/control_loops/drivetrain/ssdrivetrain.cc
@@ -9,8 +9,11 @@
 #include "y2014/constants.h"
 #include "y2014/control_loops/drivetrain/drivetrain.q.h"
 
-namespace frc971 {
+namespace y2014 {
 namespace control_loops {
+namespace drivetrain {
+
+using ::frc971::control_loops::DoCoerceGoal;
 
 DrivetrainMotorsSS::LimitedDrivetrainLoop::LimitedDrivetrainLoop(
     StateFeedbackLoop<4, 2, 2> &&loop)
@@ -168,7 +171,8 @@
   return (loop_->X_hat(1, 0) + loop_->X_hat(3, 0)) / 2;
 }
 
-void DrivetrainMotorsSS::SendMotors(DrivetrainQueue::Output *output) const {
+void DrivetrainMotorsSS::SendMotors(
+    ::frc971::control_loops::DrivetrainQueue::Output *output) const {
   if (output) {
     output->left_voltage = loop_->U(0, 0);
     output->right_voltage = loop_->U(1, 0);
@@ -177,5 +181,6 @@
   }
 }
 
+}  // namespace drivetrain
 }  // namespace control_loops
-}  // namespace frc971
+}  // namespace y2014
diff --git a/y2014/control_loops/drivetrain/ssdrivetrain.h b/y2014/control_loops/drivetrain/ssdrivetrain.h
index 982c873..f79a993 100644
--- a/y2014/control_loops/drivetrain/ssdrivetrain.h
+++ b/y2014/control_loops/drivetrain/ssdrivetrain.h
@@ -10,8 +10,9 @@
 #include "y2014/constants.h"
 #include "y2014/control_loops/drivetrain/drivetrain.q.h"
 
-namespace frc971 {
+namespace y2014 {
 namespace control_loops {
+namespace drivetrain {
 
 class DrivetrainMotorsSS {
  public:
@@ -58,7 +59,8 @@
     return loop_->output_was_capped();
   }
 
-  void SendMotors(DrivetrainQueue::Output *output) const;
+  void SendMotors(
+      ::frc971::control_loops::DrivetrainQueue::Output *output) const;
 
   const LimitedDrivetrainLoop &loop() const { return *loop_; }
 
@@ -73,7 +75,8 @@
   double raw_right_;
 };
 
+}  // namespace drivetrain
 }  // namespace control_loops
-}  // namespace frc971
+}  // namespace y2014
 
 #endif  // Y2014_CONTROL_LOOPS_DRIVETRAIN_SSDRIVETRAIN_H_