Tuned drive

Change-Id: I6e174df4a55195bde9605b49b8ed42cb4b62eb99
diff --git a/y2016_bot3/control_loops/drivetrain/drivetrain_base.cc b/y2016_bot3/control_loops/drivetrain/drivetrain_base.cc
index 403c215..5997342 100644
--- a/y2016_bot3/control_loops/drivetrain/drivetrain_base.cc
+++ b/y2016_bot3/control_loops/drivetrain/drivetrain_base.cc
@@ -37,8 +37,8 @@
       kThreeStateDriveShifter,
       true,
       0.0,
-      0.25,
-      0.50};
+      0.4,
+      1.0};
 
   return kDrivetrainConfig;
 };
diff --git a/y2016_bot3/control_loops/intake/intake.h b/y2016_bot3/control_loops/intake/intake.h
index 57d8f84..cfc204f 100644
--- a/y2016_bot3/control_loops/intake/intake.h
+++ b/y2016_bot3/control_loops/intake/intake.h
@@ -31,7 +31,7 @@
 static constexpr ::frc971::constants::Range kIntakeRange{// Lower hard stop
                                                          -0.4,
                                                          // Upper hard stop
-                                                         2.80,
+                                                         2.90,
                                                          // Lower soft stop
                                                          -0.28,
                                                          // Uppper soft stop
diff --git a/y2016_bot3/control_loops/python/drivetrain.py b/y2016_bot3/control_loops/python/drivetrain.py
index 5a67416..5de7dbc 100755
--- a/y2016_bot3/control_loops/python/drivetrain.py
+++ b/y2016_bot3/control_loops/python/drivetrain.py
@@ -71,9 +71,9 @@
     # Free Current in Amps
     self.free_current = 4.7 * self.num_motors
     # Moment of inertia of the drivetrain in kg m^2
-    self.J = 2.0
+    self.J = 8.0
     # Mass of the robot, in kg.
-    self.m = 68
+    self.m = 45
     # Radius of the robot, in meters (requires tuning by hand)
     self.rb = 0.601 / 2.0
     # Radius of the wheels, in meters.
diff --git a/y2016_bot3/control_loops/python/polydrivetrain.py b/y2016_bot3/control_loops/python/polydrivetrain.py
index ac85bb6..07f9ff9 100755
--- a/y2016_bot3/control_loops/python/polydrivetrain.py
+++ b/y2016_bot3/control_loops/python/polydrivetrain.py
@@ -128,7 +128,7 @@
     # FF * X = U (steady state)
     self.FF = self.B.I * (numpy.eye(2) - self.A)
 
-    self.PlaceControllerPoles([0.67, 0.67])
+    self.PlaceControllerPoles([0.85, 0.85])
     self.PlaceObserverPoles([0.02, 0.02])
 
     self.G_high = self._drivetrain.G_high
diff --git a/y2016_bot3/wpilib/wpilib_interface.cc b/y2016_bot3/wpilib/wpilib_interface.cc
index b870e00..3d7d8ce 100644
--- a/y2016_bot3/wpilib/wpilib_interface.cc
+++ b/y2016_bot3/wpilib/wpilib_interface.cc
@@ -84,13 +84,13 @@
 // with proper units.
 
 double drivetrain_translate(int32_t in) {
-  return -static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*4x*/) *
+  return -static_cast<double>(in) / (512.0 /*cpr*/ * 4.0 /*4x*/) *
          ::y2016_bot3::constants::kDrivetrainEncoderRatio *
          control_loops::drivetrain::kWheelRadius * 2.0 * M_PI;
 }
 
 double drivetrain_velocity_translate(double in) {
-  return (1.0 / in) / 256.0 /*cpr*/ *
+  return (1.0 / in) / 512.0 /*cpr*/ *
          ::y2016_bot3::constants::kDrivetrainEncoderRatio *
          control_loops::drivetrain::kWheelRadius * 2.0 * M_PI;
 }